Skip to content

Commit

Permalink
Propose generic messages for commanding and getting states from contr…
Browse files Browse the repository at this point in the history
…ollers. (backport #69) (#133)

* Add generic messages for commanding and getting states from controllers. (#69)

(cherry picked from commit d24165f)

---------

Co-authored-by: Dr. Denis <[email protected]>
Co-authored-by: Christoph Fröhlich <[email protected]>
  • Loading branch information
3 people authored Jun 6, 2024
1 parent 529a864 commit 0e13063
Show file tree
Hide file tree
Showing 6 changed files with 56 additions and 0 deletions.
4 changes: 4 additions & 0 deletions control_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,11 @@ set(msg_files
msg/JointTolerance.msg
msg/JointTrajectoryControllerState.msg
msg/MecanumDriveControllerState.msg
msg/MultiDOFCommand.msg
msg/MultiDOFStateStamped.msg
msg/PidState.msg
msg/SingleDOFState.msg
msg/SingleDOFStateStamped.msg
msg/SteeringControllerStatus.msg
)

Expand Down
2 changes: 2 additions & 0 deletions control_msgs/msg/JointControllerState.msg
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
# This message presents current controller state of one joint.

# It is deprecated as of Humble in favor of SingleDOFStateStamped.msg

# Header timestamp should be update time of controller state
std_msgs/Header header

Expand Down
13 changes: 13 additions & 0 deletions control_msgs/msg/MultiDOFCommand.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
# The message defines command for multiple degrees of freedom (DoF) typically used by many controllers.
# The message intentionally avoids 'joint' nomenclature because it can be generally use for command with
# different semantic meanings, e.g., joints, Cartesian axes, or have abstract meaning like GPIO interface.

# names of degrees of freedom
string[] dof_names

# values used by most of the controller
float64[] values

# First derivation of the values, e.g., velocity if values are positions.
# This is useful for PID and similar controllers.
float64[] values_dot
6 changes: 6 additions & 0 deletions control_msgs/msg/MultiDOFStateStamped.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
# This message presents current controller state of multiple degrees of freedom.

# Header timestamp should be update time of controller state
std_msgs/Header header

SingleDOFState[] dof_states
25 changes: 25 additions & 0 deletions control_msgs/msg/SingleDOFState.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
# This message presents current controller state of one degree of freedom.

# DoF name, e.g., joint or Cartesian axis name
string name

# The set point, that is, desired state.
float64 reference

# Current value of the process (ie: latest sensor measurement on the controlled value).
float64 feedback

# First time-derivative of the process value. E.g., velocity.
float64 feedback_dot

# The error of the controlled value, essentially process_value - set_point (for a regular PID implementation).
float64 error

# First time-derivative of the error of the controlled value.
float64 error_dot

# Time between two consecutive updates/execution of the control law.
float64 time_step

# Current output of the controller.
float64 output
6 changes: 6 additions & 0 deletions control_msgs/msg/SingleDOFStateStamped.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
# This message presents current controller state of one degree of freedom.

# Header timestamp should be update time of controller state
std_msgs/Header header

SingleDOFState dof_state

0 comments on commit 0e13063

Please sign in to comment.