author | date |
---|---|
a.whit ([email protected]) |
May 2022 |
The Force Dimension SDK documentation describes gravity compensation as follows:
To prevent user fatigue and to increase accuracy during manipulation, Force Dimension haptic devices features gravity compensation. When gravity compensation is enabled, the weights of the arms and of the end-effector are taken into account and a vertical force is dynamically applied to the end-effector on top of the user command. Please note that gravity compensation is computed on the host computer, and therefore only gets applied whenever a force command is sent to the device by the application.
The Force Dimension ROS2 node allows for the configuration of gravity compensation via ROS2 parameters.
Gravity compensation is controlled via two parameters: gravity_compensation
and effector_mass_kg
. The gravity_compensation
parameter is a Boolean
value that simply determines whether or not gravity compensation is enabled.
The effector_mass_kg
defines the mass of the robotic end-effector, in
kilograms. This value is used by the Force Dimension SDK to compute a
compensatory force.1 The default value is reported by the Force
Dimension node during startup configuration, and is recorded to the text
log. The default value for the Novint Falcon is 0.190
. The default value
for the delta.3 is 0.279
.
The following is a sample YAML configuration file for setting the gravity compensation parameters:
/robot/force_dimension:
ros__parameters:
gravity_compensation: true
effector_mass_kg: 0.279
Both parameters trigger an update of the robot's configuration immediately, but the forces applied to the end effector do not change until a new command is issued. This is worth emphasizing: After a change in parameters, the compensatory forces applied to the robotic end effector are updated only after the next force command is issued to the robot.
Gravity compensation is most effective when the effector_mass_kg
parameter
is close to the true mass of the robotic endpoint effector. When the parameter
setting is slightly less than the true value, the robot can be expected to
descend at a slower pace than it would without compensation. When the parameter
setting is slightly higher than the true value, the effector will rise.
Identifying the optimal parameter value may require some trial-and-error
calibration, if the mass of the effector is
uncertain.
In a configured ROS2 environment, run the Force Dimension node:
ros2 run force_dimension node
During initialization, the node will report the configured effector mass. For
this example, a mass of 0.190
kg will be assumed.
In a second configured environment, simulate reduced-gravity by increasing the
effector mass by 25% (0.190 * 1.25 = 0.2375
):
ros2 param set /robot/force_dimension effector_mass_kg 0.2375
In the first ROS2 environment, the Force Dimension should report this parameter change to the log. However, the parameter change has no effect until a force command is delivered to the robot. To trigger the gravity compensation update, send a force command:
ros2 topic pub --once /robot/command/force geometry_msgs/msg/Vector3 \
"{x: 0.0, y: 0.0, z: 0.0}"
At this point, the robot can be considered to be operating within a simulated physical environment, in which gravity has been reduced by 25%. Depending on the robot, and how it is set up, this might cause the end effector to rise toward the top of the workspace. If this does not happen, then increase the effector mass parameter by small increments -- re-issuing the force command for each parameter change -- until the end effector is observed to move upward.
To confirm the effect, disable gravity compensation:
ros2 param set /robot/force_dimension gravity_compensation false
For this parameter change to take effect, a force command must be issued to the robot, as before. Be prepared to catch the end effector when the change takes effect. With gravity compensation disabled, the force of gravity will typically cause the robotic effector to drop.
Footnotes
-
The effector mass is set via the dhdSetEffectorMass function in the Force Dimension SDK. Gravity compensation is enabled via the dhdSetGravityCompensation function. ↩