Skip to content

Commit

Permalink
add VFC state message (#62)
Browse files Browse the repository at this point in the history
  • Loading branch information
marioprats authored Sep 30, 2024
1 parent a047556 commit 7ace33d
Show file tree
Hide file tree
Showing 2 changed files with 28 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@ rosidl_generate_interfaces(
"msg/AdmittanceParameters.msg"
"msg/CartesianSelectionVector.msg"
"msg/VelocityForceCommand.msg"
"msg/VelocityForceControllerState.msg"
"srv/ConfigureVelocityForceController.srv"
DEPENDENCIES
action_msgs
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
# This message contains information about the internal state of the VelocityForceController.

# Timestamps associated to this state.
std_msgs/Header header

# Joint names associated to the controller.
# The order of the names is the same as the order of the joint positions, velocities and accelerations.
string[] joint_names

# The reference joint-space positions, velocities and accelerations, as computed by the setpoint generator.
float64[] reference_joint_positions
float64[] reference_joint_velocities
float64[] reference_joint_accelerations

# The current joint-space positions, velocities and accelerations, reported by the HW interface, or estimated internally.
float64[] joint_positions
float64[] joint_velocities
float64[] joint_accelerations

# The reference Cartesian pose, velocity and acceleration, as computed by the setpoint generator.
geometry_msgs/Pose reference_cartesian_pose
geometry_msgs/Twist reference_cartesian_velocity
geometry_msgs/Twist reference_cartesian_acceleration

# The current Cartesian pose and velocity, reported by the HW interface, or estimated internally.
geometry_msgs/Pose cartesian_pose
geometry_msgs/Twist cartesian_velocity

0 comments on commit 7ace33d

Please sign in to comment.