rl icon indicating copy to clipboard operation
rl copied to clipboard

Inverse solution ---Tool coordinates

Open jinzhouchu opened this issue 3 months ago • 4 comments

Hello! When using the RL library for inverse kinematics, I found that the rotation of joint "c" is not aligned with the direction of the tool axis. Do I need to modify any parameters? I intend to use the tool coordinate to control the robotic arm. The demo I referred to is rlCoachMdl. b3b02dcebd177a0a00c57388153e19d

jinzhouchu avatar Mar 30 '24 08:03 jinzhouchu

When I adjust the C value, the robotic arm rotates around the blue line.

jinzhouchu avatar Mar 30 '24 08:03 jinzhouchu

The values in the operational widget refer to the operational position and orientation of the robot's end effector in world coordinates. In order to specify changes in the tool frame, you can calculate the robot's Jacobian matrix in tool coordinates, see rl::mdl::Kinematic::calculateJacobian().

rickertm avatar Mar 31 '24 15:03 rickertm

Thank you for your answer, but I'm a beginner in RL. Could you please guide me on how to modify this code to achieve the desired effect? I appreciate your assistance.

` bool RLConvertAPI::SetIndexedInverseValue(const int &index, const double &value) { if (rl::mdl::Kinematic* kinematic = dynamic_castrl::mdl::Kinematic*(aReaderAPI->JointModel.get())) {

    rl::math::Transform transform = kinematic->getOperationalPosition(0);

    rl::math::Vector3 orientation = transform.linear().eulerAngles(2, 1, 0).reverse();

    switch (index)
    {
    case 0:
    case 1:
    case 2:
        transform.translation()(index) = value;
        break;
    case 3:
        transform.linear() = (
                    rl::math::AngleAxis(orientation.z(), rl::math::Vector3::UnitZ()) *
                    rl::math::AngleAxis(orientation.y(), rl::math::Vector3::UnitY()) *
                    rl::math::AngleAxis(value * rl::math::constants::deg2rad, rl::math::Vector3::UnitX())
                    ).toRotationMatrix();
        break;
    case 4:
        transform.linear() = (
                    rl::math::AngleAxis(orientation.z(), rl::math::Vector3::UnitZ()) *
                    rl::math::AngleAxis(value * rl::math::constants::deg2rad, rl::math::Vector3::UnitY()) *
                    rl::math::AngleAxis(orientation.x(), rl::math::Vector3::UnitX())
                    ).toRotationMatrix();
        break;
    case 5:
        transform.linear() = (
                    rl::math::AngleAxis(value * rl::math::constants::deg2rad, rl::math::Vector3::UnitZ()) *
                    rl::math::AngleAxis(orientation.y(), rl::math::Vector3::UnitY()) *
                    rl::math::AngleAxis(orientation.x(), rl::math::Vector3::UnitX())
                    ).toRotationMatrix();
        break;
    default:
        break;
    }

    rl::math::Vector q = kinematic->getPosition();

    rl::mdl::InverseKinematics* aInverse = new rl::mdl::JacobianInverseKinematics(kinematic);

    aInverse->addGoal(transform, 0);

    bool solved = aInverse->solve();

    if (solved)
    {
        rl::math::Vector currentPos = kinematic->getPosition();


        SetJointValue(currentPos);

        delete aInverse;

        return true;

    }
    else
    {
        kinematic->setPosition(q);

        kinematic->forwardPosition();

        delete aInverse;

        return false;
    }
}
return false;

}

`

jinzhouchu avatar Apr 01 '24 01:04 jinzhouchu

Looking forward to your reply

jinzhouchu avatar Apr 02 '24 00:04 jinzhouchu