ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
2

force frame of reference for gazebo ros bumper

asked 2011-08-24 21:11:33 -0500

GuiHome gravatar image

Hi,

I wanted to use the gazebo_ros_bumpers and retrieve the force vector for each contact. However, when drawing the vectors, it appears to me they are not in a correct reference frame.

I think, according to the comments in the source file (gazebo_ros_bumper.cpp), that the contact data (force, normal, point) are all given in the "user requested" frame of reference. I am using diamondback but this seems not to have changed in trunk version of the file. see :

I can see some coordinate frame change for the data in the source code but I cannot understand why some are using RotateVector (example force and torque)

// rotate into user specified frame. frame_rot is identity if world is used.
   Vector3 force = frame_rot.RotateVector( Vector3(contact.forces[k]. body1Force.x,

and some others are converted by RotateVectorReverse (position and normal).

// rotate normal into user specified frame. frame_rot is identity if world is used.
   Vector3 normal = frame_rot.RotateVectorReverse( Vector3(contact.normals[k].x,

with frame_rot the rotation transformation from local to global frame. To what I could read, forces and position are given by ODE in global coordinate system, so forces would need the same reverse transformation that position and normal require, but I may have missed something.

Changing both transformation to reverse seemed to show better force orientation when displayed but I cannot be totally sure as contact points are "varying a lot" due to bouncy contacts.

If any one has comments on this, it sure could help confirm the issue (or not), and I could then file a bug if required.

edit retag flag offensive close merge delete

Comments

Hi, are you running on diamondback or electric?
hsu gravatar image hsu  ( 2011-09-02 12:16:50 -0500 )edit
As mentionned in the question, I am running diamondback. I cannot switch to electric because the Shadow Hand dos not support it yet. But I verified the trunk version at the time of the question, and the code was the same for this part. In electric the code is still the same. Will try it again soon.
GuiHome gravatar image GuiHome  ( 2011-09-14 23:46:25 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2011-09-15 13:13:32 -0500

hsu gravatar image

Good point. I added a test world to check simple rotation, and plotting

rxplot -p 5 "box_bumper/state/states[0]/total_wrench/force/x" "box_bumper/state/states[0]/total_wrench/force/y" "box_bumper/state/states[0]/total_wrench/force/z" "box1_bumper/state/states[0]/total_wrench/force/x" "box1_bumper/state/states[0]/total_wrench/force/y" "box1_bumper/state/states[0]/total_wrench/force/z"

to found that RotateVectorReverse() appears to be the correct call to make in all instances. Please test and let me know if you conclude similarly? Thanks.

edit flag offensive delete link more

Comments

Test world is perfect. Without modif, rotating box1 shows wrong force on x & y. With Reverse everywhere, we get correct indication on each axis (positive if considered axis is upward, negative if downward). Other box keeps force positive on Z since bumper is on world frame. My patch was OK ! Thanks.
GuiHome gravatar image GuiHome  ( 2011-09-25 01:12:36 -0500 )edit
great! thanks for testing. I'll make a release soon.
hsu gravatar image hsu  ( 2011-09-25 06:47:54 -0500 )edit

Question Tools

Stats

Asked: 2011-08-24 21:11:33 -0500

Seen: 1,129 times

Last updated: Sep 15 '11