roboticslibrary / rl

The Robotics Library (RL) is a self-contained C++ library for rigid body kinematics and dynamics, motion planning, and control.
https://www.roboticslibrary.org/
BSD 2-Clause "Simplified" License
891 stars 206 forks source link

A minimal example for inverse kinematics - Request #15

Open svenkatachalam opened 4 years ago

svenkatachalam commented 4 years ago

I am trying to use the Robotics Library for implementing control algorithms on Industrial Robots. I am currently trying to understand the computation of the inverse kinematic model based on end effector position and orientation. The minimal example given in computing the inverse kinematics (using both jacobian and NloptInverseKinematics) uses the DH Matrix obtained from forward kinematics model and the goals are taken using ik.goals.push_back(::std::make_pair(kinematic->getOperationalPosition(0), 0)). As I understand kinematic->getOperationalPosition(0) works for forward kinematics after using kinematic->forwardPosition(). For my case, I have the goal represented in World coordinates (X,Y,Z,R,P and Y), looking to find the inverse transformation, that would fetch individual joint angles.

rickertm commented 4 years ago

The demo rlInversePositionDemo first uses forward kinematics to ensure a valid end effector frame for the following IK calculation. In order to use your own goal frame, please replace the frame calculated by the forward kinematics in line 100 with your own rl::math::Transform that is reachable with the kinematic model.

Here's an example for the Mitsubishi RV-6SL kinematic model specified in mitsubishi-rv6sl.xml with the rotation specified as Euler-ZYX (z = 0°, y = 90°, x = 0°) and the translation set to (x = 0.595 m, y = 0.0 m, z = 0.83 m):

rl::math::Transform goal;
goal.linear() = rl::math::AngleAxis(0.0 * rl::math::DEG2RAD, rl::math::Vector3::UnitZ()) *
    rl::math::AngleAxis(90.0 * rl::math::DEG2RAD, rl::math::Vector3::UnitY()) *
    rl::math::AngleAxis(0.0 * rl::math::DEG2RAD, rl::math::Vector3::UnitX()).toRotationMatrix();
goal.translation() = rl::math::Vector3(0.595, 0.0, 0.83);
ik.addGoal(goal, 0);

For your own IK calculation, you can skip the forward kinematics calculation in lines 77-89 and the random initialization in lines 102-110.

svenkatachalam commented 4 years ago

Thank you very much for providing the minimal code for IK calculation.