Wrench.gravity_compensated

Wrench.gravity_compensated(ft_sensor_frame, mass, center_of_mass)[source]

Removes the force and torque in effect of gravity from the wrench.

Parameters
  • ft_sensor_frame (compas.geometry.Frame) – The coordinate frame of the force torque sensor.

  • mass (float) – The mass of the object in kg.

  • center_of_mass (Point) – The center of mass of the object in meters.

Returns

Wrench – The gravity compensated wrench.

Examples

>>> mass, com = 10, [0, 0, 1]
>>> f = Frame([0, 0, 0], [1, 0, 0], [0, 1, 0])
>>> w = Wrench([0, 0, -98], [0, 0, 0])
>>> w.gravity_compensated(f, mass, com)
Wrench(Vector(0.000, 0.000, 0.066), Vector(0.000, 0.000, 0.000))
>>> mass, com = 10, [1, 1, 1]
>>> f = Frame([0, 0, 0], [1, 0, 0], [0, 1, 0])
>>> w = Wrench([0, 0, -98], [-98, 98, 0])
>>> w.gravity_compensated(f, mass, com)
Wrench(Vector(0.000, 0.000, 0.066), Vector(-88.193, 88.193, 0.000))

Notes

For more info, see 1.

References

1

Vougioukas S., Bias Estimation and Gravity Compensation For Force-Torque Sensors, Available at: http://citeseerx.ist.psu.edu/viewdoc/summary?doi=10.1.1.552.109.