Skip to content

Continuous joint in URDF adds 2 elements to the configuration space #794

Open
@mkatliar

Description

@mkatliar

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: #735 (comment)

Metadata

Metadata

Type

No type

Projects

No projects

Milestone

No milestone

Relationships

None yet

Development

No branches or pull requests

Issue actions