ODE Torque sensor + ODE and haptics

55 views
Skip to first unread message

Elvina Motard

unread,
Feb 7, 2008, 11:28:33 AM2/7/08
to ode-...@googlegroups.com
Dear all,

I am coming back again with my torque sensor... Just to quickly answer
to Daniele (about ODE and haptics), I am also using ODE in a haptic
research application ; my goal is to implement virtual worlds and
simulate the physics in order to compute a torque sensor on each joint.
I didn't succeed until now... but I am still trying.
So, here is my problem : I am using a motor, and I control it using a
torque. So in the dJointSetHingeParam function, I am passing a high
velocity and the torque that I want to reach. As far as I understood, I
think that when I look into the JointFeedback structure, what I get is
the torque that has really been applied by the motor. This is an
information that I need, but I would also need the reaction torques,
when I have a contact for instance. I already saw that I can get the
force that comes from a contact, on each joint, but I would like to get
those reaction torques... They should be computed somewhere...
I actually found a way to get them : if I put 0 as a desired velocity
(into dJointSetHingeParam), and a very high torque into dParamFmax, then
the system doesn't move, and if something collides with my system, I get
exactly the reaction torque (multiply by -1 because the system is
balanced, so my motors are compensating the reaction torque...) ; but
this is not a solution, it was just to test that the computation is done...

Thanks for your help,
Elvina

Daniel K. O.

unread,
Feb 7, 2008, 4:55:03 PM2/7/08
to ode-...@googlegroups.com
Elvina Motard escreveu:

> velocity and the torque that I want to reach. As far as I understood, I
> think that when I look into the JointFeedback structure, what I get is
> the torque that has really been applied by the motor. This is an
> information that I need, but I would also need the reaction torques,
> when I have a contact for instance.

Contact forces and torques will come from contact joints; so add a
feedback to them too.


--
Daniel K. O.
"The only way to succeed is to build success yourself"

Elvina Motard

unread,
Feb 8, 2008, 3:01:33 AM2/8/08
to ode-...@googlegroups.com
Yes, I've already done that, and I can see the force applied, but what I
would like to know is the torque generated in each joint of my
kinematics chain in response to this contact force.

Daniel K. O. wrote:
> Elvina Motard escreveu:
>
>> velocity and the torque that I want to reach. As far as I understood, I
>> think that when I look into the JointFeedback structure, what I get is
>> the torque that has really been applied by the motor. This is an
>> information that I need, but I would also need the reaction torques,
>> when I have a contact for instance.
>>
>
> Contact forces and torques will come from contact joints; so add a
> feedback to them too.
>
>
>
>
>


--
Elvina Motard
Robotics Engineer

Space Applications Services
Leuvensesteenweg 325, B-1932 Zaventem, Belgium
Tel: +32 2 721 54 84 Fax: +32 2 721 54 44
URL: http://www.spaceapplications.com

J.D.

unread,
Feb 8, 2008, 10:24:33 AM2/8/08
to ode-users
Elvina,

I have a guess how this is done in ODE, but how to access this
information I am not sure... and that may be your real question. But
as you may already know, calculating the joint torques due to an
external load (contact forces for your application) for any serial
link robot/device can be done using the manipulator jacobian:

tau = Jt * F

where tau are the joint torques, Jt is the transpose of the
manipulator jacobian, and F is the external force applied at the end
effector. Of course, it gets more complicated, if for example, you
want to calculated the reaction torques for contact forces applied to
links other than the last link. However, there are many, many
resources (aka libraries) for computing the manipulator jacobians for
arbitrary link mechanisms.



On Feb 8, 3:01 am, Elvina Motard <elvina.mot...@spaceapplications.com>
wrote:

Elvina Motard

unread,
Feb 8, 2008, 10:30:58 AM2/8/08
to ode-...@googlegroups.com
Thanks for your answer, my question is actually on how to access this
information. I already thought about computing the jacobian, but it gets
more complicated when contacts don't occur at the end effector. Do you
have any example of resources that could be helpful to me ?
Thanks

J.D.

unread,
Feb 8, 2008, 4:01:28 PM2/8/08
to ode-users
Elvina,

