├── msg
├── Digital.msg
├── Analog.msg
├── IOStates.msg
├── RobotModeDataMsg.msg
├── ToolDataMsg.msg
├── RobotStateRTMsg.msg
└── MasterboardDataMsg.msg
├── action
├── ToolContact.action
└── FollowJointTrajectoryUntil.action
├── srv
├── SetAnalogOutput.srv
├── SetPayload.srv
├── GetRobotSoftwareVersion.srv
├── SetSpeedSliderFraction.srv
├── SetIO.srv
└── SetForceMode.srv
├── CONTRIBUTING.md
├── README.md
├── CMakeLists.txt
├── LICENSE
├── .github
└── workflows
│ └── ci_ros2_stable.yml
├── package.xml
└── CHANGELOG.rst
/msg/Digital.msg:
--------------------------------------------------------------------------------
1 | uint8 pin
2 | bool state
3 |
--------------------------------------------------------------------------------
/action/ToolContact.action:
--------------------------------------------------------------------------------
1 |
2 | ---
3 |
4 | ---
5 |
--------------------------------------------------------------------------------
/srv/SetAnalogOutput.srv:
--------------------------------------------------------------------------------
1 | Analog data
2 | ---
3 | bool success
4 |
--------------------------------------------------------------------------------
/srv/SetPayload.srv:
--------------------------------------------------------------------------------
1 | float32 mass
2 | geometry_msgs/Vector3 center_of_gravity
3 | ---
4 | bool success
5 |
--------------------------------------------------------------------------------
/msg/Analog.msg:
--------------------------------------------------------------------------------
1 | uint8 CURRENT=0
2 | uint8 VOLTAGE=1
3 |
4 | uint8 pin
5 | uint8 domain # can be VOLTAGE or CURRENT
6 | float32 state
7 |
--------------------------------------------------------------------------------
/msg/IOStates.msg:
--------------------------------------------------------------------------------
1 | Digital[] digital_in_states
2 | Digital[] digital_out_states
3 | Digital[] flag_states
4 | Analog[] analog_in_states
5 | Analog[] analog_out_states
6 |
--------------------------------------------------------------------------------
/CONTRIBUTING.md:
--------------------------------------------------------------------------------
1 | Any contribution that you make to this repository will
2 | be under the 3-Clause BSD License, as dictated by that
3 | [license](https://opensource.org/licenses/BSD-3-Clause).
4 |
--------------------------------------------------------------------------------
/srv/GetRobotSoftwareVersion.srv:
--------------------------------------------------------------------------------
1 | ---
2 | uint32 major # Major version number
3 | uint32 minor # Minor version number
4 | uint32 bugfix # Bugfix version number
5 | uint32 build # Build number
6 |
--------------------------------------------------------------------------------
/srv/SetSpeedSliderFraction.srv:
--------------------------------------------------------------------------------
1 | # Set the speed slider on the teach pendant to the specified value.
2 | #
3 | # Values for 'speed_slider_fraction' must be from [0; 1.0]; values outside this
4 | # valid range will result in an error being returned to the caller.
5 |
6 | float64 speed_slider_fraction
7 | ---
8 | bool success
9 |
--------------------------------------------------------------------------------
/msg/RobotModeDataMsg.msg:
--------------------------------------------------------------------------------
1 | # This data structure contains the RobotModeData structure
2 | # used by the Universal Robots controller
3 | #
4 | # This data structure is send at 10 Hz on TCP port 30002
5 | #
6 | # Note: this message does not carry all fields from the RobotModeData structure as broadcast by the robot controller, but a subset.
7 |
8 | uint64 timestamp
9 | bool is_robot_connected
10 | bool is_real_robot_enabled
11 | bool is_power_on_robot
12 | bool is_emergency_stopped
13 | bool is_protective_stopped
14 | bool is_program_running
15 | bool is_program_paused
16 |
--------------------------------------------------------------------------------
/msg/ToolDataMsg.msg:
--------------------------------------------------------------------------------
1 | # This data structure contains the ToolData structure
2 | # used by the Universal Robots controller
3 |
4 | int8 ANALOG_INPUT_RANGE_CURRENT = 0
5 | int8 ANALOG_INPUT_RANGE_VOLTAGE = 1
6 |
7 | int8 analog_input_range2 # one of ANALOG_INPUT_RANGE_*
8 | int8 analog_input_range3 # one of ANALOG_INPUT_RANGE_*
9 | float64 analog_input2
10 | float64 analog_input3
11 | float32 tool_voltage_48v
12 | uint8 tool_output_voltage
13 | float32 tool_current
14 | float32 tool_temperature
15 |
16 | uint8 TOOL_BOOTLOADER_MODE = 249
17 | uint8 TOOL_RUNNING_MODE = 253
18 | uint8 TOOL_IDLE_MODE = 255
19 |
20 | uint8 tool_mode # one of TOOL_*
21 |
--------------------------------------------------------------------------------
/msg/RobotStateRTMsg.msg:
--------------------------------------------------------------------------------
1 | # Data structure for the realtime communications interface (aka Matlab interface)
2 | # used by the Universal Robots controller
3 | #
4 | # This data structure is send at 125 Hz on TCP port 30003
5 | #
6 | # Dokumentation can be found on the Universal Robots Support Wiki
7 | # (http://wiki03.lynero.net/Technical/RealTimeClientInterface?rev=9)
8 |
9 | float64 time
10 | float64[] q_target
11 | float64[] qd_target
12 | float64[] qdd_target
13 | float64[] i_target
14 | float64[] m_target
15 | float64[] q_actual
16 | float64[] qd_actual
17 | float64[] i_actual
18 | float64[] tool_acc_values
19 | float64[] tcp_force
20 | float64[] tool_vector
21 | float64[] tcp_speed
22 | float64 digital_input_bits
23 | float64[] motor_temperatures
24 | float64 controller_timer
25 | float64 test_value
26 | float64 robot_mode
27 | float64[] joint_modes
28 |
--------------------------------------------------------------------------------
/msg/MasterboardDataMsg.msg:
--------------------------------------------------------------------------------
1 | # This data structure contains the MasterboardData structure
2 | # used by the Universal Robots controller
3 | #
4 | # MasterboardData is part of the data structure being send on the
5 | # secondary client communications interface
6 | #
7 | # This data structure is send at 10 Hz on TCP port 30002
8 | #
9 | # Documentation can be found on the Universal Robots Support site, article
10 | # number 16496.
11 |
12 | uint32 digital_input_bits
13 | uint32 digital_output_bits
14 | int8 analog_input_range0
15 | int8 analog_input_range1
16 | float64 analog_input0
17 | float64 analog_input1
18 | int8 analog_output_domain0
19 | int8 analog_output_domain1
20 | float64 analog_output0
21 | float64 analog_output1
22 | float32 masterboard_temperature
23 | float32 robot_voltage_48v
24 | float32 robot_current
25 | float32 master_io_current
26 | uint8 master_safety_state
27 | uint8 master_onoff_state
28 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | # ur_msgs
2 |
3 | [](https://build.ros2.org/job/Hbin_uJ64__ur_msgs__ubuntu_jammy_amd64__binary/)
4 | [](https://github.com/ros-industrial/ur_msgs/actions/workflows/ci_ros2_stable.yml)
5 | [](http://github.com/ros-industrial/ur_msgs/issues)
6 |
7 | [](https://opensource.org/licenses/BSD-3-Clause)
8 |
9 | [](http://rosindustrial.org/news/2016/10/7/better-supporting-a-growing-ros-industrial-software-platform)
10 |
11 | Message and service definitions for use with packages supporting and interacting with Universal Robots' robot controllers.
12 |
13 | See the ROS index for more information: [index.ros.org/p/ur_msgs](https://index.ros.org/p/ur_msgs/github-ros-industrial-ur_msgs/#humble).
14 |
--------------------------------------------------------------------------------
/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 3.5)
2 | project(ur_msgs)
3 |
4 | find_package(ament_cmake REQUIRED)
5 | find_package(builtin_interfaces REQUIRED)
6 | find_package(rosidl_default_generators REQUIRED)
7 | find_package(geometry_msgs REQUIRED)
8 | find_package(control_msgs REQUIRED)
9 | find_package(trajectory_msgs REQUIRED)
10 | find_package(std_msgs REQUIRED)
11 |
12 | set(msg_files
13 | msg/Analog.msg
14 | msg/Digital.msg
15 | msg/IOStates.msg
16 | msg/RobotStateRTMsg.msg
17 | msg/MasterboardDataMsg.msg
18 | msg/RobotModeDataMsg.msg
19 | msg/ToolDataMsg.msg
20 | )
21 |
22 | set(srv_files
23 | srv/SetAnalogOutput.srv
24 | srv/SetPayload.srv
25 | srv/SetSpeedSliderFraction.srv
26 | srv/SetIO.srv
27 | srv/GetRobotSoftwareVersion.srv
28 | srv/SetForceMode.srv
29 | )
30 |
31 | set(action_files
32 | action/ToolContact.action
33 | action/FollowJointTrajectoryUntil.action
34 | )
35 |
36 | if(BUILD_TESTING)
37 | find_package(ament_lint_auto REQUIRED)
38 | ament_lint_auto_find_test_dependencies()
39 | endif()
40 |
41 | rosidl_generate_interfaces(${PROJECT_NAME}
42 | ${msg_files}
43 | ${srv_files}
44 | ${action_files}
45 | DEPENDENCIES builtin_interfaces geometry_msgs control_msgs trajectory_msgs std_msgs
46 | ADD_LINTER_TESTS
47 | )
48 |
49 | ament_export_dependencies(rosidl_default_runtime)
50 |
51 | ament_package()
52 |
53 |
--------------------------------------------------------------------------------
/action/FollowJointTrajectoryUntil.action:
--------------------------------------------------------------------------------
1 | # The joint trajectory to follow
2 | trajectory_msgs/JointTrajectory trajectory
3 |
4 | # The tolerances for the trajectory, while it is executing
5 | control_msgs/JointTolerance[] path_tolerance
6 |
7 | # The tolerances for the goal, when the trajectory is finished.
8 | control_msgs/JointTolerance[] goal_tolerance
9 | builtin_interfaces/Duration goal_time_tolerance
10 |
11 | # The condition until which the trajectory should run.
12 | uint8 until_type
13 | uint8 TOOL_CONTACT = 0
14 |
15 | ---
16 | # The trajectory will be reported as succesful if either the trajectory finishes, or the until condition is met.
17 | # The error codes will be used if the trajectory fails and the until condition is not met.
18 | int32 error_code
19 | int32 SUCCESSFUL = 0
20 | int32 INVALID_GOAL = -1
21 | int32 INVALID_JOINTS = -2
22 | int32 OLD_HEADER_TIMESTAMP = -3
23 | int32 PATH_TOLERANCE_VIOLATED = -4
24 | int32 GOAL_TOLERANCE_VIOLATED = -5
25 |
26 | int32 until_condition_result
27 | int32 TRIGGERED = 0
28 | int32 NOT_TRIGGERED = 1
29 |
30 | # The error string will contain information about the final state of the trajectory execution.
31 | string error_string
32 |
33 | ---
34 | std_msgs/Header header
35 | string[] joint_names
36 | trajectory_msgs/JointTrajectoryPoint desired
37 | trajectory_msgs/JointTrajectoryPoint actual
38 | trajectory_msgs/JointTrajectoryPoint error
39 |
--------------------------------------------------------------------------------
/LICENSE:
--------------------------------------------------------------------------------
1 | Redistribution and use in source and binary forms, with or without
2 | modification, are permitted provided that the following conditions are met:
3 |
4 | * Redistributions of source code must retain the above copyright
5 | notice, this list of conditions and the following disclaimer.
6 |
7 | * Redistributions in binary form must reproduce the above copyright
8 | notice, this list of conditions and the following disclaimer in the
9 | documentation and/or other materials provided with the distribution.
10 |
11 | * Neither the name of the copyright holder nor the names of its
12 | contributors may be used to endorse or promote products derived from
13 | this software without specific prior written permission.
14 |
15 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18 | ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
19 | LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20 | CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21 | SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22 | INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23 | CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24 | ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25 | POSSIBILITY OF SUCH DAMAGE.
26 |
--------------------------------------------------------------------------------
/.github/workflows/ci_ros2_stable.yml:
--------------------------------------------------------------------------------
1 | name: CI - ROS2 stable
2 |
3 | on:
4 | # direct pushes to protected branches are not supported
5 | pull_request:
6 | # run every day, at 6am UTC
7 | schedule:
8 | - cron: '0 6 * * *'
9 | # allow manually starting this workflow
10 | workflow_dispatch:
11 |
12 | jobs:
13 | industrial_ci:
14 | name: ROS ${{ matrix.ros_distro }} (${{ matrix.ros_repo }})
15 | runs-on: ubuntu-24.04
16 |
17 | strategy:
18 | matrix:
19 | ros_distro: [humble, iron, jazzy, rolling]
20 | ros_repo: [main]
21 |
22 | env:
23 | CCACHE_DIR: "${{ github.workspace }}/.ccache"
24 |
25 | steps:
26 | - name: Fetch repository
27 | uses: actions/checkout@v4
28 |
29 | - name: ccache cache
30 | uses: actions/cache@v3
31 | with:
32 | path: ${{ env.CCACHE_DIR }}
33 | # we always want the ccache cache to be persisted, as we cannot easily
34 | # determine whether dependencies have changed, and ccache will manage
35 | # updating the cache for us. Adding 'run_id' to the key will force an
36 | # upload at the end of the job.
37 | key: ccache-${{ matrix.ros_distro }}-${{ matrix.ros_repo }}-${{github.run_id}}
38 | restore-keys: |
39 | ccache-${{ matrix.ros_distro }}-${{ matrix.ros_repo }}
40 |
41 | - name: Run industrial_ci
42 | uses: ros-industrial/industrial_ci@master
43 | env:
44 | ROS_DISTRO: ${{ matrix.ros_distro }}
45 | ROS_REPO: ${{ matrix.ros_repo }}
46 |
--------------------------------------------------------------------------------
/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 | ur_msgs
5 | 2.3.0
6 | Message and service definitions for interacting with Universal Robots robot controllers.
7 | G.A. vd. Hoorn
8 | Miguel Prada Sarasola
9 | Nadia Hammoudeh Garcia
10 | BSD-3-Clause
11 | Andrew Glusiec
12 | Felix Messmer
13 |
14 | ament_cmake
15 | rosidl_default_generators
16 |
17 | builtin_interfaces
18 | geometry_msgs
19 | action_msgs
20 | control_msgs
21 | trajectory_msgs
22 | std_msgs
23 |
24 | rosidl_default_runtime
25 |
26 | ament_lint_auto
27 | ament_lint_common
28 |
29 | rosidl_interface_packages
30 |
31 |
32 |
33 |
34 | messages
35 | ros-industrial
36 | services
37 | universal_robot
38 |
39 |
40 |
41 |
42 |
43 | ament_cmake
44 |
45 |
46 |
--------------------------------------------------------------------------------
/srv/SetIO.srv:
--------------------------------------------------------------------------------
1 | # Service allows setting digital (DIO) and analog (AIO) IO, as well as flags
2 | # and configuring tool voltage.
3 | #
4 | # This service has three request fields (see below).
5 | #
6 | # When setting DIO or AIO pins to new values:
7 | #
8 | # fun The function to perform
9 | # pin Numeric ID of the pin to set, see constants definition below
10 | # state Desired pin state (signal level for analog or STATE_(ON|OFF) for DIO and flags)
11 | #
12 | # When configuring tool voltage:
13 | #
14 | # fun Set to FUN_SET_TOOL_VOLTAGE
15 | # pin Ignored
16 | # state Desired tool voltage (use STATE_TOOL_VOLTAGE constants)
17 |
18 | # constants
19 | # pin mapping
20 | # analog out
21 | int8 PIN_AOUT0 = 0
22 | int8 PIN_AOUT1 = 1
23 |
24 | # digital out
25 | int8 PIN_DOUT0 = 0
26 | int8 PIN_DOUT1 = 1
27 | int8 PIN_DOUT2 = 2
28 | int8 PIN_DOUT3 = 3
29 | int8 PIN_DOUT4 = 4
30 | int8 PIN_DOUT5 = 5
31 | int8 PIN_DOUT6 = 6
32 | int8 PIN_DOUT7 = 7
33 |
34 | # configurable out
35 | int8 PIN_CONF_OUT0 = 8
36 | int8 PIN_CONF_OUT1 = 9
37 | int8 PIN_CONF_OUT2 = 10
38 | int8 PIN_CONF_OUT3 = 11
39 | int8 PIN_CONF_OUT4 = 12
40 | int8 PIN_CONF_OUT5 = 13
41 | int8 PIN_CONF_OUT6 = 14
42 | int8 PIN_CONF_OUT7 = 15
43 |
44 | # digital tool output
45 | int8 PIN_TOOL_DOUT0 = 16
46 | int8 PIN_TOOL_DOUT1 = 17
47 |
48 | # valid function values
49 | #
50 | # Note: 'fun' is short for 'function' (ie: the function the service should perform).
51 | int8 FUN_SET_DIGITAL_OUT = 1
52 | int8 FUN_SET_FLAG = 2
53 | int8 FUN_SET_ANALOG_OUT = 3
54 | int8 FUN_SET_TOOL_VOLTAGE = 4
55 |
56 | # valid values for 'state' when setting digital IO or flags
57 | int8 STATE_OFF = 0
58 | int8 STATE_ON = 1
59 |
60 | # valid 'state' values when setting tool voltage
61 | int8 STATE_TOOL_VOLTAGE_0V = 0
62 | int8 STATE_TOOL_VOLTAGE_12V = 12
63 | int8 STATE_TOOL_VOLTAGE_24V = 24
64 |
65 | # request fields
66 | int8 fun
67 | int8 pin
68 | float32 state
69 | ---
70 | bool success
71 |
--------------------------------------------------------------------------------
/srv/SetForceMode.srv:
--------------------------------------------------------------------------------
1 | # A 6d pose that defines the force frame. Must be static relative to the robot's base frame.
2 | geometry_msgs/PoseStamped task_frame
3 |
4 | # 1 means that the robot will be compliant in the corresponding axis of the task frame
5 | bool selection_vector_x 0
6 | bool selection_vector_y 0
7 | bool selection_vector_z 0
8 | bool selection_vector_rx 0
9 | bool selection_vector_ry 0
10 | bool selection_vector_rz 0
11 |
12 | # The forces/torques the robot will apply to its environment. For geometric interpretation, please
13 | # see parameter `type`
14 | geometry_msgs/Wrench wrench
15 |
16 | # An integer [1;3] specifying how the robot interprets the force frame
17 | # 1: The force frame is transformed in a way such that its y-axis is aligned with a vector pointing
18 | # from the robot tcp towards the origin of the force frame.
19 | # 2: The force frame is not transformed.
20 | # 3: The force frame is transformed in a way such that its x-axis is the projection of the robot tcp
21 | # velocity vector onto the x-y plane of the force frame.
22 | uint8 type 2
23 | # Type constants:
24 | uint8 TCP_TO_ORIGIN=1
25 | uint8 NO_TRANSFORM=2
26 | uint8 TCP_VELOCITY_TO_X_Y=3
27 |
28 | # Maximum allowed tcp speed (relative to the task frame).
29 | # PLEASE NOTE: This is only relevant for axes marked as compliant in the selection_vector
30 | geometry_msgs/Twist speed_limits
31 |
32 | # For non-compliant axes, these values are the maximum allowed deviation along/about an axis
33 | # between the actual tcp position and the one set by the program.
34 | float32[6] deviation_limits [0.01, 0.01, 0.01, 0.01, 0.01, 0.01]
35 |
36 | # Force mode damping factor. Sets the damping parameter in force mode. In range [0;1], default value is 0.025
37 | # A value of 1 is full damping, so the robot will decelerate quickly if no force is present. A value of 0
38 | # is no damping, here the robot will maintain the speed.
39 | float32 damping_factor 0.025
40 |
41 | # Force mode gain scaling factor. Scales the gain in force mode. scaling parameter is in range [0;2], default is 0.5.
42 | # A value larger than 1 can make force mode unstable, e.g. in case of collisions or pushing against hard surfaces.
43 | float32 gain_scaling 0.5
44 | ---
45 | bool success
46 |
--------------------------------------------------------------------------------
/CHANGELOG.rst:
--------------------------------------------------------------------------------
1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
2 | Changelog for package ur_msgs
3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
4 |
5 | 2.3.0 (2025-07-31)
6 | ------------------
7 | * Trajectory until action definition (`#38 `_)
8 | * Contributors: URJala
9 |
10 | 2.2.0 (2025-03-17)
11 | ------------------
12 | * Tool contact action (`#37 `_)
13 | * Contributors: URJala
14 |
15 | 2.1.0 (2024-12-02)
16 | ------------------
17 | * Added service to set force mode (`#26 `_)
18 | * Contributors: URJala
19 |
20 | 2.0.1 (2024-10-07)
21 | ------------------
22 | * [ROS 2] Update README and ci (`#31 `_)
23 | * Add a service to set an analog output (`#30 `_)
24 | * Added service for getting the software version of the robot. (`#25 `_)
25 | * ci: bump checkout and cache (`#23 `_)
26 | * Contributors: Felix Exner, G.A. vd. Hoorn, URJala
27 |
28 | 2.0.0 (2022-04-12)
29 | ------------------
30 | * Porting to ros2 (`#12 `_)
31 | * Document pin mapping in SetIO service (`#16 `_)
32 | * Contributors: Denis Štogl, Felix Exner, gavanderhoorn
33 |
34 | 1.3.4 (2021-05-25)
35 | ------------------
36 | * Bump CMake version to ignore warning
37 | * Contributors: gavanderhoorn
38 |
39 | 1.3.3 (2021-05-25)
40 | ------------------
41 | * Migrate to Github Actions
42 | * Fix SetPayload srv separater invalid (`#10 `_)
43 | * Contributors: Chen Bainian, gavanderhoorn
44 |
45 | 1.3.2 (2020-10-12)
46 | ------------------
47 | * Fix domain constants in ``Analog.msg`` (`#8 `_)
48 | * Contributors: Gaël Écorchard
49 |
50 | 1.3.1 (2020-06-24)
51 | ------------------
52 | * Change ``payload`` field name to ``mass`` (`#5 `_)
53 | * Added ``center_of_gravity`` field to ``SetPayload`` service (`#2 `_)
54 | * Mark package as architecture independent (`#1 `_)
55 | * Contributors: Felix Exner, gavanderhoorn
56 |
57 | 1.3.0 (2020-06-22)
58 | ------------------
59 | * First release of this package from its new repository.
60 | * Contributors: gavanderhoorn
61 |
62 | 1.2.7 (2019-11-23)
63 | ------------------
64 |
65 | 1.2.6 (2019-11-19)
66 | ------------------
67 | * Added a service to set the speed slider position (`#454 `_)
68 | * Added a domain field to Analog.msg (`#450 `_)
69 | * Migrated all package.xml files to format=2 (`#439 `_)
70 | * Contributors: Felix Mauch
71 |
72 | 1.2.5 (2019-04-05)
73 | ------------------
74 | * Correct width and type of 'digital\_*_bits'. (`#416 `_)
75 | * Clarify use of fields in SetIO svc. (`#415 `_)
76 | * Update maintainer listing: add Miguel (`#410 `_)
77 | * Add RobotModeDataMsg (`#395 `_)
78 | * Update maintainer and author information.
79 | * Contributors: Felix von Drigalski, gavanderhoorn
80 |
81 | 1.2.1 (2018-01-06)
82 | ------------------
83 |
84 | 1.2.0 (2017-08-04)
85 | ------------------
86 |
87 | 1.1.9 (2017-01-02)
88 | ------------------
89 | * No changes.
90 |
91 | 1.1.8 (2016-12-30)
92 | ------------------
93 | * all: update maintainers.
94 | * Contributors: gavanderhoorn
95 |
96 | 1.1.7 (2016-12-29)
97 | ------------------
98 | * Add message definition for ToolData.
99 | * Contributors: Nikolas Engelhard
100 |
101 | 1.1.6 (2016-04-01)
102 | ------------------
103 | * Moved SetIO FUN constants from driver.py to relevant srv file for easier interaction from other files
104 | * catkin_lint
105 | * Contributors: Thomas Timm Andersen, ipa-fxm
106 |
--------------------------------------------------------------------------------