-
Notifications
You must be signed in to change notification settings - Fork 11
[I] luh_youbot_kinematics
luh_youbot_kinematics is a kinematics library for the youbot manipulator. It offers classes to represent poses, velocities and accelerations in jointspace and taskspace and the neccesary conversions. For the taskspace there are two coordinate systems to describe the endeffector position and orientation: cartesian coordinates and cylindrical coordinates.
If you are using the Controller API, the kinematics are already included. Otherwise include the following header:
#include <luh_youbot_kinematics/arm_kinematics.h>
###Coordinates systems
Arm poses can be described in the following three coordinate systems.
####Jointspace
A position in jointspace is defined by the five joint angles q1, q2, q3, q4 and q5.
Jointspace coordinates are represented by the following classes:
luh_youbot_kinematics::JointPosition
luh_youbot_kinematics::JointVelocity
luh_youbot_kinematics::JointAcceleration
####Taskspace: Cartesian
A position in cartesian coordinates is defined by the three translational degrees of freedom (dof) x, y and z and the two rotational dof's theta and q5. q5 is the same as in jointspace. x, y and z are defined in the frame „arm_link_0“.
Cartesian coordinates are represented by the following classes:
luh_youbot_kinematics::CartesianPosition
luh_youbot_kinematics::CartesianVelocity
luh_youbot_kinematics::CartesianAcceleration
####Taskspace: Cylindrical
A position in cylindrical coordinates is defined by the two translational dof's r and z and the three rotational dof's q1, theta and q5. q1 and q5 are the same as in jointspace and z and theta are the same as in cartesian coordinates. r is the radius of the endeffector position measured from the axis of joint 1.
Cylindrical coordinates are represented by the following classes:
luh_youbot_kinematics::CylindricPosition
luh_youbot_kinematics::CylindricVelocity
luh_youbot_kinematics::CylindricAcceleration
###Transformations
Transformations between the coordinate systems can be done by the three methods
toJointspace()
toCartesian()
toCylindric()
There are several versions of these methods which require different arguments. For a detailed description see the documentation in luh_youbot_kinematics/doc/html/index.hmtl ###Example
Here is a small example to demonstrate the basic usage.
#include <luh_youbot_kinematics/arm_kinematics.h>
using namespace luh_youbot_kinematics;
int main(int argc, char** argv)
{
// start with a position in cartesian coordinates
CartesianPosition cart_pos;
cart_pos.setX(0.2);
cart_pos.setY(0.1);
cart_pos.setZ(0.04);
cart_pos.setTheta(3.14);
cart_pos.setQ5(0);
// transform to cylindrical coordinates
CylindricPosition cyl_pos = cart_pos.toCylindric();
// print radius
std::cout << "Radius: " << cyl_pos.r() << std::endl;
// transform to jointspace
JointPosition jnt_pos = cyl_pos.toJointspace();
// print all joint angles
jnt_pos.printValues("Joint angles");
return 0;
}