You're reading the documentation for an older, but still supported, version of ROS 2. For information on the latest version, please have a look at Kilted.
Humble to Jazzy
This list summarizes important changes between Humble (previous) and Jazzy (current) releases, where changes to user code might be necessary.
controller_interface
update_reference_from_subscribers()method got time and period parameters (PR #846).The changes from (PR #1694) will affect how the controllers will be loading the parameters. Defining parameters in a single yaml file and loading it to the controller_manager node alone will no longer work. In order to load the parameters to the controllers properly, it is needed to use
--param-fileoption from the spawner. This is because the controllers will now setuse_global_argumentsfrom NodeOptions to false, to avoid getting influenced by global arguments.With (#1683) the
rclcpp_lifecycle::State & get_state()andvoid set_state(const rclcpp_lifecycle::State & new_state)are replaced byrclcpp_lifecycle::State & get_lifecycle_state()andvoid set_lifecycle_state(const rclcpp_lifecycle::State & new_state). This change affects controllers and hardware. This is related to (#1240) as variant support introducesget_stateandset_statemethods for setting/getting state of handles.The
exported_state_interfaces_andexported_reference_interfaces_now uses the the full interface name as the key to the unordered_map, instead of the interface type. This is related to (#2038). For instance, the key would bejoint_1/positioninstead ofposition.controller_interface::init()has been deprecated, use theinit(const controller_interface::ControllerInterfaceParams & params)method instead. (#2390). For example, the following code:controller_interface::ControllerInterfaceParams params; params.controller_name = "controller_name"; params.robot_description = ""; params.update_rate = 50; params.node_namespace = ""; params.node_options = controller.define_custom_node_options(); controller.init(params);
controller_manager
Rename
class_typetoplugin_name(#780)CM now subscribes to
robot_descriptiontopic instead of~/robot_description(#1410). As a consequence, when using multiple controller managers, you have to remap the topic within the launch file, an example for a python launch file:remappings=[ ('/robot_description', '/custom_1/robot_description'), ]
Changes from (PR #1256)
All
jointsdefined in the<ros2_control>-tag have to be present in the URDF received by the controller manager, otherwise the following error is shown:The published robot description file (URDF) seems not to be genuine. The following error was caught: <unknown_joint> not found in URDF.
This is to ensure that the URDF and the
<ros2_control>-tag are consistent. E.g., for configuration ports usegpiointerface types instead.The syntax for mimic joints is changed to the official URDF specification. The parameters within the
ros2_controltag are not supported any more. Instead of<ros2_control name="GazeboSystem" type="system"> <joint name="right_finger_joint"> <command_interface name="position"/> <state_interface name="position"> <param name="initial_value">0.15</param> </state_interface> <state_interface name="velocity"/> <state_interface name="effort"/> </joint> <joint name="left_finger_joint"> <param name="mimic">right_finger_joint</param> <param name="multiplier">1</param> <command_interface name="position"/> <state_interface name="position"/> <state_interface name="velocity"/> <state_interface name="effort"/> </joint> </ros2_control>
define your mimic joints directly in the joint definitions:
<joint name="right_finger_joint" type="prismatic"> <axis xyz="0 1 0"/> <origin xyz="0.0 -0.48 1" rpy="0.0 0.0 0.0"/> <parent link="base"/> <child link="finger_right"/> <limit effort="1000.0" lower="0" upper="0.38" velocity="10"/> </joint> <joint name="left_finger_joint" type="prismatic"> <mimic joint="right_finger_joint" multiplier="1" offset="0"/> <axis xyz="0 1 0"/> <origin xyz="0.0 0.48 1" rpy="0.0 0.0 3.1415926535"/> <parent link="base"/> <child link="finger_left"/> <limit effort="1000.0" lower="0" upper="0.38" velocity="10"/> </joint>
The support for the
descriptionparameter for loading the URDF was removed (#1358). Userobot_descriptiontopic instead, e.g., you can use the robot_state_publisher. For an example, see this PR where the change was applied to the demo repository.
hardware_interface
test_componentswas moved to its own package. Update the dependencies if you are using them. (#1325)With (#1683) the
rclcpp_lifecycle::State & get_state()andvoid set_state(const rclcpp_lifecycle::State & new_state)are replaced byrclcpp_lifecycle::State & get_lifecycle_state()andvoid set_lifecycle_state(const rclcpp_lifecycle::State & new_state). This change affects controllers and hardware. This is related to (#1240) as variant support introducesget_stateandset_statemethods for setting/getting state of handles.A new
get_optionalthat returns astd::optionalwas added to theCommandInterfaceandStateInterface. This can be used to check if the value is available or not. (#1976 and #2061)The
thread_priorityvariable in theHardwareInfostruct has been deprecated in favor of newly introducedasync_paramsvariable that has more options in theHardwareComponentParamsstruct. The deprecatedthread_priorityvariable will be removed in a future release. (# 2477).
Adaption of Command-/StateInterfaces
The handles for
Command-/StateInterfaceshave new set/get methods to access the values.Command-/StateInterfacesare now created and exported automatically by the framework via theon_export_command_interfaces()oron_export_state_interfaces()methods based on the interfaces defined in theros2_controlXML-tag, which get parsed and theInterfaceDescriptionis created accordingly (check the hardware_info.hpp). The memory is now allocated in the handle itself.
Access to Command-/StateInterfaces
Earlier code will issue compile-time warnings like:
warning: ‘double hardware_interface::Handle::get_value() const’ is deprecated: Use std::optional<T> get_optional() or bool get_value(double & value) instead to retrieve the value. [-Wdeprecated-declarations]
warning: ignoring return value of ‘bool hardware_interface::Handle::set_value(const T&) [with T = double]’ [-Wunused-result]
The old methods are deprecated and will be removed in the future. The new methods are:
std::optional<T> get_optional()for getting the value.
bool set_value(const T & value)for setting the value.
The return value bool or std::optional<T> with get_value can be used to check if the value is available or not. Similarly, the set_value method returns a bool to check if the value was set or not.
The get_value method will return an empty std::nullopt or false if the value is not available. The set_value method will return false if the value was not set.
Note
Checking the result of these operations is important as the value might not be available or the value might not be set. This is usually the case when the ros2_control framework has some asynchronous operations due to asynchronous controllers or asynchronous hardware components where different threads are involved to access the same data.
Migration of Command-/StateInterfaces
To adapt to the new way of creating and exporting Command-/StateInterfaces follow those steps:
Delete the
std::vector<hardware_interface::CommandInterface> export_command_interfaces() overrideandstd::vector<hardware_interface::StateInterface> export_state_interfaces() override.Delete allocated memory for any
Command-/StateInterfaces, e.g.:
If you have a
std::vector<double> hw_commands_;for joints’CommandInterfacesdelete the definition and any usage/appearance.Wherever you iterated over a state/command or accessed commands like this:
// states
for (uint i = 0; i < hw_states_.size(); i++)
{
hw_states_[i] = 0;
auto some_state = hw_states_[i];
}
// commands
for (uint i = 0; i < hw_commands_.size(); i++)
{
hw_commands_[i] = 0;
auto some_command = hw_commands_[i];
}
// specific state/command
hw_commands_[x] = hw_states_[y];
replace it with
// states replace with this
for (const auto & [name, descr] : joint_state_interfaces_)
{
set_state(name, 0.0);
auto some_state = get_state(name);
}
//commands replace with this
for (const auto & [name, descr] : joint_commands_interfaces_)
{
set_command(name, 0.0);
auto some_command = get_command(name);
}
// replace specific state/command, for this you need to store the names which are strings
// somewhere or know them. However be careful since the names are fully qualified names which
// means that the prefix is included for the name: E.g.: prefix/joint_1/velocity
set_command(name_of_command_interface_x, get_state(name_of_state_interface_y));
Migration of unlisted Command-/StateInterfaces not defined in ros2_control XML-tag
If you want some unlisted Command-/StateInterfaces not included in the ros2_control XML-tag you can follow those steps:
Override the
virtual std::vector<hardware_interface::InterfaceDescription> export_unlisted_command_interfaces()orvirtual std::vector<hardware_interface::InterfaceDescription> export_unlisted_state_interfaces()Create the InterfaceDescription for each of the interfaces you want to create in the override
export_unlisted_command_interfaces()orexport_unlisted_state_interfaces()function, add it to a vector and return the vector:
std::vector<hardware_interface::InterfaceDescription> my_unlisted_interfaces; InterfaceInfo unlisted_interface; unlisted_interface.name = "some_unlisted_interface"; unlisted_interface.min = "-5.0"; unlisted_interface.data_type = "double"; my_unlisted_interfaces.push_back(InterfaceDescription(info_.name, unlisted_interface)); return my_unlisted_interfaces;
The unlisted interface will then be stored in either the
unlisted_command_interfaces_orunlisted_state_interfaces_map depending in which function they are created.You can access it like any other interface with the
get_state(name),set_state(name, value),get_command(name)orset_command(name, value). E.g.get_state("some_unlisted_interface").
Custom export of Command-/StateInterfaces
In case the default implementation (on_export_command_interfaces() or on_export_state_interfaces() ) for exporting the Command-/StateInterfaces is not enough you can override them. You should however consider the following things:
If you want to have unlisted interfaces available you need to call the
export_unlisted_command_interfaces()orexport_unlisted_state_interfaces()and add them to theunlisted_command_interfaces_orunlisted_state_interfaces_.Don’t forget to store the created
Command-/StateInterfacesinternally as you only returnstd::shared_ptrand the resource manager will not provide access to the createdCommand-/StateInterfacefor the hardware. So you must take care of storing them yourself.Names must be unique!