ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
Fundamentally, that is a problem that requires "inverse kinematics" (often called IK). The general IK problem is to find a set of joint angles that produce a desired end-effector position (an XYZ location) and/or orientation (a position and orientation is often referred to as a pose). For a robot like Baxter with 7 degrees-of-freedom in a single arm, if you choose a feasible pose (one that is actually reachable) there are actually an infinite number of solutions to this problem, and deciding which solution to choose and how to find it is not necessarily a trivial task.
Baxter's API offers no direct way of controlling the arm in Cartesian space, however, they do give you tools that would allow you to do what you want. For example, you could use Baxter's built-in IK service to solve for a joint angle solution, and then you could use something like Limb.move_to_joint_positions to command the arm to that set of joint angles.
Note that there are many other tools available that might also be useful for solving the IK problem. KDL, which is released as a ROS package, has libraries for calculating IK solutions with a variety of different constraints. These library functions are available in C++ and Python through PyKDL. There is also pykdl_utils (and baxter_pykdl) that have nice Python interfaces for calculating IK with KDL.
A properly configured MoveIt! robot offers several ways of computing an IK solution (there are services and API calls). MoveIt! uses different plugins to compute IK, but commonly people use KDL, IKFast, or trac_ik to as the backend for MoveIt!.
If you would like an interface that directly moves the EE in Cartesian directions (likely while keeping the orientation fixed, based on your question), you need to learn about manipulator Jacobians. This topic is often called operational space control. I'd suggest checking out section 11.3 of Modern Robotics: Mechanics, Planning, and Control by Lynch and Park (PDF online) for a comprehensive description of using joint velocities to track desired EE poses. There are many other great resources available as well.
2 | No.2 Revision |
Fundamentally, that is a problem that requires "inverse kinematics" (often called IK). The general IK problem is to find a set of joint angles that produce a desired end-effector position (an XYZ location) and/or orientation (a (could be a quaternion, some set of Euler angles, or a rotation matrix). A position and orientation together is often referred to as a pose). pose. For a robot like Baxter with 7 degrees-of-freedom in a single arm, if you choose a feasible pose (one that is actually reachable) there are actually an infinite number of solutions to this problem, and deciding which solution to choose and how to find it is not necessarily a trivial task.
Baxter's API offers no direct way of controlling the arm in Cartesian space, however, they do give you tools that would allow you to do what you want. For example, you could use Baxter's built-in IK service to solve for a joint angle solution, and then you could use something like Limb.move_to_joint_positions to command the arm to that set of joint angles.
Note that there are many other tools available that might also be useful for solving the IK problem. KDL, which is released as a ROS package, has libraries for calculating IK solutions with a variety of different constraints. These library functions are available in C++ and Python through PyKDL. There is also pykdl_utils (and baxter_pykdl) that have nice Python interfaces for calculating IK with KDL.
A properly configured MoveIt! robot offers several ways of computing an IK solution (there are services and API calls). MoveIt! uses different plugins to compute IK, but commonly people use KDL, IKFast, or trac_ik to as the backend for MoveIt!.MoveIt! IK computations.
If you would like an interface that directly moves the EE in Cartesian directions (likely while keeping the orientation fixed, based on your question), you need to learn about manipulator Jacobians. This topic is often called operational space control. I'd suggest checking out section 11.3 of Modern Robotics: Mechanics, Planning, and Control by Lynch and Park (PDF online) for a comprehensive description of using joint velocities to track desired EE poses. There are many other great resources available as well.