Behavior-based Arm Control for an Autonomous Bucket Excavator

Size: px
Start display at page:

Download "Behavior-based Arm Control for an Autonomous Bucket Excavator"

Transcription

1 Behavior-based Arm Control for an Autonomous Bucket Excavator Sergey Pluzhnikov, Daniel Schmidt, Jochen Hirth, and Karsten Berns Robotics Research Lab, Dept. of Computer Science, University of Kaiserslautern, Gottlieb-Daimler-Straße, Kaiserslautern Abstract. The paper at hand presents a novel, biologically inspired approach to numerically solve the inverse kinematics problem of arbitrary kinematic chains without instability problems and with low computational complexity. The kinematic chain of the robot arm is transferred to a network of behavior-based joint controllers, which try to deliver the best control value to solve the global problem. By means of controlling a wheeled excavator robot arm, the capabilities of this approach to work for redundant structures with the desired precision are shown. 1 Introduction Autonomous and assistive systems become more and more important for both, industrial products as well as academical research. These systems can operate in areas polluted by toxic waste or radiation without any risk for humans. One of the projects in this field involves the development of a fully autonomous bucket excavator. A key functionality of such a system is autonomous landscaping according to a specified target state. This paper presents the scientific system idea in comparison to classical inverse kinematics solvers and proves its capability to control complex machines by implementing it to control the arm of an autonomous 18 t bucket excavator (see figure 1). Using this implementation several experiments to determine the quality have been realized. A crucial aspect for the realization of this task as well as an interesting functionality to support the human operator is to control the movement of the bucket by simply specifying its target position and orientation in 3D-space. To solve this problem, traditional approaches like inverse kinematics can be adopted from industrial robotics. Unfortunately these approaches require time consuming processing (typically complex numeric solvers) and detailed knowledge of the environment in order to calculate the trajectories for every single joint. Since the perception of the environment in outdoor scenarios is a very difficult task as the situation dynamically changes and because of disturbances that will appear on the real construction field, more robust and flexible approaches to control the excavator s bucket are required. Looking to the area of autonomous robotics lead to so called biologically motivated solutions. For recent years behavior-based control approaches have been developed and investigated for the realization of flexible and robust control system. Based on these considerations a behavior-based system to control the TCP (Tool Center Point) of a kinematic chain has been developed. The first idea of such a system has been implemented for the control of the arms and the body of the robot Work Partner [1]. This

2 Fig. 1. The autonomous bucket excavator fulfilling an automated dumping task. idea has been refined to control the focused point of the humanoid robot ROMAN [2]. Based on these ideas, a general control system capable of modelling various kinematic chains has been developed. The most widely used methods in this field are analytical and numerical solvers. A good overview of these methods is given in [3]. Generally speaking, both types of methods have serious drawbacks. They are based on division of joint structure of an object into kinematic units for which analytical solutions can be derived and partition an inverse kinematics problem into subproblems for each of these units. Analytical methods are generally more efficient and reliable than their numerical counterparts, but require special kinematic structures. Such methods in most cases are not applicable to redundant robots. Numerical solvers take a system of equations describing kinematic constraints and search for a solution with various approximation methods. Usually such methods require much computational power as inverse matrix calculations is required and provide unacceptable results in regions close to singularities. Moreover, convergence of such methods depends on initial guess made at the beginning of the task solving. One more drawback of traditional inverse kinematics algorithms is that they can break down or become unacceptably slow for highly redundant systems. Trying to overcome these difficulties, many alternative solutions were proposed. For example, in [4] a method based on neural networks is described. It is applied to a manipulator with 3 degrees of freedom. According to the paper, the method produced reasonable results, but tool orientation was not considered and the result was influenced by initial guess greatly. Another option is to use a behavior-based approach. An example of such solver for a human arm with 7 DOF is presented in [5]. The author does not provide a general algorithm; his solution is applicable only to arm kinematics as it fully exploits specific features of such kinematic configuration.

3 Fig. 2. Schematic view and a model of the boom of the bucket excavator. 1 - Torso joint, 2 - Boom joint, 3 - Dipper arm joint, 4 - Stick joint, 5 - Bucket pitch joint, 6 - Bucket roll joint, 7 - Tool center point (TCP) In this paper a behavior-based inverse kinematics solver is introduced. It works within the ib2c-framework 1 presented in [6]. The solver has been simulated with 6-DOF bucket excavator (see figure 2) as a part of the AMoBA (Autonomer Mobilbagger - Autonomous Mobile Excavator) project whose long term goal is to make a real bucket excavator fully autonomous to perform landscaping tasks on a planned excavation site. The input parameters for the whole inverse kinematics are the position (x, y, z) and the orientation (Roll, Pitch, Yaw) relative to the center point at the bottom of the bucket excavator. The outputs of the task are 6 values of joint angles. The proposed solution does not involve complex algebraic calculations and singular configurations do not affect its performance. Another positive ability is that the solver could be easily expanded to systems with higher number of joints without greatly increasing the amount of computations. 2 Concept Unlike traditional inverse kinematics solvers suggested, the approach at hand does not presume centralized solution of the task. Instead every joint has a controller deciding in 1 integrated Behavior-based Control

4 Fig. 3. State machine of the designed inverse kinematics solver. i - iteration counter; i max - maximum number of iterations; new_desired_pose - a flag set when desired pose is changed, reset in Start solving state. which direction a joint should rotate in order to solve the global task of moving the tool to the desired point with desired orientation. In general, these controllers do not know whether the task is solvable, the position of the other joints, and how these joints move. The inverse kinematics task is solved incrementally according to the following procedure (see figure 3). When a new desired pose of TCP is set by a higher-level controller, the behavior network becomes active. At this moment it acquires the data about the current joint angles and switches to solving mode. During each iteration, all the joint controllers calculate a relatively small (approximately 1 4 ) step in the desired direction, then the steps of all joints are internally simulated and a new virtual position of the TCP is calculated. The joint controllers use this virtual position as new input and generate values for the next step. One supervising module compares the desired TCP pose and simulated virtual TCP pose. If the poses are close to each other, in position and orientation, the inverse kinematics task is considered as solved and the last calculated values of joint angles are provided as output of the solver. Afterwards, the solver remains inactive until a new desired TCP pose is provided as an input. Alternatively, if the task has not been solved in a reasonable number of iterations, the values that pro-

5 vided the closest TCP pose compared to the desired pose are given as the result. In this case the solver does not stop working and continues the search for a better solution. 3 Implementation The whole algorithm was implemented as a behavior-based network described in the following. The basic component of the proposed system is the so-called behaviorbased module of the ib2c-framework (figure 4). A behavior-based module is characterized by the triples: B = ( f a, f r,f) (1) e s ı B = ( f a, f r,f) u a r Fig. 4. The basic behavior module and the behavior fusion module both provide the same standardized inputs and outputs. where f a represents the activity function, f r means the target rating function, and F is the transfer function of the behavior. Depending on the input signals of a behavior, the stimulation s, the inhibition ı, and the input vector e, these functions calculate the output signals, activity a, target rating r, and the output vector u. The characteristic functions of a behavior as well as the input and output signals are defined as follows: Stimulation s: All behaviors receive their stimulation from other parts of the control system. The co-domain of the stimulation is [0,1], where s = 0 means no stimulation and s = 1 means full stimulation, values in between refer to a partially stimulated behavior. The stimulation of a behavior can be seen as the intended relevance of this behavior in the current situation. For some applications it is usefull to stimulate a behavior module permanently. This is indicated by a black triangle at the stimulation iput of the depicted module. Inhibition ı: A behavior can be inhibited by several other behaviors. The inhibition i of a behavior is defined as: i = max i j, where n denotes the number of inhibiting j=0,...,n 1 behaviors. The inhibition has the inverse effect of stimulation, i = 0 refers to no inhibition and i = 1 refers to full inhibition.

