pinocchio icon indicating copy to clipboard operation
pinocchio copied to clipboard

Continuous joint in URDF adds 2 elements to the configuration space

Open mkatliar opened this issue 5 years ago • 7 comments

Example:

auto const xml = R"urdf(
    <robot name="test">
        <link name="base">
        </link>
        <link name="link1">
            <inertial>
            <origin xyz="0. 0. 0."/>
            <mass value="1."/>
            <inertia ixx="1." ixy="0." ixz="0." iyy="1." iyz="0." izz="1."/>
            </inertial>
        </link>
        <joint name="joint0" type="continuous">
            <parent link="base"/>
            <child link="link1"/>
            <axis xyz="0. 0. 1."/>
            <origin rpy="0. 0. 0." xyz="0. 0. 0."/>
        </joint>
    </robot>
)urdf";

pinocchio::Model model;
pinocchio::urdf::buildModelFromXML(xml, model);

assert(model.nq == 1);

This code results in model.nq == 2 and the assert fails. Changing joint type to "revolute" results in model.nq == 1, as expected.

According to http://wiki.ros.org/urdf/XML/joint,

type (required)

Specifies the type of joint, where type can be one of the following:
...
continuous - a continuous hinge joint that rotates around the axis and has no upper and lower limits.

Therefore I expect a continuous joint to add 1 element to the configuration space, the same way as a revolute joint would do.

This issue seems also to be related to this question: https://github.com/stack-of-tasks/pinocchio/issues/735#issuecomment-472506592

mkatliar avatar May 07 '19 11:05 mkatliar

For continuous joints, Pinocchio uses the complex representation of SO(2). The 2 elements are thus cos(theta), sin(theta).

jmirabel avatar May 07 '19 11:05 jmirabel

We use cos(theta), sin(theta) to represent the configuration vector of a Continuous joint while only theta for a revolute joint. This expected because continuous means that there are no bounds on the configuration vectors. But for both cases, we have \dot{theta}which corresponds to the velocity of the joint.

We also use cos(theta), sin(theta) for continuous joints in a similar way we use rely on quaternions to represent the configuration of a spherical joint.

@mkatliar I hope this answer will satisfy your curiosity.

jcarpent avatar May 07 '19 12:05 jcarpent

This was already the subject of a previous issue. You can find more info here: #777

gabrielebndn avatar May 07 '19 12:05 gabrielebndn

I will close this issue. @mkatliar Feel free to open it again if needed.

jcarpent avatar May 07 '19 13:05 jcarpent

Thank you very much for your replies, now it is clear. Would it be possible to add this explanation somewhere in the docs?

mkatliar avatar May 07 '19 13:05 mkatliar

Sorry. I was too fast. We will add it in the doc very soon.

jcarpent avatar May 07 '19 13:05 jcarpent

@gabrielebndn Can you help me to structure the documentation of the Joint classes inside the Pinocchio doc?

jcarpent avatar May 07 '19 13:05 jcarpent