Re: [ros-users] Closed kinematic chains in ros/gazebo

Top Page
Attachments:
Message as email
+ (text/plain)
+ (text/html)
Delete this message
Reply to this message
Author: User discussions
Date:  
To: John Hsu
CC: User discussions
Subject: Re: [ros-users] Closed kinematic chains in ros/gazebo
Thanks for the feedback. I've been looking at urdf2gazebo.cpp to see how I
can add in the last joint to the gazebo model, using, as you suggest, a
gazebo extension to get the joint information. Is the support already built
into that code, or a previous version? I have a plan on adding it, but may
not be doing everything in the best manner possible.

Looking through the gripper xacro file, there is this:

 <joint:hinge name="${prefix}_r_parallel_root_joint">
          <body1>${prefix}_r_parallel_link</body1>
          <body2>${prefix}_palm_link</body2>
          <anchor>${prefix}_palm_link</anchor>
          <axis>0 0 -1</axis>
          <damping>0.2</damping>
          <anchorOffset>${0.07691+parallel_link_x_offset}
${-0.01-parallel_link_y_offset} 0</anchorOffset>
      </joint:hinge>


Is this the code that adds in the parallel link? If so, I should be able to
decipher what everything in there does.

As far as the application, we have a pan/tilt platform, where the tilt axis
controls one of the bars of a 4-bar linkage so that upper platform actually
translates instead of tilts. There is then another pan/tilt head on top of
the first one to do the actual tilting. But the 4-bar linkage is the one
causing the difficulties.

Thanks

Andrew


On Fri, Oct 8, 2010 at 2:39 PM, John Hsu <> wrote:

> Hi Andrew,
>
> Can you provide some more detail about the robot you're simulating and your
> application?
>
> To model the closed loop chain in the PR2 gripper, I hid an additional
> joint constraint in <gazebo> extension for each gripper so we are
> effectively solving the dynamics of a closed 4-bar linkage in ODE. The
> implementation is far from pretty but that's what I had to do to get around
> the urdf tree-structure requirement. For urdf-2.0, we plan on adding graph
> support <https://code.ros.org/trac/ros-pkg/ticket/4263>, but that's in the
> discussion stage.
>
> As for joint mimic, ODE internally does not support dynamic joint mimicking
> right now, it's something on my todo list, but may take a while, pending
> priority of the functionality.
>
> Without a specific context for your simulation, I might suggest trying the
> same trick I did for the PR2 gripper first by hiding the additional
> "loop-closing" joint in gazebo extensions, and the physics engine can take
> care of the implicit joint mimicking behavior due to closed loop
> constraints.
>
> Note that using the set_link_state service call for partial robot will most
> likely disrupt dynamics of the entire of the system.
>
> I cc'd the list in case someone else has more experiences with similar
> problems.
> John
>
>
> On Fri, Oct 8, 2010 at 8:24 AM, Andrew Mor <> wrote:
>
>> John,
>>
>> I was wondering if there was a straightforward way of constraining the
>> orientation of a joint within the urdf framework? I looked through the
>> archives of the mailing list and the pr2_gripper code, and nothing is really
>> popping out at me. We have a simple 4 bar mechanism where the side bars are
>> both the same size and the top is the same as the bottom, so the side links
>> are always parallel as is the top to the bottom. I was hoping to use the
>> mimic tag from within my controller to set the joint_state_ position to be
>> equal to the other joint, but position_ is read-only. Is there another way
>> to get around this without constructing a custom transmission?
>>
>> I had thought about calling the /gazebo/set_link_state service and that is
>> still my backup plan before writing a transmission.
>>
>> Would this be better to send to the ros-users list?
>>
>> Thanks
>>
>> Andrew Mor
>>
>
>