[ros-users] Flexible & remote transmission

Jeroen Willems jjpa.willems at gmail.com
Thu Dec 16 10:50:38 UTC 2010


Hi John,

Great job!
You got the gist of the problem and that was basically what I meant.
I tested your urdf spring_transmission and it looks like I intuitive
expected.
I am gonna give it a shot implementing it in my robot.

Thanks, Jeroen

On Thu, Dec 16, 2010 at 01:14, John Hsu <johnhsu at willowgarage.com> wrote:

> I went ahead and checked it into the sandbox:
>
> https://code.ros.org/svn/wg-ros-pkg/branches/trunk_cturtle/sandbox/pr2_spring_transmission_example
>  John
>
>
> On Wed, Dec 15, 2010 at 4:08 PM, John Hsu <johnhsu at willowgarage.com>wrote:
>
>> Hi Jeroen,
>>
>> Thanks for the updated description, though I think I might understand the
>> gist of the problem, can you attach a diagram as well?
>>
>> To briefly describe what I think you are modeling here, the motor output
>> has it's own degree of freedom and an encoder attached to the motor output
>> position, independent of the leg joint's degree of freedom.   In addition,
>> the motor dof and the leg joint dof are coupled by a spring-like link
>> mechanism?
>>
>> One way to do this is to model the spring dynamics in transmission.  To do
>> this, you can model the two joints independently, and specify a transmission
>> that applies the right amount of torque on the leg joint based on joint
>> position differences between motor output joint and leg joint.  In the
>> attached package, I created a simple urdf with two joints
>> (motor_output_joint and leg_joint).  leg_joint is connected to
>> motor_output_joint via something called a SpringTransmission.  Basically,
>> motor_output_joint can potentially be controlled by one of the mechanism
>> controllers (e.g. Joint Effort Controller<http://www.ros.org/wiki/robot_mechanism_controllers/JointEffortController>,
>> Joint Velocity Controller or
>> <http://www.ros.org/wiki/robot_mechanism_controllers/JointVelocityController>Joint
>> Position Controller<http://www.ros.org/wiki/robot_mechanism_controllers/JointPositionController>)
>> while the position difference between motor_output_joint and leg_joint
>> dictates the amount of torque to be applied to the leg_joint.
>> Does that sound about right?
>>
>> You can see the spring joint in action by:
>>
>> roslaunch pr2_spring_transmission_example spring_link.launch
>>
>> and in a separate terminal:
>>
>> rostopic pub /test_controller/command std_msgs/Float64 0.5
>>
>> John
>>
>>
>>
>>
>> On Wed, Dec 15, 2010 at 4:02 AM, Jeroen Willems <jjpa.willems at gmail.com>wrote:
>>
>>> To problem can be simplified to a motor which is connected through a
>>> ~20cm axis with a joint. Both, the motor and joint, are having position
>>> encoders.
>>> We assume that the main dynamics of the axis (the transmission) can be
>>> modeled as a linear spring ( T_spring = k * (theta_joint - theta_motor) ).
>>>
>>> This problem is probably also due the fact I'm have problems
>>> understanding the mechnism_model. I'm used to that the controller is getting
>>> a joint error, it outputs a control signal to the robot (torque applied to
>>> the motor for instance). So the mechanism_model is somewhat confusing to me
>>> because you put the effort directly on the joints and then via a
>>> transmission the effort on the actuator is determined. If I get it
>>> correctly.
>>>
>>> I'm using an hexapod so imagine that if you eventually want to jump, you
>>> want to use the kinetic energy of the springs.  When landing you also want
>>> to use the
>>> springs to reduce the impact on the robot by obtaining a part of the
>>> energy.
>>>
>>> Jeroen
>>>
>>>
>>>
>>> On Tue, Dec 14, 2010 at 23:39, Stuart Glaser <sglaser at willowgarage.com>wrote:
>>>
>>>> Hi Jeroen,
>>>>
>>>> Could you describe what you're trying to model in more detail?  In
>>>> particular, where are the encoders, motors, springs, gears, and joints
>>>> in relation to each other?
>>>>
>>>> -Stu
>>>>
>>>> On Tue, Dec 14, 2010 at 4:37 AM, Jeroen Willems <jjpa.willems at gmail.com>
>>>> wrote:
>>>> > Okay I'm looking into the flexibility between the actuator and the
>>>> joint by
>>>> > adding a custom transmission but I'm having some difficulties.
>>>> >
>>>> > I've looked into the existing transmissions and those are pretty
>>>> > straightforward (except for the pr2_gripper).
>>>> > I want to add the (linear, rotational) flexibility, I will neglect the
>>>> > damping for simplicity.
>>>> > I'm used to use the equations of motion:
>>>> > Load:  Jl theta_L_ddot + k ( theta_L - theta_M ) = 0
>>>> > Motor: Jm theta_M_ddot - k ( theta_L - theta_M ) = u
>>>> >
>>>> > I don't get it how to implement this in the transmission. I was
>>>> thinking of
>>>> > a little bit of rewriting as in the attachment but it did not
>>>> influence
>>>> > anything at all.
>>>> > Would be great if someone has an idea, solution or suggestion on how
>>>> > implementing this flexibility.
>>>> >
>>>> > Thanks in advance
>>>> >
>>>> > Jeroen
>>>> >
>>>> > On Sat, Nov 20, 2010 at 21:07, Stuart Glaser <
>>>> sglaser at willowgarage.com>
>>>> > wrote:
>>>> >>
>>>> >> Hi Joeren,
>>>> >>
>>>> >> For both of these, the solution is to write a transmission.  Both
>>>> >> issues require a specific translation between actuators and joints,
>>>> >> and the best way to encode that translation is in a transmission.
>>>> >>
>>>> >> -Stu
>>>> >>
>>>> >> On Fri, Nov 19, 2010 at 1:36 AM, Jeroen Willems <
>>>> jjpa.willems at gmail.com>
>>>> >> wrote:
>>>> >> > Hi All,
>>>> >> >
>>>> >> > I'm currently modeling a hexapod in Gazebo but I'm currently having
>>>> some
>>>> >> > difficulties.
>>>> >> >
>>>> >> > I have basically 2 questions, I hope that this is not a problem for
>>>> one
>>>> >> > post
>>>> >> > but both have to do with the transmission:
>>>> >> >
>>>> >> > 1) Between the actuators and the joints are torsion springs. I
>>>> haven't
>>>> >> > found
>>>> >> > something that incorporates flexibility between actuators and
>>>> joints.
>>>> >> > Is there some solution or workaround to obtain this or should I try
>>>> an
>>>> >> > alternative solution like writing a custom transmission?
>>>> >> >
>>>> >> > 2) As you can imagine I have 6 legs consisting of three links,
>>>> basically
>>>> >> > an
>>>> >> > elbow manipulator.
>>>> >> > The last two links can be regarded as in a 2D-plane. The third link
>>>> is
>>>> >> > remotely driven.
>>>> >> > This means that when rotating the second link the third link does
>>>> not
>>>> >> > change
>>>> >> > the rotation with respect to the body.
>>>> >> > So in a 'standard' situation the third link rotates with the second
>>>> link
>>>> >> > so
>>>> >> > the angle between those two does not change.
>>>> >> > I hope this is a bit clear.
>>>> >> > So again is there some solution or workaround?
>>>> >> >
>>>> >> > Thanks!
>>>> >> >
>>>> >> > Jeroen
>>>> >> >
>>>> >> > _______________________________________________
>>>> >> > ros-users mailing list
>>>> >> > ros-users at code.ros.org
>>>> >> > https://code.ros.org/mailman/listinfo/ros-users
>>>> >> >
>>>> >> >
>>>> >>
>>>> >>
>>>> >>
>>>> >> --
>>>> >> Stuart Glaser
>>>> >> sglaser -at- willowgarage -dot- com
>>>> >> www.willowgarage.com
>>>> >> _______________________________________________
>>>> >> ros-users mailing list
>>>> >> ros-users at code.ros.org
>>>> >> https://code.ros.org/mailman/listinfo/ros-users
>>>> >
>>>> >
>>>> > _______________________________________________
>>>> > ros-users mailing list
>>>> > ros-users at code.ros.org
>>>> > https://code.ros.org/mailman/listinfo/ros-users
>>>> >
>>>> >
>>>>
>>>>
>>>>
>>>> --
>>>> Stuart Glaser
>>>> sglaser -at- willowgarage -dot- com
>>>> www.willowgarage.com
>>>> _______________________________________________
>>>> ros-users mailing list
>>>> ros-users at code.ros.org
>>>> https://code.ros.org/mailman/listinfo/ros-users
>>>>
>>>
>>>
>>
>
-------------- next part --------------
An HTML attachment was scrubbed...
URL: <http://lists.ros.org/pipermail/ros-users/attachments/20101216/5ed34aba/attachment-0003.html>


More information about the ros-users mailing list