Skip to content

Commit

Permalink
Merge branch 'master' into rm/iron
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich authored Nov 18, 2024
2 parents 248945d + 94da4d9 commit e830742
Show file tree
Hide file tree
Showing 6 changed files with 22 additions and 1 deletion.
6 changes: 6 additions & 0 deletions control_msgs/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,12 @@
Changelog for package control_msgs
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

5.3.0 (2024-11-18)
------------------
* Add Dynamic Interface Group Values message (`#155 <https://github.com/ros-controls/control_msgs/issues/155>`_)
* Add speed_scaling_factor msg and field in JointTrajectoryControllerState (`#143 <https://github.com/ros-controls/control_msgs/issues/143>`_)
* Contributors: Felix Exner (fexner), Wiktor Bajor

5.2.0 (2024-06-10)
------------------
* Add message for publishing interface values with name and stamp (`#98 <https://github.com/ros-controls/control_msgs/issues/98>`_)
Expand Down
2 changes: 2 additions & 0 deletions control_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@ find_package(trajectory_msgs REQUIRED)

set(msg_files
msg/AdmittanceControllerState.msg
msg/DynamicInterfaceGroupValues.msg
msg/DynamicInterfaceValues.msg
msg/DynamicJointState.msg
msg/GripperCommand.msg
Expand All @@ -37,6 +38,7 @@ set(msg_files
msg/SingleDOFState.msg
msg/SingleDOFStateStamped.msg
msg/SteeringControllerStatus.msg
msg/SpeedScalingFactor.msg
)

set(action_files
Expand Down
6 changes: 6 additions & 0 deletions control_msgs/msg/DynamicInterfaceGroupValues.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
std_msgs/Header header

# List of interface group names , e.g. ["flange_analog_IOs", "flange_vacuum"]
string[] interface_groups
# Key-value pairs representing interfaces and their corresponding values for each interface group listed in `interface_groups`
InterfaceValue[] interface_values
2 changes: 2 additions & 0 deletions control_msgs/msg/JointTrajectoryControllerState.msg
Original file line number Diff line number Diff line change
Expand Up @@ -22,3 +22,5 @@ trajectory_msgs/MultiDOFJointTrajectoryPoint multi_dof_feedback
trajectory_msgs/MultiDOFJointTrajectoryPoint multi_dof_error
# Current output of the controller.
trajectory_msgs/MultiDOFJointTrajectoryPoint multi_dof_output
# The speed scaling factor the trajectory is currently being executed with
float64 speed_scaling_factor
5 changes: 5 additions & 0 deletions control_msgs/msg/SpeedScalingFactor.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
# This message contains a scaling factor to scale trajectory execution. A factor of 1.0 means
# execution at normal speed, a factor of 0.0 means a full pause.
# Negative values are not allowed (Which should be checked by any instance consuming this message).

float64 factor
2 changes: 1 addition & 1 deletion control_msgs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>control_msgs</name>
<version>5.2.0</version>
<version>5.3.0</version>
<description>
control_msgs contains base messages and actions useful for
controlling robots. It provides representations for controller
Expand Down

0 comments on commit e830742

Please sign in to comment.