Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Position part of force_torque sensor pose is ignored and this may be confusing or impractical #130

Open
osrf-migration opened this issue Oct 30, 2016 · 5 comments
Labels
bug Something isn't working major

Comments

@osrf-migration
Copy link

Original report (archived issue) by Silvio Traversaro (Bitbucket: traversaro).


TL; DR: There is bug in Valkyrie F/T sensor model that could cause up to 20 Nm of error between the simulated F/T measure and the real one.

Back in https://bitbucket.org/osrf/gazebo/issues/940/force-torque-sensor-forcetorquesensorcc , the semantics for force_torque sensor pose tag was defined.

In particular it was decided (probably for back-compatibility) that the point with respect to which the measured torque is expressed was always the origin of the "joint" frame, regardless of the sensor pose and of the frame tag (see https://bitbucket.org/osrf/gazebo/issues/940/force-torque-sensor-forcetorquesensorcc#comment-9473056).

Personally I was ok with this, because I always modeled six axis force torque sensors as "fixed" joints (as described in https://bitbucket.org/osrf/gazebo/issues/940/force-torque-sensor-forcetorquesensorcc#comment-9485945), for which the origin of the joint frame can be freely assigned without any other constraint.

However recently I was porting some estimation software to the Walkman robot ( https://www.walk-man.eu/ ) and I noticed that in building their SDF they choose a different option: they modeled their F/T sensors as sensors measuring the force transmitted over a non-fixed joint. The Walkman model is not public, but then I noticed that the same choice was done in the SDF of the Valkyrie robot, see for example:

    <gazebo reference="${joint_to_attach_sensor_to}">
      <sensor name="${sensorName}" type="force_torque">
        <pose>${origin_xyz} ${origin_rpy}</pose>
        <sensor_number id="${sensor_number}" />
        <node id="${sensor_node}" />
        <api name="${sensor_api}" />
        <always_on>true</always_on>
        <update_rate>500.0</update_rate>
        <force_torque>
          <frame>sensor</frame>
          <measure_direction>parent_to_child</measure_direction>
        </force_torque>
    	</sensor>
    </gazebo>

See https://gitlab.com/nasa-jsc-robotics/val_description/blob/master/model/robots/common/xacro/sensors/ati_force_torque.xacro#L16 .

As in the case of the Walkman, even here the force_torque sensor is instantiated with a non-zero origin_xyz in

<xacro:ati_force_torque_sensor sensorName="${prefix}FootSixAxis"
                               parentLink="${AnkleRollLinkName}"
                               joint_to_attach_sensor_to="${AnkleRollJointName}"                          
                               origin_xyz="0.0215646 0.0 -0.051054"                        
                               origin_rpy="3.14 0.0 0.0"                
                               sensor_number="${ATI_serial_number}"                                
                               sensor_node="${ATI_node}"                           
                               sensor_api="${ForceTorqueSensorApi}" />

See https://gitlab.com/nasa-jsc-robotics/val_description/blob/master/model/robots/common/xacro/leg/leg.xacro#L173 .

Modelling the F/T sensor as attached to a non-fixed joint can make sense if the mass of the flange connecting the F/T sensor with its revolute joint is small enough and its weight and dynamical effect can be safely disregarded. However the presence of a non-fixed joints constraints the joint frame origin to be on the joint's revolution axis, and prevents to correctly simulate a sensor whose origin does not lie on the revolution axis. As far as I understood is the case in Walkman/Valkyrie, and the authors of those models tried to encode the position offset between the joint frame and the sensor frame using the sensor pose, apparently ignoring that the position part would be ignored.

I don't know if there is an easy way to fix this issue in these models. Two possible ways can be:

  • create a new value for the frame tag: a sensor_posandrot (better name preferable) that means that the sensor orientation is used to express the wrench, and the sensor origin is used as the point with respect to which the torque is expressed,

  • or considering that any model with a non-zero sensor position offset for a force_torque sensor is broken, we can just modify the definition of <frame>sensor</frame> to "the sensor orientation is used to express the wrench, and the sensor origin is used as the point with respect to which the torque is expressed".

@osrf-migration
Copy link
Author

Original comment by Silvio Traversaro (Bitbucket: traversaro).


  • Edited issue description

2 similar comments
@osrf-migration
Copy link
Author

Original comment by Silvio Traversaro (Bitbucket: traversaro).


  • Edited issue description

@osrf-migration
Copy link
Author

Original comment by Silvio Traversaro (Bitbucket: traversaro).


  • Edited issue description

@traversaro
Copy link
Contributor

The problem described in this issue created an error in FT sensor frame localization that went unnoticed for three years: icub-tech-iit/ergocub-software#146 .

@traversaro
Copy link
Contributor

Back in https://bitbucket.org/osrf/gazebo/issues/940/force-torque-sensor-forcetorquesensorcc , the semantics for force_torque sensor pose tag was defined.

In particular it was decided (probably for back-compatibility) that the point with respect to which the measured torque is expressed was always the origin of the "joint" frame, regardless of the sensor pose and of the frame tag (see https://bitbucket.org/osrf/gazebo/issues/940/force-torque-sensor-forcetorquesensorcc#comment-9473056).

Personally I was ok with this, because I always modeled six axis force torque sensors as "fixed" joints (as described in https://bitbucket.org/osrf/gazebo/issues/940/force-torque-sensor-forcetorquesensorcc#comment-9485945), for which the origin of the joint frame can be freely assigned without any other constraint.

I can't edit the original post as I don't have write permission on this repo, but updating the reference to working links this is:

Back in gazebosim/gazebo-classic#940 , the semantics for force_torque sensor pose tag was defined.

In particular it was decided (probably for back-compatibility) that the point with respect to which the measured torque is expressed was always the origin of the "joint" frame, regardless of the sensor pose and of the frame tag (see gazebosim/gazebo-classic#940 (comment)).

Personally I was ok with this, because I always modeled six axis force torque sensors as "fixed" joints (as described in gazebosim/gazebo-classic#940 (comment)), for which the origin of the joint frame can be freely assigned without any other constraint.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
bug Something isn't working major
Projects
None yet
Development

No branches or pull requests

2 participants