6 Activation ι: The activation of a behavior represents the relevance of a behavior for handling the current situation. It is calculated depending on the stimulation s and the inhibition i, with ι = s (1 i). The co-domain of the activation is [0,1], where 1 refers to full activation and 0 to no activation. Activity a: The activity a [0, 1] of a behavior represents its influence on the current robot behavior. An activity of 1 represents a fully active behavior whereas an activity of 0 represents a completely inactive behavior. The activity of a behavior is used to stimulate other behaviors. Furthermore so-called derived activities have been introduced. They offer the possibility to transfer only a part of the activity to other behaviors. That way more fine-grained stimulation can be realized. The activity a and the derived activities a are calculated by the activity function f a. They are defined as follows: f a : R m [0,1] [0,1] [0,1] q, f a ( e,ι) = a = (a, a) T (2) where with a = ( a 0,a 1,...,a q 1 ) T (3) a i a i {0,1,...,q 1} (4) Target Rating r: The target rating r [0,1] of a behavior indicated the behavior s satisfaction. A target rating of 0 refers to a satisfied behavior, a target rating of 1 to a completely unsatisfied one. In contrast to the activity the target rating does not depend on the activation. Therefore, it can be used to indicate whether a behavior would become active in case of activation. In case of the Exclusive Behavior (introduced below), this information is used to coordinate multiple behaviors. The target rating is calculated by the target rating function f r, which is defined as f r : R m [0,1], f r ( e) = r (5) Transfer Function F: The transfer function represents the intelligence of a behavior. It can be implemented in a way that it depends on internal variables representing a certain state of the behavior. That way, not only reactive sensor responses but also deliberative behaviors can be implemented. The transfer function calculates the output vector u R n of a behavior depending on the input vector e R m and the behavior s activation ι. Typically the input vector consists of sensor information and behavior signals of other behaviors. The output vector on the other hand provides control data for the actuators or for other behaviors. A typical application for behavior-based approaches is the modelling of complex control networks by combining and coordinating multiple rather simple behavior modules. Therefore, ib2c provides the so called Fusion Behavior modules. Such a Fusion Behavior is implemented as a specialized behavior module, which receives the output vectors as well as the behavior signals of the behavior modules to be coordinated and generates a combined output vector depending on the fusion function.

7 Fig. 5. Modular structure of the inverse kinematics solver. It contains four elements which deliver their sensor values (yellow) and control values (red) via specific interface channels. These ib2c elements are used to build up the structure of the solver, which is depicted in figure 5. The core element of the solver is the group Boom Behavioral Network which contains a set of identical joint controllers per joint. During each iteration they calculate the desired delta joint value. According to kinematic structure of the bucket excavator, four joints work in the same plane. This can lead to negative consequences, as all the joints, unaware of each other, may move towards the same direction and, therefore, lead to a too large global step. To prevent this, inhibition connections are used. It means that if, for example, a joint which is close to the end of kinematic chain moves, the other joints rotating in the same plane are inhibited and their activity is reduced for one iteration. The inhibition signals should propagate from the end of the kinematic chain to its beginning across all the joints, moving in the same plane. Each joint controller has two parts which work simultaneously. Its structure is represented in figure 6. One is trying to reach the desired position (Increase/Decrease Angle to Reach Position), another adjusts the desired orientation (Increase/Decrease Angle to Reach Orientation) of the TCP. Their results are combined by a fusion behavior with weighted fusion function, which creates the control values by summing up the input values and dividing them by two. The relation, how big the role of the positioning part is compared to the role of the orientation part, is defined by a special coefficient K w. If K w = 1, only the positioning part is important and the output of orientation part is disregarded. At the value K w = 0 the opposite happens. If 0 < K w < 1, both parts are considered, but with different importance. The joints at the end of kinematic chain deal with the orientation of the TCP, the further a joint is from end of kinematic chain, the more position-oriented it is.

8 Fig. 6. Internal structure of a joint controller. The modules and the structure used by both parts are identical. Each of them consists of two identical behavior modules whose output is consolidated by a fusion behavior which delivers the highest input value as a control value (maximum fusion). One of these behaviors tries to rotate the joint in positive direction, the other one in negative one. Each of the four behavior modules, composing a joint controller, has a clear and simple structure. It receives the actual joint angle and the x and y coordinates of the actual and desired TCP points within the local 2D joint rotation plane as an input. Each behavior tries move the actual point to the desired point by rotation of the corresponding joint. The maximum increment of the angle for a step is limited. Additionally it depends on how close the actual and desired points are to each other. The latter one allows to decrease the maximal step size in a region close to the desired pose and increase accuracy. The Direct Kinematics Transform module (see figure 5) provides the input for the joint controllers. The module contains a model of kinematic chain in Denavit-Hartenberg [7] notation and updates it with the values of joint angles provided to its input. After the chain is updated, the module provides data for both parts of joint controllers responsible for positioning and orientation of TCP correspondingly. For the positioning part, the module translates the coordinates of actual and desired positions of the TCP into the coordinate frames connected to corresponding joints. The resulting x and y coordinates serve as input for the joint controllers. For the orientation part, coordinate frames representing actual and desired orientation of TCP are translated to corresponding joint coordinate frames. The frames are represented as 3 3 rotation matrices. Each column of the rotation matrix represents coordinates of 3 basis vectors i, j, k of corresponding coordinate system. A joint can perform rotation only around 1 axis and cannot adjust all the 3 vectors simultaneously. Therefore, only those vectors that can be affected most should be chosen. As the rotation around the z-axis can change only x and y coordinates of basis vectors, the basis vectors with the least z-coordinates should be picked which that means that they lie in the XY -plane of the joint at most. As both, the actual (a) and desired (d) TCP orientations have to be considered at the same time, the final selection of output coordinates is made on basis

9 of the following criteria: arg min( i d z + i a z, j d z + j a z, k d z + k a z ) The x and y coordinates of corresponding coordinate vectors serve as input for the joint controllers. The main purpose of Behavioral Network Enable Switch module depicted in figure 5 is estimation whether the desired pose of TCP is achieved. It generates the activation signal for the behavioral network which is active since the moment when the new desired pose is introduced till the task has been solved. It also generates Reset and Store current position signals for the Output MUX module. This module decides when and which signals should be provided as output of the solver and what signals Direct Kinematics Transform module receives as input. The decision if it is closer or not is made based on two ratings for orientation and for position. In this particular implementation the orientation rating has priority as it is important for an excavator not to lose the content of the bucket. 4 Experiments To evaluate the developed system, several experiments to determine the quality have been realized. figure 7 presents the deviation of the TCP from the given target position. In this test scenario a sequence of different target positions, which were several meters apart, was given. It can be seen that every time a new target position is provided there is a high deviation which is decreased over time. It is remarkable that after a while the errors are always below 5 cm. Fig. 7. Deviation of the TCP from the given target position. The peaks are caused by the new target positions. The vertical axis depicts the deviation in meters, the horizontal axis depicts the time.