No. Not any examples with ODE. If you are working with a serial link
mechanism and can describe that mechanism in terms of DH parameters,
then a library like ROBOOP (http://www.cours.polymtl.ca/roboop/) can
compute the jacobian for any link of the mechanism. Of course, that
jacobian will be computed for the joint centers of each link. So
contact forces will have be translated from arbitrary positions on the
link to the link's joint center.

I actually implemented something like this for a potential field
navigation demo. I looped through each link of my mechanism, computed
its jacobian, summed the external forces for that link, and then
computed the resultant joint torques. Using ROBOOP this task was
fairly easy to program and it worked pretty well.

Sorry I can not provide any help using ODE for this task. Similar
calculations are being done under the covers but I am not sure how to
access it or even if the developer(s) allow access to that
information.

J.D.


On Feb 8, 10:30 am, Elvina Motard

J.D.

unread,
Feb 8, 2008, 4:01:47 PM2/8/08
to ode-users
Elvina,

No. Not any examples with ODE. If you are working with a serial link
mechanism and can describe that mechanism in terms of DH parameters,
then a library like ROBOOP (http://www.cours.polymtl.ca/roboop/) can
compute the jacobian for any link of the mechanism. Of course, that
jacobian will be computed for the joint centers of each link. So
contact forces will have be translated from arbitrary positions on the
link to the link's joint center.

I actually implemented something like this for a potential field
navigation demo. I looped through each link of my mechanism, computed
its jacobian, summed the external forces for that link, and then
computed the resultant joint torques. Using ROBOOP this task was
fairly easy to program and it worked pretty well.

Sorry I can not provide any help using ODE for this task. Similar
calculations are being done under the covers but I am not sure how to
access it or even if the developer(s) allow access to that
information.

J.D.


On Feb 8, 10:30 am, Elvina Motard

Gazi Alankus

unread,
Feb 12, 2008, 5:31:02 PM2/12/08
to ode-...@googlegroups.com
If I may jump in, calculating Jacobian for an articulated robot with
hinge joints is pretty straightforward and does not require DH params.
Let's say body E and body B are connected through a series of hinge
joints and we want to calculate the Jacobian matrices Jv and Jw. Jv
relates the joint angle speeds to the linear velocity of a selected
point P on body E relative to body B. Jw relates the joint angle
speeds to the angular velocity of body E relative to body B. Each
column of Jv is the cross product of a unit hinge joint axis and the
distance of P to that hinge joint axis. Jw's columns are the unit
hinge joint axes. That's about it really. Once you order your joint
angle speed vector thetadot to match the corresponding axes, you have
v_P = Jv . thetadot and w_E = Jw . thetadot where v_P is the linear
velocity of the point P that is attached to E and v_P is relative to
B. w_E is E's angular velocity relative to B.

I thought this could save some headache from messing with DH params.

-Gazi

Elvina Motard

unread,
Mar 10, 2008, 10:04:44 AM3/10/08
to ode-...@googlegroups.com
Thank you for your answers and sorry for this late reply.
Regarding my issue, I would really like to find a solution using ODE.
This information has to be computed into ODE's source code. The problem
with computing it all again is that it will take too much time for my
application.

I actually downloaded the SVN version of ODE and looked a bit into it.
There are lots of details I don't understand, but I think it is located
into step.cpp, in the function dInternalStepIsland_x2. Is there anybody
who participated to the development of this function that could help me,
finding out the information of how much torque is acting on each joint
as a result of a contact on a joint chain ? I don't need you to modify
ODE so that I can access this information, I would just like to know
where this information is and then I would be able to make my own
version of ODE.

Thank you,
Elvina

Elvina Motard

unread,
Mar 18, 2008, 11:12:21 AM3/18/08
to ode-...@googlegroups.com
Dear Gazi and J.D.,

Thank you for your help regarding the torque torque sensor computing.
Finally, I gave up looking through ODE code to find a solution (I don't
have enough time to understand it all...) and I did like Gazi said, i.e.
I didn't compute the jacobian using the DH parameters, but I build it
using the hinges axis and the distance between the anchor and the
contact point. It is working well, and is fast to compute, so thank you
both !

Elvina

Reply all
Reply to author
Forward
0 new messages