Show EOL distros:
Package Summary
A set of packages that include controller interfaces, controller managers, transmissions, hardware_interfaces and the control_toolbox.
- Maintainer status: developed
- Maintainer: Wim Meeussen <wim AT hidof DOT com>, Adolfo Rodriguez Tsouroukdissian <adolfo.rodriguez AT pal-robotics DOT com>, Dave Coleman <davetcoleman AT gmail DOT com>
- Author: Wim Meeussen
- License: BSD
- Bug / feature tracker: https://github.com/ros-controls/ros_control/issues
- Source: git https://github.com/ros-controls/ros_control.git (branch: hydro-devel)
Package Summary
A set of packages that include controller interfaces, controller managers, transmissions, hardware_interfaces and the control_toolbox.
- Maintainer status: developed
- Maintainer: Adolfo Rodriguez Tsouroukdissian <adolfo.rodriguez AT pal-robotics DOT com>, Dave Coleman <davetcoleman AT gmail DOT com>
- Author: Wim Meeussen
- License: BSD
- Bug / feature tracker: https://github.com/ros-controls/ros_control/issues
- Source: git https://github.com/ros-controls/ros_control.git (branch: indigo-devel)
Package Summary
A set of packages that include controller interfaces, controller managers, transmissions, hardware_interfaces and the control_toolbox.
- Maintainer status: maintained
- Maintainer: Adolfo Rodriguez Tsouroukdissian <adolfo.rodriguez AT pal-robotics DOT com>, Dave Coleman <davetcoleman AT gmail DOT com>
- Author: Wim Meeussen
- License: BSD
- Bug / feature tracker: https://github.com/ros-controls/ros_control/issues
- Source: git https://github.com/ros-controls/ros_control.git (branch: jade-devel)
Package Summary
A set of packages that include controller interfaces, controller managers, transmissions and hardware_interfaces.
- Maintainer status: maintained
- Maintainer: Bence Magyar <bence.magyar.robotics AT gmail DOT com>, Enrique Fernandez <enrique.fernandez.perdomo AT gmail DOT com>, Mathias Lüdtke <mathias.luedtke AT ipa.fraunhofer DOT de>
- Author: Wim Meeussen
- License: BSD
- Bug / feature tracker: https://github.com/ros-controls/ros_control/issues
- Source: git https://github.com/ros-controls/ros_control.git (branch: kinetic-devel)
Package Summary
A set of packages that include controller interfaces, controller managers, transmissions and hardware_interfaces.
- Maintainer status: maintained
- Maintainer: Bence Magyar <bence.magyar.robotics AT gmail DOT com>, Enrique Fernandez <enrique.fernandez.perdomo AT gmail DOT com>, Mathias Lüdtke <mathias.luedtke AT ipa.fraunhofer DOT de>
- Author: Wim Meeussen
- License: BSD
- Bug / feature tracker: https://github.com/ros-controls/ros_control/issues
- Source: git https://github.com/ros-controls/ros_control.git (branch: kinetic-devel)
Package Summary
A set of packages that include controller interfaces, controller managers, transmissions and hardware_interfaces.
- Maintainer status: maintained
- Maintainer: Bence Magyar <bence.magyar.robotics AT gmail DOT com>, Enrique Fernandez <enrique.fernandez.perdomo AT gmail DOT com>, Mathias Lüdtke <mathias.luedtke AT ipa.fraunhofer DOT de>
- Author: Wim Meeussen
- License: BSD
- Bug / feature tracker: https://github.com/ros-controls/ros_control/issues
- Source: git https://github.com/ros-controls/ros_control.git (branch: melodic-devel)
Package Summary
A set of packages that include controller interfaces, controller managers, transmissions and hardware_interfaces.
- Maintainer status: maintained
- Maintainer: Bence Magyar <bence.magyar.robotics AT gmail DOT com>, Enrique Fernandez <enrique.fernandez.perdomo AT gmail DOT com>, Mathias Lüdtke <mathias.luedtke AT ipa.fraunhofer DOT de>
- Author: Wim Meeussen
- License: BSD
- Bug / feature tracker: https://github.com/ros-controls/ros_control/issues
- Source: git https://github.com/ros-controls/ros_control.git (branch: noetic-devel)
Contents
Overview
The ros_control packages are a rewrite of the pr2_mechanism packages to make controllers generic to all robots beyond just the PR2.
Diagram source in ros_control/documentation
The ros_control packages takes as input the joint state data from your robot's actuator's encoders and an input set point. It uses a generic control loop feedback mechanism, typically a PID controller, to control the output, typically effort, sent to your actuators. ros_control gets more complicated for physical mechanisms that do not have one-to-one mappings of joint positions, efforts, etc but these scenarios are accounted for using transmissions.
A high-level overview of the project can be found in the ROScon 2014 talk entitled ros_control: An overview (slides, video).
A short summary of CombinedRobotHW can be found in this ROScon 2016 talk.
Additional documentation is available at the Github Wiki
Publication
If you find this work useful please give credits to the authors by citing:
- S. Chitta, E. Marder-Eppstein, W. Meeussen, V. Pradeep, A. Rodríguez Tsouroukdissian, J. Bohren, D. Coleman, B. Magyar, G. Raiola, M. Lüdtke and E. Fernandez Perdomo
- "ros_control: A generic and simple control framework for ROS"
The Journal of Open Source Software, 2017. PDF
@article{ros_control, author = {Chitta, Sachin and Marder-Eppstein, Eitan and Meeussen, Wim and Pradeep, Vijay and Rodr{\'i}guez Tsouroukdissian, Adolfo and Bohren, Jonathan and Coleman, David and Magyar, Bence and Raiola, Gennaro and L{\"u}dtke, Mathias and Fern{\'a}ndez Perdomo, Enrique}, title = {ros\_control: A generic and simple control framework for ROS}, journal = {The Journal of Open Source Software}, year = {2017}, doi = {10.21105/joss.00456}, URL = {http://www.theoj.org/joss-papers/joss.00456/10.21105.joss.00456.pdf} }
Controllers
A list of available controller plugins, contained in ros_controllers, as of this writing. You can of course create your own and are not limited to the below list.
joint_state_controller - Publishes the state of all resources registered to a hardware_interface::JointStateInterface to a topic of type sensor_msgs/JointState.
- joint_state_controller
position_controllers - Command a desired position to the HardwareInterface.
joint_position_controller - Receives a position input and sends a position output, just transferring the input with the forward_command_controller.
- joint_group_position_controller - Set multiple joint positions at once.
velocity_controllers - Command a desired velocity to the HardwareInterface.
- joint_position_controller - Receives a position input and sends a velocity output, using a PID controller.
joint_velocity_controller - Receives a velocity input and sends a velocity output, just transferring the input with the forward_command_controller.
- joint_group_velocity_controller - Set multiple joint velocities at once.
effort_controllers - Command a desired effort(force/torque) to the Hardware Interface.
- joint_position_controller - Receives a position input and sends an effort output, using a PID controller.
- joint_group_position_controller - Set multiple joint positions at once.
- joint_velocity_controller - Receives a velocity input and sends an effort output, using a PID controller.
joint_effort_controller - Receives an effort input and sends an effort output, just transferring the input with the forward_command_controller.
- joint_group_effort_controller - Set multiple joint efforts at once.
joint_trajectory_controllers - Extra functionality for splining an entire trajectory. Take a look at the source file to understand how the joint_trajectory_controller is namespaced with the position_controller, velocity_controller, etc.
- position_controller
- velocity_controller
- effort_controller
- position_velocity_controller
- position_velocity_acceleration_controller
Hardware Interfaces
Hardware Interfaces are used by ROS control in conjunction with one of the above ROS controllers to send and receive commands to hardware. A list of available Hardware Interfaces (via the Hardware Resource Manager) as of this writing. If the Hardware Interface for your robot doesn't already exist, you can of course create your own and are not limited to this list:
Joint Command Interface - Hardware interface to support commanding an array of joints. Note that these commands can have any semantic meaning as long as they each can be represented by a single double, they are not necessarily effort commands. To specify a meaning to this command, see the derived classes:
Effort Joint Interface - for commanding effort-based joints.
Velocity Joint Interface - for commanding velocity-based joints.
Position Joint Interface - for commanding position-based joints.
Joint State Interfaces - Hardware interface to support reading the state of an array of named joints, each of which has some position, velocity, and effort (force or torque).
Actuator State Interfaces - Hardware interface to support reading the state of an array of named actuators, each of which has some position, velocity, and effort (force or torque).
- Actuator Command Interfaces
- Effort Actuator Interface
- Velocity Actuator Interface
- Position Actuator Interface
- Force-torque sensor Interface
- IMU sensor Interface
Also refer to the C++ API of the hardware_interface and the package documentation wiki.
Transmissions
A transmission is an element in your control pipeline that transforms efforts/flow variables such that their product - power - remains constant. A transmission interface implementation maps effort/flow variables to output effort/flow variables while preserving power.
Mechanical transmissions are power-preserving transformations, ie.
P_in = P_out F_in x V_in = F_out x V_out
where P, F and V stand for power, force and velocity. More generally, power is the product of an effort (eg. force, voltage) and a flow (eg. velocity, current) variable. For a simple mechanical reducer with ratio n, one has:
effort map: F_joint = F_actuator * n flow map: V_joint = V_actuator / n
From the above it can be seen that power remains constant between input and output. Complementary Wikipedia link (first part will do).
Transmission URDF Format
See URDF Transmissions.
Transmission Interfaces
Transmission-specific code (not robot-specific) implementing bidirectional (actuator <-> joint) effort and flow maps under a uniform interface shared across transmission types. This is hardware-interface-agnostic. A list of available transmission types as of this writing:
- Simple Reduction Transmission
- Differential Transmission
- Four Bar Linkage Transmission
Usages:
transmission_interface::ActuatorToJointStateInterface to populate joint state from actuator variables.
hardware_interface::JointStateInterface to expose the joint state to controllers.
Example
See here
Joint Limits
The joint_limits_interface contains data structures for representing joint limits, methods for populating them from common formats such as URDF and rosparam, and methods for enforcing limits on different kinds of joint commands.
The joint_limits_interface is not used by controllers themselves (it does not implement a HardwareInterface) but instead operates after the controllers have updated, in the write() method (or equivalent) of the robot abstraction. Enforcing limits will overwrite the commands set by the controllers, it does not operate on a separate raw data buffer.
Specification
Joint limits Position, velocity, acceleration, jerk and effort.
Soft joint limits Soft position limits, k_p, k_v (as described in pr2_controller_manager/safety_limits).
Utility method for loading joint limits information from URDF (only position, velocity, effort)
Utility method for loading soft joint limits information from URDF
Utility method for loading joint limits from ROS parameter server (all values). Parameter specification is the same used in MoveIt, with the addition that we also parse jerk and effort limits.
Joint limits interface
ros_control interface for enforcing joint limits.
For effort-controlled joints, position-controlled joints, and velocity-controlled joints, two types of interfaces have been created. The first is a saturation interface, used for joints that have normal limits but not soft limits. The second is an interface that implements soft limits, similar to the one used on the PR2.
Example
See here
Additional Examples
The Github wiki page of ros_control provides a detailed walkthrough of selected examples: The ros_control Wiki
Barrett WAM controllers at Johns Hopkins University: barrett_control on Github
RRBot in Gazebo: ros_control with Gazebo tutorial
Rethink Baxter hardware as used at the University of Colorado Boulder: Baxter on Github
ROS HAL interface provides interfaces to MachineKit HAL from ROS: https://github.com/zultron/hal_ros_control/
Install
On Ubuntu, you can install ros_control from debian packages (recommended):
sudo apt-get install ros-$ROS_DISTRO-ros-control ros-$ROS_DISTRO-ros-controllers
Or on Ubuntu and other platforms from source. To ease installing from source a rosinstall file is provided:
cd CATKIN_WORKSPACE/src wstool init wstool merge https://raw.github.com/ros-controls/ros_control/$ROS_DISTRO-devel/ros_control.rosinstall wstool update cd .. rosdep install --from-paths . --ignore-src --rosdistro $ROS_DISTRO -y catkin_make
Ideas and future perspectives
Not exactly a roadmap, but this page contains discussion and proposed solutions to allow ros_control to better accommodate more complex control setups and address shortcomings in the current implementation.
A ROS Control SIG exists with a mailing list for discussing ros_control issues and features. You are encouraged to join and help with ros_control's development!
Acknowledgments
Supported by ROSIN - ROS-Industrial Quality-Assured Robot Software Components.
More information: rosin-project.eu
|
This project has received funding from the European Union’s Horizon 2020 |