10 The proposed inverse kinematics solver was tested with the simulation model of the bucket excavator and demonstrated adequate good results. It was used together with a trajectory planner that divided the whole trajectory into small steps so the smooth movement of the excavator could be achieved. figure 7 represents the error of the task solution during performing a complex trajectory consisting of 6000 steps which included simultaneous changes of bucket pitch angle and x and z coordinates of TCP. Each point on horizontal axis represents one point in time when the trajectory planner provided new input to the inverse kinematics solver. At this moment the so far found solution of previous task was estimated and the corresponding errors are represented along the vertical axis (in cm for x and z coordinates and in radians for pitch angle). The overall accuracy of the solver was set to 5 cm for position and to 0.09 rad (5.2 ) for roll, pitch and yaw. When the error violates those bounds on the graph it means that the solution has not been found within the period between calculation of 2 consecutive points by the trajectory planner. Increasing this period or running the solver quicker improves the overall performance. The number of iterations needed to solve a task depends on how much the actual and desired poses differ. For situations when this difference is not too big the solution is usually found within 10 till 30 iterations. 5 Conclusion and Future Work The advantage of the proposed solver is that it does not require great computational power: the solving process does not involve calculations of Jacobians or matrix inversions; the most complex operation is matrix multiplication, which is also performed predetermined number of times per step. Therefore, even for robots with redundant kinematic structure the solver does not have problems with singularities and redundant configurations that may arise while using numerical inverse kinematics solvers. Another positive ability is that the solver could be easily expanded to systems with bigger number of joints without great increase in amount of computations. Moreover, in future the whole solver may be implemented as a library component configurable for desired kinematic chain with arbitrary number of joints. The drawback of such solver is that it has a heuristic nature which means that not always the solution is found even if the desired pose is reachable. This effect may become more evident in systems with complex kinematics. Also the solver lacks time determinism as the number of iterations needed for solving a task may differ significantly depending on the task. One more difficulty arises in the fine tuning of the solver. Each joint controller has 5 parameters (not including joint limits) affecting overall performance and determination of optimal solution may be quite complicated. Formalizing how the parameter values should be defined could be also a matter for future research. Another important characteristic of the behavior-based control is the ability to specifically suppress the movement of one joint controller. As the others are still active, the overall task solving process still continues. This will make complex obstacle avoidance during movements possible or allow for working with less joints if hardware breakdowns occur.

11 References 1. Halme, A., Luksch, T., Ylönen, S.: Biomimicing motion control of the workpartner robot. Industrial Robot (IFR) Vol. 31(2) (2004) pp Hirth, J., Berns, K.: Concept for behavior generation for the humanoid robot head ROMAN based on habits of interaction. In: Proceedings of the IEEE-RAS International Conference on Humanoid Robots (Humanoids), Pittsburgh, PA, USA (November 29-December ) Tolani, D., Goswami, A.,, Badler, N.I.: Real-time inverse kinematics techniques for anthropomorphic limbs. Graphical Models 62(5) (2000) Tejomurtula, S., Kak, S.: Inverse kinematics in robotics using neural networks. Information Sciences 116(2-4) (1999) Wang, X.: A behavior-based inverse kinematics algorithm to predict arm prehension postures for computer-aided ergonomic evaluation. Journal of Biomechanics 32(5) (May 1999) Proetzsch, M.: Development Process for Complex Behavior-Based Robot Control Systems. RRLab Dissertations. Verlag Dr. Hut (2010) ISBN Hartenberg, R.S., Denavit, J.: A kinematic notation for lower pair mechanisms based on matrices. Journal of Applied Mechanics 77 (1955)

Safety for an Autonomous Bucket Excavator During Typical Landscaping Tasks

Safety for an Autonomous Bucket Excavator During Typical Landscaping Tasks Safety for an Autonomous Bucket Excavator During Typical Landscaping Tasks Gregor Zolynski, Daniel Schmidt and Karsten Berns Abstract The Robotics Research Lab in Kaiserserlautern, Germany, pursues the

More information

Inverse Kinematics. Given a desired position (p) & orientation (R) of the end-effector

Inverse Kinematics. Given a desired position (p) & orientation (R) of the end-effector Inverse Kinematics Given a desired position (p) & orientation (R) of the end-effector q ( q, q, q ) 1 2 n Find the joint variables which can bring the robot the desired configuration z y x 1 The Inverse

More information

Inverse Kinematics Analysis for Manipulator Robot With Wrist Offset Based On the Closed-Form Algorithm

Inverse Kinematics Analysis for Manipulator Robot With Wrist Offset Based On the Closed-Form Algorithm Inverse Kinematics Analysis for Manipulator Robot With Wrist Offset Based On the Closed-Form Algorithm Mohammed Z. Al-Faiz,MIEEE Computer Engineering Dept. Nahrain University Baghdad, Iraq Mohammed S.Saleh

More information

1498. End-effector vibrations reduction in trajectory tracking for mobile manipulator

1498. End-effector vibrations reduction in trajectory tracking for mobile manipulator 1498. End-effector vibrations reduction in trajectory tracking for mobile manipulator G. Pajak University of Zielona Gora, Faculty of Mechanical Engineering, Zielona Góra, Poland E-mail: g.pajak@iizp.uz.zgora.pl

More information

An Efficient Method for Solving the Direct Kinematics of Parallel Manipulators Following a Trajectory

An Efficient Method for Solving the Direct Kinematics of Parallel Manipulators Following a Trajectory An Efficient Method for Solving the Direct Kinematics of Parallel Manipulators Following a Trajectory Roshdy Foaad Abo-Shanab Kafr Elsheikh University/Department of Mechanical Engineering, Kafr Elsheikh,

More information

Applying Neural Network Architecture for Inverse Kinematics Problem in Robotics

