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.
- ft_sensor_frame
- Returns:
- Wrench
The gravity compensated wrench.
Notes
For more info, see [1].
References
[1]Vougioukas S., Bias Estimation and Gravity Compensation For Force-Torque Sensors, Available at: https://www.semanticscholar.org/paper/Bias-Estimation-and-Gravity-Compensation-For-Vougioukas/900c5de4ac54cf28df816584264fa0de71c4817f
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]) >>> x = w.gravity_compensated(f, mass, com) >>> print(x.force) Vector(x=0.000, y=0.000, z=0.066) >>> print(x.torque) Vector(x=0.000, y=0.000, z=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]) >>> x = w.gravity_compensated(f, mass, com) >>> print(x.force) Vector(x=0.000, y=0.000, z=0.066) >>> print(x.torque) Vector(x=-88.193, y=88.193, z=0.000)