Robotics StackExchange | Archived questions

spherical joint in urdf.xacro

Created a custom spherical joint using dummy links to simulate a spherical pendulum in Gazebo. Code below,

<xacro:macro name="rotational_joint" params="parent child jx jy jz r p y">
    <xacro:dummy_link name="${parent}_${child}_dummylink1"/>
    <xacro:dummy_link name="${parent}_${child}_dummylink2"/>
    <joint name="${parent}_${child}_roll" type="continuous">
        <parent link="${parent}"/>
        <child link="${parent}_${child}_dummylink1"/>
        <axis xyz="1 0 0"/>
        <!-- <joint_properties damping="0.0" friction="0.0" /> -->
        <origin xyz="${jx} ${jy} ${jz}" rpy="${r} 0 0"/>
    </joint>
    <joint name="${parent}_${child}_pitch" type="continuous">
        <parent link="${parent}_${child}_dummylink1"/>
        <child link="${parent}_${chilC:\fakepath\sp_smallmass.gifd}_dummylink2"/>
        <axis xyz="0 1 0"/>
        <!-- <joint_properties damping="0.0" friction="0.0" /> -->
        <origin xyz="0 0 0" rpy="0 ${p} 0"/>
    </joint>
    <joint name="${parent}_${child}_yaw" type="continuous">
        <parent link="${parent}_${child}_dummylink2"/>
        <child link="${child}"/>
        <axis xyz="0 0 1"/>
        <!-- <joint_properties damping="0.0" friction="0.0" /> -->
        <origin xyz="0 0 0" rpy="0 0 ${y}"/>
    </joint>
</xacro:macro>

It works (looks) good for smaller pendulum mass but for larger mass values, the joint disconnects and (moves along the cable length in addition to the rotations). See image below (left larger mass value, right smaller mass). image description

Link to the videos vid1, vid2. Full urdf file here.

What can I try to fix this issue?


I understand there is a universal joint in Gazebo link1, link2. However, I haven't been able to get it to work. From link 2, could I potentially create a model_plugin to incorporate a spherical pendulum? Any suggestions?


Asked by pkot on 2020-12-08 04:54:31 UTC

Comments

Created a model plugin to add a universal joint between the parent & child link (modeled as a floating joint in urdf), this seems to have a good performance.

// Create a universal joint
  std::string joint_name = parent_link_name_+"_"+child_link_name_+"_universal_joint";
  joint_ = model_->CreateJoint(joint_name, "universal", parent_link_, child_link_ );
  joint_->SetAnchor(0, child_link_->WorldPose().Pos());
  joint_->SetAnchor(1, child_link_->WorldPose().Pos());

Asked by pkot on 2021-01-04 23:39:45 UTC

Answers