Applying Neural Network Architecture for Inverse Kinematics Problem in Robotics J. Software Engineering & Applications, 2010, 3: 230-239 doi:10.4236/jsea.2010.33028 Published Online March 2010 (http://www.scirp.org/journal/jsea) Applying Neural Network Architecture for Inverse Kinematics

More information

Introduction to Robotics

Introduction to Robotics Université de Strasbourg Introduction to Robotics Bernard BAYLE, 2013 http://eavr.u-strasbg.fr/ bernard Modelling of a SCARA-type robotic manipulator SCARA-type robotic manipulators: introduction SCARA-type

More information

Triangulation: A new algorithm for Inverse Kinematics

Triangulation: A new algorithm for Inverse Kinematics Triangulation: A new algorithm for Inverse Kinematics R. Müller-Cajar 1, R. Mukundan 1, 1 University of Canterbury, Dept. Computer Science & Software Engineering. Email: rdc32@student.canterbury.ac.nz

More information

Instant Prediction for Reactive Motions with Planning

Instant Prediction for Reactive Motions with Planning The 2009 IEEE/RSJ International Conference on Intelligent Robots and Systems October 11-15, 2009 St. Louis, USA Instant Prediction for Reactive Motions with Planning Hisashi Sugiura, Herbert Janßen, and

More information

Kinematics. Kinematics analyzes the geometry of a manipulator, robot or machine motion. The essential concept is a position.

Kinematics. Kinematics analyzes the geometry of a manipulator, robot or machine motion. The essential concept is a position. Kinematics Kinematics analyzes the geometry of a manipulator, robot or machine motion. The essential concept is a position. 1/31 Statics deals with the forces and moments which are aplied on the mechanism

More information

Force control of redundant industrial robots with an approach for singularity avoidance using extended task space formulation (ETSF)

Force control of redundant industrial robots with an approach for singularity avoidance using extended task space formulation (ETSF) Force control of redundant industrial robots with an approach for singularity avoidance using extended task space formulation (ETSF) MSc Audun Rønning Sanderud*, MSc Fredrik Reme**, Prof. Trygve Thomessen***

More information

Chapter 1: Introduction

Chapter 1: Introduction Chapter 1: Introduction This dissertation will describe the mathematical modeling and development of an innovative, three degree-of-freedom robotic manipulator. The new device, which has been named the

More information

1724. Mobile manipulators collision-free trajectory planning with regard to end-effector vibrations elimination

1724. Mobile manipulators collision-free trajectory planning with regard to end-effector vibrations elimination 1724. Mobile manipulators collision-free trajectory planning with regard to end-effector vibrations elimination Iwona Pajak 1, Grzegorz Pajak 2 University of Zielona Gora, Faculty of Mechanical Engineering,

More information

Modeling of Humanoid Systems Using Deductive Approach

Modeling of Humanoid Systems Using Deductive Approach INFOTEH-JAHORINA Vol. 12, March 2013. Modeling of Humanoid Systems Using Deductive Approach Miloš D Jovanović Robotics laboratory Mihailo Pupin Institute Belgrade, Serbia milos.jovanovic@pupin.rs Veljko

More information

This week. CENG 732 Computer Animation. Warping an Object. Warping an Object. 2D Grid Deformation. Warping an Object.

This week. CENG 732 Computer Animation. Warping an Object. Warping an Object. 2D Grid Deformation. Warping an Object. CENG 732 Computer Animation Spring 2006-2007 Week 4 Shape Deformation Animating Articulated Structures: Forward Kinematics/Inverse Kinematics This week Shape Deformation FFD: Free Form Deformation Hierarchical

More information

MTRX4700 Experimental Robotics

MTRX4700 Experimental Robotics MTRX 4700 : Experimental Robotics Lecture 2 Stefan B. Williams Slide 1 Course Outline Week Date Content Labs Due Dates 1 5 Mar Introduction, history & philosophy of robotics 2 12 Mar Robot kinematics &

More information

Humanoid Robotics. Inverse Kinematics and Whole-Body Motion Planning. Maren Bennewitz

Humanoid Robotics. Inverse Kinematics and Whole-Body Motion Planning. Maren Bennewitz Humanoid Robotics Inverse Kinematics and Whole-Body Motion Planning Maren Bennewitz 1 Motivation Planning for object manipulation Whole-body motion to reach a desired goal configuration Generate a sequence

More information

Inverse Kinematics of 6 DOF Serial Manipulator. Robotics. Inverse Kinematics of 6 DOF Serial Manipulator

Inverse Kinematics of 6 DOF Serial Manipulator. Robotics. Inverse Kinematics of 6 DOF Serial Manipulator Inverse Kinematics of 6 DOF Serial Manipulator Robotics Inverse Kinematics of 6 DOF Serial Manipulator Vladimír Smutný Center for Machine Perception Czech Institute for Informatics, Robotics, and Cybernetics

More information

Jacobians. 6.1 Linearized Kinematics. Y: = k2( e6)

Jacobians. 6.1 Linearized Kinematics. Y: = k2( e6) Jacobians 6.1 Linearized Kinematics In previous chapters we have seen how kinematics relates the joint angles to the position and orientation of the robot's endeffector. This means that, for a serial robot,

More information

Humanoid Robotics. Inverse Kinematics and Whole-Body Motion Planning. Maren Bennewitz

Humanoid Robotics. Inverse Kinematics and Whole-Body Motion Planning. Maren Bennewitz Humanoid Robotics Inverse Kinematics and Whole-Body Motion Planning Maren Bennewitz 1 Motivation Plan a sequence of configurations (vector of joint angle values) that let the robot move from its current

More information

ÉCOLE POLYTECHNIQUE DE MONTRÉAL

ÉCOLE POLYTECHNIQUE DE MONTRÉAL ÉCOLE POLYTECHNIQUE DE MONTRÉAL MODELIZATION OF A 3-PSP 3-DOF PARALLEL MANIPULATOR USED AS FLIGHT SIMULATOR MOVING SEAT. MASTER IN ENGINEERING PROJET III MEC693 SUBMITTED TO: Luc Baron Ph.D. Mechanical

More information

Lecture «Robot Dynamics»: Kinematic Control

Lecture «Robot Dynamics»: Kinematic Control Lecture «Robot Dynamics»: Kinematic Control 151-0851-00 V lecture: CAB G11 Tuesday 10:15 12:00, every week exercise: HG E1.2 Wednesday 8:15 10:00, according to schedule (about every 2nd week) Marco Hutter,

More information

Simulation and Control of an Autonomous Bucket Excavator for Landscaping Tasks

Simulation and Control of an Autonomous Bucket Excavator for Landscaping Tasks Simulation and Control of an Autonomous Bucket Excavator for Landscaping Tasks Daniel Schmidt, Martin Proetzsch, and Karsten Berns Abstract Introducing autonomous machines to construction areas can improve

More information

The Collision-free Workspace of the Tripteron Parallel Robot Based on a Geometrical Approach

The Collision-free Workspace of the Tripteron Parallel Robot Based on a Geometrical Approach The Collision-free Workspace of the Tripteron Parallel Robot Based on a Geometrical Approach Z. Anvari 1, P. Ataei 2 and M. Tale Masouleh 3 1,2 Human-Robot Interaction Laboratory, University of Tehran

More information

13. Learning Ballistic Movementsof a Robot Arm 212

13. Learning Ballistic Movementsof a Robot Arm 212 13. Learning Ballistic Movementsof a Robot Arm 212 13. LEARNING BALLISTIC MOVEMENTS OF A ROBOT ARM 13.1 Problem and Model Approach After a sufficiently long training phase, the network described in the

More information

A 12-DOF Analytic Inverse Kinematics Solver for Human Motion Control

A 12-DOF Analytic Inverse Kinematics Solver for Human Motion Control Journal of Information & Computational Science 1: 1 (2004) 137 141 Available at http://www.joics.com A 12-DOF Analytic Inverse Kinematics Solver for Human Motion Control Xiaomao Wu, Lizhuang Ma, Zhihua

More information

A novel approach to motion tracking with wearable sensors based on Probabilistic Graphical Models

A novel approach to motion tracking with wearable sensors based on Probabilistic Graphical Models A novel approach to motion tracking with wearable sensors based on Probabilistic Graphical Models Emanuele Ruffaldi Lorenzo Peppoloni Alessandro Filippeschi Carlo Alberto Avizzano 2014 IEEE International

More information

EEE 187: Robotics Summary 2

EEE 187: Robotics Summary 2 1 EEE 187: Robotics Summary 2 09/05/2017 Robotic system components A robotic system has three major components: Actuators: the muscles of the robot Sensors: provide information about the environment and

More information

MOTION TRAJECTORY PLANNING AND SIMULATION OF 6- DOF MANIPULATOR ARM ROBOT

MOTION TRAJECTORY PLANNING AND SIMULATION OF 6- DOF MANIPULATOR ARM ROBOT MOTION TRAJECTORY PLANNING AND SIMULATION OF 6- DOF MANIPULATOR ARM ROBOT Hongjun ZHU ABSTRACT:In order to better study the trajectory of robot motion, a motion trajectory planning and simulation based

More information

Robot mechanics and kinematics

Robot mechanics and kinematics University of Pisa Master of Science in Computer Science Course of Robotics (ROB) A.Y. 2016/17 cecilia.laschi@santannapisa.it http://didawiki.cli.di.unipi.it/doku.php/magistraleinformatica/rob/start Robot

More information

Rotating Table with Parallel Kinematic Featuring a Planar Joint

Rotating Table with Parallel Kinematic Featuring a Planar Joint Rotating Table with Parallel Kinematic Featuring a Planar Joint Stefan Bracher *, Luc Baron and Xiaoyu Wang Ecole Polytechnique de Montréal, C.P. 679, succ. C.V. H3C 3A7 Montréal, QC, Canada Abstract In

More information

Design and Optimization of the Thigh for an Exoskeleton based on Parallel Mechanism

Design and Optimization of the Thigh for an Exoskeleton based on Parallel Mechanism Design and Optimization of the Thigh for an Exoskeleton based on Parallel Mechanism Konstantin Kondak, Bhaskar Dasgupta, Günter Hommel Technische Universität Berlin, Institut für Technische Informatik

More information

10/25/2018. Robotics and automation. Dr. Ibrahim Al-Naimi. Chapter two. Introduction To Robot Manipulators

10/25/2018. Robotics and automation. Dr. Ibrahim Al-Naimi. Chapter two. Introduction To Robot Manipulators Robotics and automation Dr. Ibrahim Al-Naimi Chapter two Introduction To Robot Manipulators 1 Robotic Industrial Manipulators A robot manipulator is an electronically controlled mechanism, consisting of

More information

SCREW-BASED RELATIVE JACOBIAN FOR MANIPULATORS COOPERATING IN A TASK

SCREW-BASED RELATIVE JACOBIAN FOR MANIPULATORS COOPERATING IN A TASK ABCM Symposium Series in Mechatronics - Vol. 3 - pp.276-285 Copyright c 2008 by ABCM SCREW-BASED RELATIVE JACOBIAN FOR MANIPULATORS COOPERATING IN A TASK Luiz Ribeiro, ribeiro@ime.eb.br Raul Guenther,

More information

[2] J. "Kinematics," in The International Encyclopedia of Robotics, R. Dorf and S. Nof, Editors, John C. Wiley and Sons, New York, 1988.

[2] J. Kinematics, in The International Encyclopedia of Robotics, R. Dorf and S. Nof, Editors, John C. Wiley and Sons, New York, 1988. 92 Chapter 3 Manipulator kinematics The major expense in calculating kinematics is often the calculation of the transcendental functions (sine and cosine). When these functions are available as part of

More information

Jane Li. Assistant Professor Mechanical Engineering Department, Robotic Engineering Program Worcester Polytechnic Institute

Jane Li. Assistant Professor Mechanical Engineering Department, Robotic Engineering Program Worcester Polytechnic Institute Jane Li Assistant Professor Mechanical Engineering Department, Robotic Engineering Program Worcester Polytechnic Institute (3 pts) Compare the testing methods for testing path segment and finding first

More information

Research Subject. Dynamics Computation and Behavior Capture of Human Figures (Nakamura Group)

Research Subject. Dynamics Computation and Behavior Capture of Human Figures (Nakamura Group) Research Subject Dynamics Computation and Behavior Capture of Human Figures (Nakamura Group) (1) Goal and summary Introduction Humanoid has less actuators than its movable degrees of freedom (DOF) which

More information

Robots are built to accomplish complex and difficult tasks that require highly non-linear motions.

Robots are built to accomplish complex and difficult tasks that require highly non-linear motions. Path and Trajectory specification Robots are built to accomplish complex and difficult tasks that require highly non-linear motions. Specifying the desired motion to achieve a specified goal is often a

More information

Optimization of a two-link Robotic Manipulator

Optimization of a two-link Robotic Manipulator Optimization of a two-link Robotic Manipulator Zachary Renwick, Yalım Yıldırım April 22, 2016 Abstract Although robots are used in many processes in research and industry, they are generally not customized

More information

Motion Planning for Dynamic Knotting of a Flexible Rope with a High-speed Robot Arm

Motion Planning for Dynamic Knotting of a Flexible Rope with a High-speed Robot Arm The 2010 IEEE/RSJ International Conference on Intelligent Robots and Systems October 18-22, 2010, Taipei, Taiwan Motion Planning for Dynamic Knotting of a Flexible Rope with a High-speed Robot Arm Yuji

More information

which is shown in Fig We can also show that the plain old Puma cannot reach the point we specified

which is shown in Fig We can also show that the plain old Puma cannot reach the point we specified 152 Fig. 7.8. Redundant manipulator P8 >> T = transl(0.5, 1.0, 0.7) * rpy2tr(0, 3*pi/4, 0); The required joint coordinates are >> qi = p8.ikine(t) qi = -0.3032 1.0168 0.1669-0.4908-0.6995-0.1276-1.1758

More information

Robot mechanics and kinematics

Robot mechanics and kinematics University of Pisa Master of Science in Computer Science Course of Robotics (ROB) A.Y. 2017/18 cecilia.laschi@santannapisa.it http://didawiki.cli.di.unipi.it/doku.php/magistraleinformatica/rob/start Robot

More information

OPTIMIZATION OF INVERSE KINEMATICS OF ROBOTIC ARM USING ANFIS

OPTIMIZATION OF INVERSE KINEMATICS OF ROBOTIC ARM USING ANFIS OPTIMIZATION OF INVERSE KINEMATICS OF ROBOTIC ARM USING ANFIS 1. AMBUJA SINGH, 2. DR. MANOJ SONI 1(M.TECH STUDENT, R&A, DEPARTMENT OF MAE, IGDTUW, DELHI, INDIA) 2(ASSOCIATE PROFESSOR, DEPARTMENT OF MAE,

More information

Basilio Bona ROBOTICA 03CFIOR 1

Basilio Bona ROBOTICA 03CFIOR 1 Kinematic chains 1 Readings & prerequisites Chapter 2 (prerequisites) Reference systems Vectors Matrices Rotations, translations, roto-translations Homogeneous representation of vectors and matrices Chapter

More information

7-Degree-Of-Freedom (DOF) Cable-Driven Humanoid Robot Arm. A thesis presented to. the faculty of. In partial fulfillment

7-Degree-Of-Freedom (DOF) Cable-Driven Humanoid Robot Arm. A thesis presented to. the faculty of. In partial fulfillment Mechanism Design, Kinematics and Dynamics Analysis of a 7-Degree-Of-Freedom (DOF) Cable-Driven Humanoid Robot Arm A thesis presented to the faculty of the Russ College of Engineering and Technology of

More information

Table of Contents. Chapter 1. Modeling and Identification of Serial Robots... 1 Wisama KHALIL and Etienne DOMBRE

Table of Contents. Chapter 1. Modeling and Identification of Serial Robots... 1 Wisama KHALIL and Etienne DOMBRE Chapter 1. Modeling and Identification of Serial Robots.... 1 Wisama KHALIL and Etienne DOMBRE 1.1. Introduction... 1 1.2. Geometric modeling... 2 1.2.1. Geometric description... 2 1.2.2. Direct geometric

More information

Inverse KKT Motion Optimization: A Newton Method to Efficiently Extract Task Spaces and Cost Parameters from Demonstrations

Inverse KKT Motion Optimization: A Newton Method to Efficiently Extract Task Spaces and Cost Parameters from Demonstrations Inverse KKT Motion Optimization: A Newton Method to Efficiently Extract Task Spaces and Cost Parameters from Demonstrations Peter Englert Machine Learning and Robotics Lab Universität Stuttgart Germany

More information

Simulation-Based Design of Robotic Systems

Simulation-Based Design of Robotic Systems Simulation-Based Design of Robotic Systems Shadi Mohammad Munshi* & Erik Van Voorthuysen School of Mechanical and Manufacturing Engineering, The University of New South Wales, Sydney, NSW 2052 shadimunshi@hotmail.com,

More information

DIMENSIONAL SYNTHESIS OF SPATIAL RR ROBOTS

DIMENSIONAL SYNTHESIS OF SPATIAL RR ROBOTS DIMENSIONAL SYNTHESIS OF SPATIAL RR ROBOTS ALBA PEREZ Robotics and Automation Laboratory University of California, Irvine Irvine, CA 9697 email: maperez@uci.edu AND J. MICHAEL MCCARTHY Department of Mechanical

More information

A Full Analytical Solution to the Direct and Inverse Kinematics of the Pentaxis Robot Manipulator

A Full Analytical Solution to the Direct and Inverse Kinematics of the Pentaxis Robot Manipulator A Full Analtical Solution to the Direct and Inverse Kinematics of the Pentais Robot Manipulator Moisés Estrada Castañeda, Luis Tupak Aguilar Bustos, Luis A. Gonále Hernánde Instituto Politécnico Nacional

More information

Redundancy Resolution by Minimization of Joint Disturbance Torque for Independent Joint Controlled Kinematically Redundant Manipulators

Redundancy Resolution by Minimization of Joint Disturbance Torque for Independent Joint Controlled Kinematically Redundant Manipulators 56 ICASE :The Institute ofcontrol,automation and Systems Engineering,KOREA Vol.,No.1,March,000 Redundancy Resolution by Minimization of Joint Disturbance Torque for Independent Joint Controlled Kinematically

More information

10/11/07 1. Motion Control (wheeled robots) Representing Robot Position ( ) ( ) [ ] T

10/11/07 1. Motion Control (wheeled robots) Representing Robot Position ( ) ( ) [ ] T 3 3 Motion Control (wheeled robots) Introduction: Mobile Robot Kinematics Requirements for Motion Control Kinematic / dynamic model of the robot Model of the interaction between the wheel and the ground

More information

ROBOTICS 01PEEQW. Basilio Bona DAUIN Politecnico di Torino

ROBOTICS 01PEEQW. Basilio Bona DAUIN Politecnico di Torino ROBOTICS 01PEEQW Basilio Bona DAUIN Politecnico di Torino Kinematic chains Readings & prerequisites From the MSMS course one shall already be familiar with Reference systems and transformations Vectors

More information

Solving IK problems for open chains using optimization methods

Solving IK problems for open chains using optimization methods Proceedings of the International Multiconference on Computer Science and Information Technology pp. 933 937 ISBN 978-83-60810-14-9 ISSN 1896-7094 Solving IK problems for open chains using optimization

More information

ROBOTICS 01PEEQW. Basilio Bona DAUIN Politecnico di Torino

ROBOTICS 01PEEQW. Basilio Bona DAUIN Politecnico di Torino ROBOTICS 01PEEQW Basilio Bona DAUIN Politecnico di Torino Control Part 4 Other control strategies These slides are devoted to two advanced control approaches, namely Operational space control Interaction

More information

Kinematics and dynamics analysis of micro-robot for surgical applications

Kinematics and dynamics analysis of micro-robot for surgical applications ISSN 1 746-7233, England, UK World Journal of Modelling and Simulation Vol. 5 (2009) No. 1, pp. 22-29 Kinematics and dynamics analysis of micro-robot for surgical applications Khaled Tawfik 1, Atef A.

More information

Finding Reachable Workspace of a Robotic Manipulator by Edge Detection Algorithm

Finding Reachable Workspace of a Robotic Manipulator by Edge Detection Algorithm International Journal of Advanced Mechatronics and Robotics (IJAMR) Vol. 3, No. 2, July-December 2011; pp. 43-51; International Science Press, ISSN: 0975-6108 Finding Reachable Workspace of a Robotic Manipulator

More information

This blog addresses the question: how do we determine the intersection of two circles in the Cartesian plane?

This blog addresses the question: how do we determine the intersection of two circles in the Cartesian plane? Intersecting Circles This blog addresses the question: how do we determine the intersection of two circles in the Cartesian plane? This is a problem that a programmer might have to solve, for example,

More information

Planning, Execution and Learning Application: Examples of Planning for Mobile Manipulation and Articulated Robots

Planning, Execution and Learning Application: Examples of Planning for Mobile Manipulation and Articulated Robots 15-887 Planning, Execution and Learning Application: Examples of Planning for Mobile Manipulation and Articulated Robots Maxim Likhachev Robotics Institute Carnegie Mellon University Two Examples Planning

More information

Intermediate Desired Value Approach for Continuous Transition among Multiple Tasks of Robots

Intermediate Desired Value Approach for Continuous Transition among Multiple Tasks of Robots 2 IEEE International Conference on Robotics and Automation Shanghai International Conference Center May 9-3, 2, Shanghai, China Intermediate Desired Value Approach for Continuous Transition among Multiple

More information

Inverse Kinematics of Robot Manipulators with Multiple Moving Control Points

Inverse Kinematics of Robot Manipulators with Multiple Moving Control Points Inverse Kinematics of Robot Manipulators with Multiple Moving Control Points Agostino De Santis and Bruno Siciliano PRISMA Lab, Dipartimento di Informatica e Sistemistica, Università degli Studi di Napoli

More information

Cecilia Laschi The BioRobotics Institute Scuola Superiore Sant Anna, Pisa

Cecilia Laschi The BioRobotics Institute Scuola Superiore Sant Anna, Pisa University of Pisa Master of Science in Computer Science Course of Robotics (ROB) A.Y. 2016/17 cecilia.laschi@santannapisa.it http://didawiki.cli.di.unipi.it/doku.php/magistraleinformatica/rob/start Robot

More information

A Geometric Approach to Inverse Kinematics of a 3 DOF Robotic Arm

A Geometric Approach to Inverse Kinematics of a 3 DOF Robotic Arm A Geometric Approach to Inverse Kinematics of a 3 DOF Robotic Arm Ayush Gupta 1, Prasham Bhargava 2, Ankur Deshmukh 3, Sankalp Agrawal 4, Sameer Chourika 5 1, 2, 3, 4, 5 Department of Electronics & Telecommunication,

More information

Robot Vision without Calibration

Robot Vision without Calibration XIV Imeko World Congress. Tampere, 6/97 Robot Vision without Calibration Volker Graefe Institute of Measurement Science Universität der Bw München 85577 Neubiberg, Germany Phone: +49 89 6004-3590, -3587;

More information

Virtual Interaction System Based on Optical Capture

Virtual Interaction System Based on Optical Capture Sensors & Transducers 203 by IFSA http://www.sensorsportal.com Virtual Interaction System Based on Optical Capture Peng CHEN, 2 Xiaoyang ZHOU, 3 Jianguang LI, Peijun WANG School of Mechanical Engineering,

More information

Inverse Kinematics Solution for Trajectory Tracking using Artificial Neural Networks for SCORBOT ER-4u

Inverse Kinematics Solution for Trajectory Tracking using Artificial Neural Networks for SCORBOT ER-4u Inverse Kinematics Solution for Trajectory Tracking using Artificial Neural Networks for SCORBOT ER-4u Rahul R Kumar 1, Praneel Chand 2 School of Engineering and Physics The University of the South Pacific

More information

1 Trajectories. Class Notes, Trajectory Planning, COMS4733. Figure 1: Robot control system.

1 Trajectories. Class Notes, Trajectory Planning, COMS4733. Figure 1: Robot control system. Class Notes, Trajectory Planning, COMS4733 Figure 1: Robot control system. 1 Trajectories Trajectories are characterized by a path which is a space curve of the end effector. We can parameterize this curve

More information

Inverse Kinematics with Closed Form Solutions for Highly Redundant Robotic Systems

Inverse Kinematics with Closed Form Solutions for Highly Redundant Robotic Systems 29 IEEE International Conference on Robotics and Automation Kobe International Conference Center Kobe, Japan, May 12-17, 29 Inverse Kinematics with Closed Form Solutions for Highly Redundant Robotic Systems

More information

Autonomous Sensor Center Position Calibration with Linear Laser-Vision Sensor

Autonomous Sensor Center Position Calibration with Linear Laser-Vision Sensor International Journal of the Korean Society of Precision Engineering Vol. 4, No. 1, January 2003. Autonomous Sensor Center Position Calibration with Linear Laser-Vision Sensor Jeong-Woo Jeong 1, Hee-Jun

More information

Kinematics, Kinematics Chains CS 685

Kinematics, Kinematics Chains CS 685 Kinematics, Kinematics Chains CS 685 Previously Representation of rigid body motion Two different interpretations - as transformations between different coord. frames - as operators acting on a rigid body

More information

Visualization and Analysis of Inverse Kinematics Algorithms Using Performance Metric Maps

Visualization and Analysis of Inverse Kinematics Algorithms Using Performance Metric Maps Visualization and Analysis of Inverse Kinematics Algorithms Using Performance Metric Maps Oliver Cardwell, Ramakrishnan Mukundan Department of Computer Science and Software Engineering University of Canterbury

More information

Parallel Robots. Mechanics and Control H AMID D. TAG HI RAD. CRC Press. Taylor & Francis Group. Taylor & Francis Croup, Boca Raton London NewYoric

Parallel Robots. Mechanics and Control H AMID D. TAG HI RAD. CRC Press. Taylor & Francis Group. Taylor & Francis Croup, Boca Raton London NewYoric Parallel Robots Mechanics and Control H AMID D TAG HI RAD CRC Press Taylor & Francis Group Boca Raton London NewYoric CRC Press Is an Imprint of the Taylor & Francis Croup, an informs business Contents

More information

Control of industrial robots. Kinematic redundancy

Control of industrial robots. Kinematic redundancy Control of industrial robots Kinematic redundancy Prof. Paolo Rocco (paolo.rocco@polimi.it) Politecnico di Milano Dipartimento di Elettronica, Informazione e Bioingegneria Kinematic redundancy Direct kinematics

More information

3 No-Wait Job Shops with Variable Processing Times

3 No-Wait Job Shops with Variable Processing Times 3 No-Wait Job Shops with Variable Processing Times In this chapter we assume that, on top of the classical no-wait job shop setting, we are given a set of processing times for each operation. We may select

More information

Resolution of spherical parallel Manipulator (SPM) forward kinematic model (FKM) near the singularities

Resolution of spherical parallel Manipulator (SPM) forward kinematic model (FKM) near the singularities Resolution of spherical parallel Manipulator (SPM) forward kinematic model (FKM) near the singularities H. Saafi a, M. A. Laribi a, S. Zeghloul a a. Dept. GMSC, Pprime Institute, CNRS - University of Poitiers

More information

KINEMATIC ANALYSIS OF 3 D.O.F OF SERIAL ROBOT FOR INDUSTRIAL APPLICATIONS

KINEMATIC ANALYSIS OF 3 D.O.F OF SERIAL ROBOT FOR INDUSTRIAL APPLICATIONS KINEMATIC ANALYSIS OF 3 D.O.F OF SERIAL ROBOT FOR INDUSTRIAL APPLICATIONS Annamareddy Srikanth 1 M.Sravanth 2 V.Sreechand 3 K.Kishore Kumar 4 Iv/Iv B.Tech Students, Mechanical Department 123, Asst. Prof.

More information

Matlab Simulator of a 6 DOF Stanford Manipulator and its Validation Using Analytical Method and Roboanalyzer

Matlab Simulator of a 6 DOF Stanford Manipulator and its Validation Using Analytical Method and Roboanalyzer Matlab Simulator of a 6 DOF Stanford Manipulator and its Validation Using Analytical Method and Roboanalyzer Maitreyi More 1, Rahul Abande 2, Ankita Dadas 3, Santosh Joshi 4 1, 2, 3 Department of Mechanical

More information

Artificial Neural Network-Based Prediction of Human Posture

Artificial Neural Network-Based Prediction of Human Posture Artificial Neural Network-Based Prediction of Human Posture Abstract The use of an artificial neural network (ANN) in many practical complicated problems encourages its implementation in the digital human

More information

Singularity Loci of Planar Parallel Manipulators with Revolute Joints

Singularity Loci of Planar Parallel Manipulators with Revolute Joints Singularity Loci of Planar Parallel Manipulators with Revolute Joints ILIAN A. BONEV AND CLÉMENT M. GOSSELIN Département de Génie Mécanique Université Laval Québec, Québec, Canada, G1K 7P4 Tel: (418) 656-3474,

More information

Kinematics Analysis of Free-Floating Redundant Space Manipulator based on Momentum Conservation. Germany, ,

Kinematics Analysis of Free-Floating Redundant Space Manipulator based on Momentum Conservation. Germany, , Kinematics Analysis of Free-Floating Redundant Space Manipulator based on Momentum Conservation Mingming Wang (1) (1) Institute of Astronautics, TU Muenchen, Boltzmannstr. 15, D-85748, Garching, Germany,

More information

Local Search Methods. CS 188: Artificial Intelligence Fall Announcements. Hill Climbing. Hill Climbing Diagram. Today

Local Search Methods. CS 188: Artificial Intelligence Fall Announcements. Hill Climbing. Hill Climbing Diagram. Today CS 188: Artificial Intelligence Fall 2006 Lecture 5: Robot Motion Planning 9/14/2006 Local Search Methods Queue-based algorithms keep fallback options (backtracking) Local search: improve what you have

More information

Humanoid Robotics. Monte Carlo Localization. Maren Bennewitz

Humanoid Robotics. Monte Carlo Localization. Maren Bennewitz Humanoid Robotics Monte Carlo Localization Maren Bennewitz 1 Basis Probability Rules (1) If x and y are independent: Bayes rule: Often written as: The denominator is a normalizing constant that ensures

More information

Occluded Facial Expression Tracking

Occluded Facial Expression Tracking Occluded Facial Expression Tracking Hugo Mercier 1, Julien Peyras 2, and Patrice Dalle 1 1 Institut de Recherche en Informatique de Toulouse 118, route de Narbonne, F-31062 Toulouse Cedex 9 2 Dipartimento

More information

Using Algebraic Geometry to Study the Motions of a Robotic Arm

Using Algebraic Geometry to Study the Motions of a Robotic Arm Using Algebraic Geometry to Study the Motions of a Robotic Arm Addison T. Grant January 28, 206 Abstract In this study we summarize selected sections of David Cox, John Little, and Donal O Shea s Ideals,

More information

Design & Kinematic Analysis of an Articulated Robotic Manipulator

Design & Kinematic Analysis of an Articulated Robotic Manipulator Design & Kinematic Analysis of an Articulated Robotic Manipulator Elias Eliot 1, B.B.V.L. Deepak 1*, D.R. Parhi 2, and J. Srinivas 2 1 Department of Industrial Design, National Institute of Technology-Rourkela

More information

UNIVERSITY OF OSLO. Faculty of Mathematics and Natural Sciences

UNIVERSITY OF OSLO. Faculty of Mathematics and Natural Sciences Page 1 UNIVERSITY OF OSLO Faculty of Mathematics and Natural Sciences Exam in INF3480 Introduction to Robotics Day of exam: May 31 st 2010 Exam hours: 3 hours This examination paper consists of 5 page(s).

More information

Jacobian: Velocities and Static Forces 1/4

Jacobian: Velocities and Static Forces 1/4 Jacobian: Velocities and Static Forces /4 Advanced Robotic - MAE 6D - Department of Mechanical & Aerospace Engineering - UCLA Kinematics Relations - Joint & Cartesian Spaces A robot is often used to manipulate

More information

Trajectory Optimization

Trajectory Optimization Trajectory Optimization Jane Li Assistant Professor Mechanical Engineering & Robotics Engineering http://users.wpi.edu/~zli11 Recap We heard about RRT*, a sampling-based planning in high-dimensional cost

More information

DEVELOPMENT OF TELE-ROBOTIC INTERFACE SYSTEM FOR THE HOT-LINE MAINTENANCE. Chang-Hyun Kim, Min-Soeng Kim, Ju-Jang Lee,1

DEVELOPMENT OF TELE-ROBOTIC INTERFACE SYSTEM FOR THE HOT-LINE MAINTENANCE. Chang-Hyun Kim, Min-Soeng Kim, Ju-Jang Lee,1 DEVELOPMENT OF TELE-ROBOTIC INTERFACE SYSTEM FOR THE HOT-LINE MAINTENANCE Chang-Hyun Kim, Min-Soeng Kim, Ju-Jang Lee,1 Dept. of Electrical Engineering and Computer Science Korea Advanced Institute of Science

More information

Reinforcement Learning for Appearance Based Visual Servoing in Robotic Manipulation

Reinforcement Learning for Appearance Based Visual Servoing in Robotic Manipulation Reinforcement Learning for Appearance Based Visual Servoing in Robotic Manipulation UMAR KHAN, LIAQUAT ALI KHAN, S. ZAHID HUSSAIN Department of Mechatronics Engineering AIR University E-9, Islamabad PAKISTAN

More information

Control of Snake Like Robot for Locomotion and Manipulation

Control of Snake Like Robot for Locomotion and Manipulation Control of Snake Like Robot for Locomotion and Manipulation MYamakita 1,, Takeshi Yamada 1 and Kenta Tanaka 1 1 Tokyo Institute of Technology, -1-1 Ohokayama, Meguro-ku, Tokyo, Japan, yamakita@ctrltitechacjp

More information

KINEMATIC IDENTIFICATION OF PARALLEL MECHANISMS BY A DIVIDE AND CONQUER STRATEGY

KINEMATIC IDENTIFICATION OF PARALLEL MECHANISMS BY A DIVIDE AND CONQUER STRATEGY KINEMATIC IDENTIFICATION OF PARALLEL MECHANISMS BY A DIVIDE AND CONQUER STRATEGY Sebastián Durango a, David Restrepo a, Oscar Ruiz a, John Restrepo-Giraldo b and Sofiane Achiche b a CAD CAM CAE research

More information

Improving Vision-Based Distance Measurements using Reference Objects

Improving Vision-Based Distance Measurements using Reference Objects Improving Vision-Based Distance Measurements using Reference Objects Matthias Jüngel, Heinrich Mellmann, and Michael Spranger Humboldt-Universität zu Berlin, Künstliche Intelligenz Unter den Linden 6,

More information

Lecture VI: Constraints and Controllers. Parts Based on Erin Catto s Box2D Tutorial

Lecture VI: Constraints and Controllers. Parts Based on Erin Catto s Box2D Tutorial Lecture VI: Constraints and Controllers Parts Based on Erin Catto s Box2D Tutorial Motion Constraints In practice, no rigid body is free to move around on its own. Movement is constrained: wheels on a

More information

PSO based Adaptive Force Controller for 6 DOF Robot Manipulators

PSO based Adaptive Force Controller for 6 DOF Robot Manipulators , October 25-27, 2017, San Francisco, USA PSO based Adaptive Force Controller for 6 DOF Robot Manipulators Sutthipong Thunyajarern, Uma Seeboonruang and Somyot Kaitwanidvilai Abstract Force control in

More information

Singularity Management Of 2DOF Planar Manipulator Using Coupled Kinematics

Singularity Management Of 2DOF Planar Manipulator Using Coupled Kinematics Singularity Management Of DOF lanar Manipulator Using oupled Kinematics Theingi, huan Li, I-Ming hen, Jorge ngeles* School of Mechanical & roduction Engineering Nanyang Technological University, Singapore

More information

A modular neural network architecture for inverse kinematics model learning

A modular neural network architecture for inverse kinematics model learning Neurocomputing 38}40 (2001) 797}805 A modular neural network architecture for inverse kinematics model learning Eimei Oyama*, Arvin Agah, Karl F. MacDorman, Taro Maeda, Susumu Tachi Intelligent System

More information

Kinematic Model of Robot Manipulators

Kinematic Model of Robot Manipulators Kinematic Model of Robot Manipulators Claudio Melchiorri Dipartimento di Ingegneria dell Energia Elettrica e dell Informazione (DEI) Università di Bologna email: claudio.melchiorri@unibo.it C. Melchiorri

More information

IntroductionToRobotics-Lecture02

IntroductionToRobotics-Lecture02 IntroductionToRobotics-Lecture02 Instructor (Oussama Khatib):Okay. Let's get started. So as always, the lecture starts with a video segment, and today's video segment comes from 1991, and from the group

More information

An Interactive Technique for Robot Control by Using Image Processing Method

An Interactive Technique for Robot Control by Using Image Processing Method An Interactive Technique for Robot Control by Using Image Processing Method Mr. Raskar D. S 1., Prof. Mrs. Belagali P. P 2 1, E&TC Dept. Dr. JJMCOE., Jaysingpur. Maharashtra., India. 2 Associate Prof.

More information