Skip to content
Snippets Groups Projects
Commit 102c6a02 authored by Younes Oubkis's avatar Younes Oubkis
Browse files

submodule

parent 98fab1d9
Branches
No related tags found
No related merge requests found
Showing
with 482 additions and 1 deletion
control_msgs @ 36e2e305
Subproject commit 36e2e30551e3f2bfd9e55fca553f1ef019f4e4b1
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Changelog for package control_msgs
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
5.0.0 (2023-04-28)
------------------
* Update JTC state message (`#86 <https://github.com/ros-controls/control_msgs/issues/86>`_)
* Contributors: Christoph Fröhlich
4.3.0 (2023-04-02)
------------------
* Add generic messages for commanding and getting states from controllers. (`#69 <https://github.com/ros-controls/control_msgs/issues/69>`_)
* Contributors: Dr. Denis
4.2.0 (2023-03-22)
------------------
* Add state message for mechanum controller #79
* Status message for steering controllers
* Contributors: Denis Štogl, GiridharBukka, petkovich
4.1.0 (2022-10-19)
------------------
* Add status admittance controller message (`#68 <https://github.com/ros-controls/control_msgs/issues/68>`_)
* Contributors: Paul Gesel
4.0.0 (2022-08-01)
------------------
* Added controller states for multi dof joints (`#64 <https://github.com/ros-controls/control_msgs/issues/64>`_)
* Add initial configurations for multiple distros. (`#59 <https://github.com/ros-controls/control_msgs/issues/59>`_)
* Add CI configuration with multiple ROS distributions and use pre-commit in the repository.
* Add badges
* Contributors: Denis Štogl, George Stavrinos
3.0.0 (2021-05-27)
------------------
* Extend FollowJointTrajectoryAction with multi_dof_trajectory variable
https://github.com/ros-controls/control_msgs/pull/55
* Refractor dependency list for better overview.
* Contributors: Bence Magyar, David V. Lu, Denis Štogl, JafarAbdi
2.5.0 (2021-01-22)
------------------
* Extend QueryTrajectoryState to allow to report errors
* Contributors: Victor Lopez
2.4.1 (2020-08-01)
------------------
* Move author field lower in package.xml
* Don't define C standard
* Define package.xml schema for validator
* depend -> build_depend, exec_depend
* Contributors: Bence Magyar, ahcorde
2.4.0 (2020-07-03)
------------------
* Add std_msgs prefix path to header
* Add JointJog msg to ROS 2 - foxy
* Contributors: AdamPettinger, AndyZe
2.3.0 (2020-05-16)
------------------
* Implement "flexible joint states" message: add DynamicJointState message
* add description of JointControllerState.msg (`#30 <https://github.com/ros-controls/control_msgs/issues/30>`_) (`#39 <https://github.com/ros-controls/control_msgs/issues/39>`_)
* Contributors: Bence Magyar
2.2.0 (2019-09-09)
------------------
* generate action interfaces
* Contributors: Mathias Lüdtke
2.1.0 (2019-01-29)
------------------
* Fix up dependencies for actionlib and Crystal
* Contributors: Bence Magyar
2.0.0 (2019-01-25)
------------------
* ROS2 Bouncy conversion
* Replace Adolfo with Bence as maintainer
* Contributors: Austin Deric, Bence Magyar, Nestor Gonzalez
1.4.0 (2016-04-15)
------------------
* Add antiwindup to JointControllerState message definition
* Add PidState message
* Contributors: Paul Bovbel
1.3.1 (2015-03-05)
------------------
* Export architecture_independent flag in package.xml
* Change package maintainer.
* Contributors: Adolfo Rodriguez Tsouroukdissian, Scott K Logan
1.3.0 (2014-02-27)
------------------
* Add error_string to action result.
* Contributors: Adolfo Rodriguez Tsouroukdissian
1.2.0 (2013-04-25)
------------------
1.1.6 (2013-02-11)
------------------
* adds missing feedback field to PointHeadAction
* Contributors: Adam Leeper
1.1.5 (2013-01-23)
------------------
* changes PointHeadAction.action to PointHead.action
* Contributors: Adam Leeper
1.1.4 (2013-01-22)
------------------
* this now contains all messages, services and actions that used to be in ros_controllers and/or pr2_controllers_msgs
* copy JointControllerState and JointTrajectoryControllerState from pr2_controllers_msgs
* copy GripperCommand from pr2_controllers_msgs
* modified dep type of catkin
* Contributors: Dirk Thomas, Ioan Sucan
1.1.3 (2012-12-13)
------------------
* fix dep
* add missing downstream depend
* switched from langs to message_* packages
* Contributors: Dirk Thomas
1.1.2 (2012-12-03)
------------------
1.1.1 (2012-11-19 15:52)
------------------------
* added metapackage for backward compatibility
* Contributors: Ioan Sucan
1.1.0 (2012-11-19 14:54)
------------------------
* port to catkin
* add bogus dependency on rospy, to get ros_comm
* Added documentation for the FollowJointTrajectory action and the JointTolerance message.
* Added PointHeadAction to control_msgs
* First cut at a FollowJointTrajectory action
* Contributors: Brian Gerkey, Ioan Sucan, Stuart Glaser
cmake_minimum_required(VERSION 3.5)
project(control_msgs)
# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
find_package(action_msgs REQUIRED)
find_package(ament_cmake REQUIRED)
find_package(builtin_interfaces REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(rosidl_default_generators REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(std_msgs REQUIRED)
find_package(trajectory_msgs REQUIRED)
set(msg_files
msg/AdmittanceControllerState.msg
msg/DynamicJointState.msg
msg/GripperCommand.msg
msg/InterfaceValue.msg
msg/JointComponentTolerance.msg
msg/JointControllerState.msg
msg/JointJog.msg
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
)
set(action_files
action/FollowJointTrajectory.action
action/GripperCommand.action
action/JointTrajectory.action
action/PointHead.action
action/SingleJointPosition.action
)
set(srv_files
srv/QueryCalibrationState.srv
srv/QueryTrajectoryState.srv
)
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
endif()
rosidl_generate_interfaces(${PROJECT_NAME}
${action_files}
${msg_files}
${srv_files}
DEPENDENCIES
action_msgs
builtin_interfaces
geometry_msgs
sensor_msgs
std_msgs
trajectory_msgs
ADD_LINTER_TESTS
)
ament_export_dependencies(rosidl_default_runtime)
ament_package()
# The trajectory for all revolute, continuous or prismatic joints
trajectory_msgs/JointTrajectory trajectory
# The trajectory for all planar or floating joints (i.e. individual joints with more than one DOF)
trajectory_msgs/MultiDOFJointTrajectory multi_dof_trajectory
# Tolerances for the trajectory. If the measured joint values fall
# outside the tolerances the trajectory goal is aborted. Any
# tolerances that are not specified (by being omitted or set to 0) are
# set to the defaults for the action server (often taken from the
# parameter server).
# Tolerances applied to the joints as the trajectory is executed. If
# violated, the goal aborts with error_code set to
# PATH_TOLERANCE_VIOLATED.
JointTolerance[] path_tolerance
JointComponentTolerance[] component_path_tolerance
# To report success, the joints must be within goal_tolerance of the
# final trajectory value. The goal must be achieved by time the
# trajectory ends plus goal_time_tolerance. (goal_time_tolerance
# allows some leeway in time, so that the trajectory goal can still
# succeed even if the joints reach the goal some time after the
# precise end time of the trajectory).
#
# If the joints are not within goal_tolerance after "trajectory finish
# time" + goal_time_tolerance, the goal aborts with error_code set to
# GOAL_TOLERANCE_VIOLATED
JointTolerance[] goal_tolerance
JointComponentTolerance[] component_goal_tolerance
builtin_interfaces/Duration goal_time_tolerance
---
int32 error_code
int32 SUCCESSFUL = 0
int32 INVALID_GOAL = -1
int32 INVALID_JOINTS = -2
int32 OLD_HEADER_TIMESTAMP = -3
int32 PATH_TOLERANCE_VIOLATED = -4
int32 GOAL_TOLERANCE_VIOLATED = -5
# Human readable description of the error code. Contains complementary
# information that is especially useful when execution fails, for instance:
# - INVALID_GOAL: The reason for the invalid goal (e.g., the requested
# trajectory is in the past).
# - INVALID_JOINTS: The mismatch between the expected controller joints
# and those provided in the goal.
# - PATH_TOLERANCE_VIOLATED and GOAL_TOLERANCE_VIOLATED: Which joint
# violated which tolerance, and by how much.
string error_string
---
std_msgs/Header header
string[] joint_names
trajectory_msgs/JointTrajectoryPoint desired
trajectory_msgs/JointTrajectoryPoint actual
trajectory_msgs/JointTrajectoryPoint error
string[] multi_dof_joint_names
trajectory_msgs/MultiDOFJointTrajectoryPoint multi_dof_desired
trajectory_msgs/MultiDOFJointTrajectoryPoint multi_dof_actual
trajectory_msgs/MultiDOFJointTrajectoryPoint multi_dof_error
GripperCommand command
---
float64 position # The current gripper gap size (in meters)
float64 effort # The current effort exerted (in Newtons)
bool stalled # True iff the gripper is exerting max effort and not moving
bool reached_goal # True iff the gripper position has reached the commanded setpoint
---
float64 position # The current gripper gap size (in meters)
float64 effort # The current effort exerted (in Newtons)
bool stalled # True iff the gripper is exerting max effort and not moving
bool reached_goal # True iff the gripper position has reached the commanded setpoint
trajectory_msgs/JointTrajectory trajectory
---
---
geometry_msgs/PointStamped target
geometry_msgs/Vector3 pointing_axis
string pointing_frame
builtin_interfaces/Duration min_duration
float64 max_velocity
---
---
float64 pointing_angle_error
float64 position
builtin_interfaces/Duration min_duration
float64 max_velocity
---
---
std_msgs/Header header
float64 position
float64 velocity
float64 error
# Admittance parameters
std_msgs/Float64MultiArray mass # 6-vector of mass terms used in the admittance calculation
std_msgs/Float64MultiArray damping # 6-vector of damping terms used in the admittance calculation
std_msgs/Float64MultiArray stiffness # 6-vector of stiffness terms used in the admittance calculation
# Frame information
geometry_msgs/Quaternion rot_base_control # quaternion describing the orientation of the control frame
geometry_msgs/TransformStamped ref_trans_base_ft # force torque sensor transform at the reference joint configuration
std_msgs/Int8MultiArray selected_axes # 6-vector of 0/1 describing if admittance is enable in the corresponding control frame axis
std_msgs/String ft_sensor_frame # name of the force torque frame
# State information
geometry_msgs/TransformStamped admittance_position # calculated admittance position in cartesian space
geometry_msgs/TwistStamped admittance_acceleration # calculated admittance acceleration in cartesian space
geometry_msgs/TwistStamped admittance_velocity # calculated admittance velocity in cartesian space
geometry_msgs/WrenchStamped wrench_base # wrench used in the admittance calculation
sensor_msgs/JointState joint_state # calculated admittance offsets in joint space
std_msgs/Header header
# List of resource names, e.g. ["arm_joint_1", "arm_joint_2", "gripper_joint"]
string[] joint_names
# Key-value pairs representing interfaces and their corresponding values for each joint listed in `joint_names`
InterfaceValue[] interface_values
float64 position
float64 max_effort
# List of resource interface names
string[] interface_names
# Values corresponding to the list of interfaces in `interface_names`, [1.0, 0.0] for example
float64[] values
# Version of JointTolerance.msg with added component field for joints with multiple degrees of freedom
# The difference between two MultiDOFJointTrajectoryPoint cannot be represented as a single number,
# hence we use the component field to represent how to calculate the difference in a way that can
# be represented as a single number.
# Since each joint has multiple degrees of freedom,
# there can be multiple tolerances for each joint, each looking
# at different components.
# If the component is X_AXIS, Y_AXIS, or Z_AXIS, then the tolerance
# is only applied for the specific axis.
# However, if the component is TRANSLATION, then the tolerance is for
# the overall Euclidean distance.
# For these components, the units are meters, meters/sec and meters/sec^2.
# Z_AXIS is only valid with a floating joint, not planar.
# If the component is ROTATION the tolerance is measured in
# radians, radians/sec and radians/sec^2, computed
# between the difference in quaternions.
uint16 X_AXIS=1
uint16 Y_AXIS=2
uint16 Z_AXIS=3
uint16 TRANSLATION=4
uint16 ROTATION=5
string joint_name
uint16 component
float64 position
float64 velocity
float64 acceleration
# 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
# The set point, that is, desired state.
float64 set_point
# Current value of the process (ie: latest sensor measurement on the controlled value).
float64 process_value
# First time-derivative of the process value.
float64 process_value_dot
# The error of the controlled value, essentially process_value - set_point (for a regular PID implementation).
float64 error
# Time between two consecutive updates/execution of the control law.
float64 time_step
# Current output of the controller.
float64 command
# Current PID parameters of the controller.
float64 p
float64 i
float64 d
float64 i_clamp
bool antiwindup
# Used in time-stamping the message.
std_msgs/Header header
# Name list of the joints. You don't need to specify all joints of the
# robot. Joint names are case-sensitive.
string[] joint_names
# A position command to the joints listed in joint_names.
# The order must be identical.
# Units are meters or radians.
# If displacements and velocities are filled, a profiled motion is requested.
float64[] displacements # or position_deltas
# A velocity command to the joints listed in joint_names.
# The order must be identical.
# Units are m/s or rad/s.
# If displacements and velocities are filled, a profiled motion is requested.
float64[] velocities
float64 duration
# The tolerances specify the amount the position, velocity, and
# accelerations can vary from the setpoints. For example, in the case
# of trajectory control, when the actual position varies beyond
# (desired position + position tolerance), the trajectory goal may
# abort.
#
# There are two special values for tolerances:
# * 0 - The tolerance is unspecified and will remain at whatever the default is
# * -1 - The tolerance is "erased". If there was a default, the joint will be
# allowed to move without restriction.
string name
float64 position # in radians or meters (for a revolute or prismatic joint, respectively)
float64 velocity # in rad/sec or m/sec
float64 acceleration # in rad/sec^2 or m/sec^2
# This message presents current controller state of JTC
# Header timestamp should be update time of controller state
std_msgs/Header header
string[] joint_names
# The set point, that is, desired state.
trajectory_msgs/JointTrajectoryPoint reference
# Current value of the process (ie: latest sensor measurement on the controlled value).
trajectory_msgs/JointTrajectoryPoint feedback
# The error of the controlled value, essentially reference - feedback (for a regular PID implementation).
trajectory_msgs/JointTrajectoryPoint error
# Current output of the controller.
trajectory_msgs/JointTrajectoryPoint output
string[] multi_dof_joint_names
# The set point, that is, desired state.
trajectory_msgs/MultiDOFJointTrajectoryPoint multi_dof_reference
# Current value of the process (ie: latest sensor measurement on the controlled value).
trajectory_msgs/MultiDOFJointTrajectoryPoint multi_dof_feedback
# The error of the controlled value, essentially reference - feedback (for a regular PID implementation).
trajectory_msgs/MultiDOFJointTrajectoryPoint multi_dof_error
# Current output of the controller.
trajectory_msgs/MultiDOFJointTrajectoryPoint multi_dof_output
std_msgs/Header header
float64 front_left_wheel_velocity
float64 back_left_wheel_velocity
float64 back_right_wheel_velocity
float64 front_right_wheel_velocity
geometry_msgs/Twist reference_velocity
# 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
# 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
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment