From fad8023dab259af6add082e31e063eb36b817006 Mon Sep 17 00:00:00 2001 From: AndyZe Date: Wed, 19 May 2021 15:02:29 -0500 Subject: [PATCH] Rename force->wrench --- control_msgs/msg/AdmittanceControllerState.msg | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/control_msgs/msg/AdmittanceControllerState.msg b/control_msgs/msg/AdmittanceControllerState.msg index d461957..c7ad1d2 100644 --- a/control_msgs/msg/AdmittanceControllerState.msg +++ b/control_msgs/msg/AdmittanceControllerState.msg @@ -1,14 +1,14 @@ -geometry_msgs/WrenchStamped input_force_command #commanded input force for the controller +geometry_msgs/WrenchStamped input_wrench_command #commanded input wrench for the controller geometry_msgs/PoseStamped input_pose_command #commanded input pose for the controller trajectory_msgs/JointTrajectory input_joint_command # commanded input JointTrajectory (used only first point) -geometry_msgs/WrenchStamped input_force_control_frame # input force transformed into control frame +geometry_msgs/WrenchStamped input_wrench_control_frame # input wrench transformed into control frame geometry_msgs/PoseStamped input_pose_control_frame # input pose transformed into control frame -geometry_msgs/WrenchStamped measured_force # measured force from the sensor (sensor frame) -geometry_msgs/WrenchStamped measured_force_filtered # measured force after low-pass and gravity compensation filters in sensor frame -geometry_msgs/WrenchStamped measured_force_control_frame # transformed measured force to control frame -geometry_msgs/WrenchStamped measured_force_endeffector_frame # measured force transformed to endeffector +geometry_msgs/WrenchStamped measured_wrench # measured wrench from the sensor (sensor frame) +geometry_msgs/WrenchStamped measured_wrench_filtered # measured wrench after low-pass and gravity compensation filters in sensor frame +geometry_msgs/WrenchStamped measured_wrench_control_frame # transformed measured wrench to control frame +geometry_msgs/WrenchStamped measured_wrench_endeffector_frame # measured wrench transformed to endeffector geometry_msgs/PoseStamped desired_pose # goal pose to send to the robot geometry_msgs/TransformStamped relative_desired_pose # relative pose from the actual pose as result of the admittance rule