From 7090f411327fda778c29dcc3c9bd88388d528b10 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Wed, 8 May 2024 19:41:50 +0200 Subject: [PATCH 01/11] Add hardware components exception handling in resource manager (#1508) --- hardware_interface/src/resource_manager.cpp | 446 ++++++++++++++++---- 1 file changed, 354 insertions(+), 92 deletions(-) diff --git a/hardware_interface/src/resource_manager.cpp b/hardware_interface/src/resource_manager.cpp index d23965a65f..92b6d01519 100644 --- a/hardware_interface/src/resource_manager.cpp +++ b/hardware_interface/src/resource_manager.cpp @@ -67,6 +67,26 @@ auto trigger_and_print_hardware_state_transition = return result; }; +std::string interfaces_to_string( + const std::vector & start_interfaces, + const std::vector & stop_interfaces) +{ + std::stringstream ss; + ss << "Start interfaces: " << std::endl << "[" << std::endl; + for (const auto & start_if : start_interfaces) + { + ss << " " << start_if << std::endl; + } + ss << "]" << std::endl; + ss << "Stop interfaces: " << std::endl << "[" << std::endl; + for (const auto & stop_if : stop_interfaces) + { + ss << " " << stop_if << std::endl; + } + ss << "]" << std::endl; + return ss.str(); +}; + class ResourceStorage { static constexpr const char * pkg_name = "hardware_interface"; @@ -90,27 +110,62 @@ class ResourceStorage } template - void load_hardware( + [[nodiscard]] bool load_hardware( const HardwareInfo & hardware_info, pluginlib::ClassLoader & loader, std::vector & container) { - RCUTILS_LOG_INFO_NAMED( - "resource_manager", "Loading hardware '%s' ", hardware_info.name.c_str()); - // hardware_plugin_name has to match class name in plugin xml description - auto interface = std::unique_ptr( - loader.createUnmanagedInstance(hardware_info.hardware_plugin_name)); - HardwareT hardware(std::move(interface)); - container.emplace_back(std::move(hardware)); - // initialize static data about hardware component to reduce later calls - HardwareComponentInfo component_info; - component_info.name = hardware_info.name; - component_info.type = hardware_info.type; - component_info.plugin_name = hardware_info.hardware_plugin_name; - component_info.is_async = hardware_info.is_async; - - hardware_info_map_.insert(std::make_pair(component_info.name, component_info)); - hardware_used_by_controllers_.insert( - std::make_pair(component_info.name, std::vector())); + bool is_loaded = false; + try + { + RCUTILS_LOG_INFO_NAMED( + "resource_manager", "Loading hardware '%s' ", hardware_info.name.c_str()); + // hardware_plugin_name has to match class name in plugin xml description + auto interface = std::unique_ptr( + loader.createUnmanagedInstance(hardware_info.hardware_plugin_name)); + if (interface) + { + RCUTILS_LOG_INFO_NAMED( + "resource_manager", "Loaded hardware '%s' from plugin '%s'", hardware_info.name.c_str(), + hardware_info.hardware_plugin_name.c_str()); + HardwareT hardware(std::move(interface)); + container.emplace_back(std::move(hardware)); + // initialize static data about hardware component to reduce later calls + HardwareComponentInfo component_info; + component_info.name = hardware_info.name; + component_info.type = hardware_info.type; + component_info.plugin_name = hardware_info.hardware_plugin_name; + component_info.is_async = hardware_info.is_async; + + hardware_info_map_.insert(std::make_pair(component_info.name, component_info)); + hardware_used_by_controllers_.insert( + std::make_pair(component_info.name, std::vector())); + is_loaded = true; + } + else + { + RCUTILS_LOG_ERROR_NAMED( + "resource_manager", "Failed to load hardware '%s' from plugin '%s'", + hardware_info.name.c_str(), hardware_info.hardware_plugin_name.c_str()); + } + } + catch (const pluginlib::PluginlibException & ex) + { + RCUTILS_LOG_ERROR_NAMED( + "resource_manager", "Exception while loading hardware: %s", ex.what()); + } + catch (const std::exception & ex) + { + RCUTILS_LOG_ERROR_NAMED( + "resource_manager", "Exception occurred while loading hardware '%s': %s", + hardware_info.name.c_str(), ex.what()); + } + catch (...) + { + RCUTILS_LOG_ERROR_NAMED( + "resource_manager", "Unknown exception occurred while loading hardware '%s'", + hardware_info.name.c_str()); + } + return is_loaded; } template @@ -119,30 +174,62 @@ class ResourceStorage RCUTILS_LOG_INFO_NAMED( "resource_manager", "Initialize hardware '%s' ", hardware_info.name.c_str()); - const rclcpp_lifecycle::State new_state = hardware.initialize(hardware_info); - - bool result = new_state.id() == lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED; + bool result = false; + try + { + const rclcpp_lifecycle::State new_state = hardware.initialize(hardware_info); + result = new_state.id() == lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED; - if (result) + if (result) + { + RCUTILS_LOG_INFO_NAMED( + "resource_manager", "Successful initialization of hardware '%s'", + hardware_info.name.c_str()); + } + else + { + RCUTILS_LOG_INFO_NAMED( + "resource_manager", "Failed to initialize hardware '%s'", hardware_info.name.c_str()); + } + } + catch (const std::exception & ex) { - RCUTILS_LOG_INFO_NAMED( - "resource_manager", "Successful initialization of hardware '%s'", - hardware_info.name.c_str()); + RCUTILS_LOG_ERROR_NAMED( + "resource_manager", "Exception occurred while initializing hardware '%s': %s", + hardware_info.name.c_str(), ex.what()); } - else + catch (...) { - RCUTILS_LOG_INFO_NAMED( - "resource_manager", "Failed to initialize hardware '%s'", hardware_info.name.c_str()); + RCUTILS_LOG_ERROR_NAMED( + "resource_manager", "Unknown exception occurred while initializing hardware '%s'", + hardware_info.name.c_str()); } + return result; } template bool configure_hardware(HardwareT & hardware) { - bool result = trigger_and_print_hardware_state_transition( - std::bind(&HardwareT::configure, &hardware), "configure", hardware.get_name(), - lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE); + bool result = false; + try + { + result = trigger_and_print_hardware_state_transition( + std::bind(&HardwareT::configure, &hardware), "configure", hardware.get_name(), + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE); + } + catch (const std::exception & ex) + { + RCUTILS_LOG_ERROR_NAMED( + "resource_manager", "Exception occurred while configuring hardware '%s': %s", + hardware.get_name().c_str(), ex.what()); + } + catch (...) + { + RCUTILS_LOG_ERROR_NAMED( + "resource_manager", "Unknown exception occurred while configuring hardware '%s'", + hardware.get_name().c_str()); + } if (result) { @@ -269,9 +356,25 @@ class ResourceStorage template bool cleanup_hardware(HardwareT & hardware) { - bool result = trigger_and_print_hardware_state_transition( - std::bind(&HardwareT::cleanup, &hardware), "cleanup", hardware.get_name(), - lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED); + bool result = false; + try + { + result = trigger_and_print_hardware_state_transition( + std::bind(&HardwareT::cleanup, &hardware), "cleanup", hardware.get_name(), + lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED); + } + catch (const std::exception & ex) + { + RCUTILS_LOG_ERROR_NAMED( + "resource_manager", "Exception occurred while cleaning up hardware '%s': %s", + hardware.get_name().c_str(), ex.what()); + } + catch (...) + { + RCUTILS_LOG_ERROR_NAMED( + "resource_manager", "Unknown exception occurred while cleaning up hardware '%s'", + hardware.get_name().c_str()); + } if (result) { @@ -283,9 +386,25 @@ class ResourceStorage template bool shutdown_hardware(HardwareT & hardware) { - bool result = trigger_and_print_hardware_state_transition( - std::bind(&HardwareT::shutdown, &hardware), "shutdown", hardware.get_name(), - lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED); + bool result = false; + try + { + result = trigger_and_print_hardware_state_transition( + std::bind(&HardwareT::shutdown, &hardware), "shutdown", hardware.get_name(), + lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED); + } + catch (const std::exception & ex) + { + RCUTILS_LOG_ERROR_NAMED( + "resource_manager", "Exception occurred while shutting down hardware '%s': %s", + hardware.get_name().c_str(), ex.what()); + } + catch (...) + { + RCUTILS_LOG_ERROR_NAMED( + "resource_manager", "Unknown exception occurred while shutting down hardware '%s'", + hardware.get_name().c_str()); + } if (result) { @@ -302,9 +421,25 @@ class ResourceStorage template bool activate_hardware(HardwareT & hardware) { - bool result = trigger_and_print_hardware_state_transition( - std::bind(&HardwareT::activate, &hardware), "activate", hardware.get_name(), - lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE); + bool result = false; + try + { + result = trigger_and_print_hardware_state_transition( + std::bind(&HardwareT::activate, &hardware), "activate", hardware.get_name(), + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE); + } + catch (const std::exception & ex) + { + RCUTILS_LOG_ERROR_NAMED( + "resource_manager", "Exception occurred while activating hardware '%s': %s", + hardware.get_name().c_str(), ex.what()); + } + catch (...) + { + RCUTILS_LOG_ERROR_NAMED( + "resource_manager", "Unknown exception occurred while activating hardware '%s'", + hardware.get_name().c_str()); + } if (result) { @@ -321,9 +456,25 @@ class ResourceStorage template bool deactivate_hardware(HardwareT & hardware) { - bool result = trigger_and_print_hardware_state_transition( - std::bind(&HardwareT::deactivate, &hardware), "deactivate", hardware.get_name(), - lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE); + bool result = false; + try + { + result = trigger_and_print_hardware_state_transition( + std::bind(&HardwareT::deactivate, &hardware), "deactivate", hardware.get_name(), + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE); + } + catch (const std::exception & ex) + { + RCUTILS_LOG_ERROR_NAMED( + "resource_manager", "Exception occurred while deactivating hardware '%s': %s", + hardware.get_name().c_str(), ex.what()); + } + catch (...) + { + RCUTILS_LOG_ERROR_NAMED( + "resource_manager", "Unknown exception occurred while deactivating hardware '%s'", + hardware.get_name().c_str()); + } if (result) { @@ -435,25 +586,60 @@ class ResourceStorage template void import_state_interfaces(HardwareT & hardware) { - auto interfaces = hardware.export_state_interfaces(); - std::vector interface_names; - interface_names.reserve(interfaces.size()); - for (auto & interface : interfaces) + try { - auto key = interface.get_name(); - state_interface_map_.emplace(std::make_pair(key, std::move(interface))); - interface_names.push_back(key); + auto interfaces = hardware.export_state_interfaces(); + std::vector interface_names; + interface_names.reserve(interfaces.size()); + for (auto & interface : interfaces) + { + auto key = interface.get_name(); + state_interface_map_.emplace(std::make_pair(key, std::move(interface))); + interface_names.push_back(key); + } + hardware_info_map_[hardware.get_name()].state_interfaces = interface_names; + available_state_interfaces_.reserve( + available_state_interfaces_.capacity() + interface_names.size()); + } + catch (const std::exception & e) + { + RCUTILS_LOG_ERROR_NAMED( + "resource_manager", + "Exception occurred while importing state interfaces for the hardware '%s' : %s", + hardware.get_name().c_str(), e.what()); + } + catch (...) + { + RCUTILS_LOG_ERROR_NAMED( + "resource_manager", + "Unknown exception occurred while importing state interfaces for the hardware '%s'", + hardware.get_name().c_str()); } - hardware_info_map_[hardware.get_name()].state_interfaces = interface_names; - available_state_interfaces_.reserve( - available_state_interfaces_.capacity() + interface_names.size()); } template void import_command_interfaces(HardwareT & hardware) { - auto interfaces = hardware.export_command_interfaces(); - hardware_info_map_[hardware.get_name()].command_interfaces = add_command_interfaces(interfaces); + try + { + auto interfaces = hardware.export_command_interfaces(); + hardware_info_map_[hardware.get_name()].command_interfaces = + add_command_interfaces(interfaces); + } + catch (const std::exception & ex) + { + RCUTILS_LOG_ERROR_NAMED( + "resource_manager", + "Exception occurred while importing command interfaces for the hardware '%s' : %s", + hardware.get_name().c_str(), ex.what()); + } + catch (...) + { + RCUTILS_LOG_ERROR_NAMED( + "resource_manager", + "Unknown exception occurred while importing command interfaces for the hardware '%s'", + hardware.get_name().c_str()); + } } /// Adds exported command interfaces into internal storage. @@ -516,7 +702,10 @@ class ResourceStorage auto load_and_init_actuators = [&](auto & container) { check_for_duplicates(hardware_info); - load_hardware(hardware_info, actuator_loader_, container); + if (!load_hardware(hardware_info, actuator_loader_, container)) + { + return; + } if (initialize_hardware(hardware_info, container.back())) { import_state_interfaces(container.back()); @@ -546,7 +735,10 @@ class ResourceStorage auto load_and_init_sensors = [&](auto & container) { check_for_duplicates(hardware_info); - load_hardware(hardware_info, sensor_loader_, container); + if (!load_hardware(hardware_info, sensor_loader_, container)) + { + return; + } if (initialize_hardware(hardware_info, container.back())) { import_state_interfaces(container.back()); @@ -575,7 +767,10 @@ class ResourceStorage auto load_and_init_systems = [&](auto & container) { check_for_duplicates(hardware_info); - load_hardware(hardware_info, system_loader_, container); + if (!load_hardware(hardware_info, system_loader_, container)) + { + return; + } if (initialize_hardware(hardware_info, container.back())) { import_state_interfaces(container.back()); @@ -1085,24 +1280,6 @@ bool ResourceManager::prepare_command_mode_switch( return true; } - auto interfaces_to_string = [&]() - { - std::stringstream ss; - ss << "Start interfaces: " << std::endl << "[" << std::endl; - for (const auto & start_if : start_interfaces) - { - ss << " " << start_if << std::endl; - } - ss << "]" << std::endl; - ss << "Stop interfaces: " << std::endl << "[" << std::endl; - for (const auto & stop_if : stop_interfaces) - { - ss << " " << stop_if << std::endl; - } - ss << "]" << std::endl; - return ss.str(); - }; - // Check if interface exists std::stringstream ss_not_existing; ss_not_existing << "Not existing: " << std::endl << "[" << std::endl; @@ -1124,7 +1301,8 @@ bool ResourceManager::prepare_command_mode_switch( ss_not_existing << "]" << std::endl; RCUTILS_LOG_ERROR_NAMED( "resource_manager", "Not acceptable command interfaces combination: \n%s%s", - interfaces_to_string().c_str(), ss_not_existing.str().c_str()); + interfaces_to_string(start_interfaces, stop_interfaces).c_str(), + ss_not_existing.str().c_str()); return false; } @@ -1149,12 +1327,12 @@ bool ResourceManager::prepare_command_mode_switch( ss_not_available << "]" << std::endl; RCUTILS_LOG_ERROR_NAMED( "resource_manager", "Not acceptable command interfaces combination: \n%s%s", - interfaces_to_string().c_str(), ss_not_available.str().c_str()); + interfaces_to_string(start_interfaces, stop_interfaces).c_str(), + ss_not_available.str().c_str()); return false; } - auto call_prepare_mode_switch = - [&start_interfaces, &stop_interfaces, &interfaces_to_string](auto & components) + auto call_prepare_mode_switch = [&start_interfaces, &stop_interfaces](auto & components) { bool ret = true; for (auto & component : components) @@ -1163,14 +1341,38 @@ bool ResourceManager::prepare_command_mode_switch( component.get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE || component.get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) { - if ( - return_type::OK != - component.prepare_command_mode_switch(start_interfaces, stop_interfaces)) + try + { + if ( + return_type::OK != + component.prepare_command_mode_switch(start_interfaces, stop_interfaces)) + { + RCUTILS_LOG_ERROR_NAMED( + "resource_manager", + "Component '%s' did not accept command interfaces combination: \n%s", + component.get_name().c_str(), + interfaces_to_string(start_interfaces, stop_interfaces).c_str()); + ret = false; + } + } + catch (const std::exception & e) { RCUTILS_LOG_ERROR_NAMED( "resource_manager", - "Component '%s' did not accept command interfaces combination: \n%s", - component.get_name().c_str(), interfaces_to_string().c_str()); + "Exception occurred while preparing command mode switch for component '%s' for the " + "interfaces: \n %s : %s", + component.get_name().c_str(), + interfaces_to_string(start_interfaces, stop_interfaces).c_str(), e.what()); + ret = false; + } + catch (...) + { + RCUTILS_LOG_ERROR_NAMED( + "resource_manager", + "Unknown exception occurred while preparing command mode switch for component '%s' for " + "the interfaces: \n %s", + component.get_name().c_str(), + interfaces_to_string(start_interfaces, stop_interfaces).c_str()); ret = false; } } @@ -1204,13 +1406,37 @@ bool ResourceManager::perform_command_mode_switch( component.get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE || component.get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) { - if ( - return_type::OK != - component.perform_command_mode_switch(start_interfaces, stop_interfaces)) + try + { + if ( + return_type::OK != + component.perform_command_mode_switch(start_interfaces, stop_interfaces)) + { + RCUTILS_LOG_ERROR_NAMED( + "resource_manager", "Component '%s' could not perform switch", + component.get_name().c_str()); + ret = false; + } + } + catch (const std::exception & e) { RCUTILS_LOG_ERROR_NAMED( - "resource_manager", "Component '%s' could not perform switch", - component.get_name().c_str()); + "resource_manager", + "Exception occurred while performing command mode switch for component '%s' for the " + "interfaces: \n %s : %s", + component.get_name().c_str(), + interfaces_to_string(start_interfaces, stop_interfaces).c_str(), e.what()); + ret = false; + } + catch (...) + { + RCUTILS_LOG_ERROR_NAMED( + "resource_manager", + "Unknown exception occurred while performing command mode switch for component '%s' " + "for " + "the interfaces: \n %s", + component.get_name().c_str(), + interfaces_to_string(start_interfaces, stop_interfaces).c_str()); ret = false; } } @@ -1345,7 +1571,25 @@ HardwareReadWriteStatus ResourceManager::read( { for (auto & component : components) { - auto ret_val = component.read(time, period); + auto ret_val = return_type::OK; + try + { + ret_val = component.read(time, period); + } + catch (const std::exception & e) + { + RCUTILS_LOG_ERROR_NAMED( + "resource_manager", "Exception thrown durind read of the component '%s': %s", + component.get_name().c_str(), e.what()); + ret_val = return_type::ERROR; + } + catch (...) + { + RCUTILS_LOG_ERROR_NAMED( + "resource_manager", "Unknown exception thrown during read of the component '%s'", + component.get_name().c_str()); + ret_val = return_type::ERROR; + } if (ret_val == return_type::ERROR) { read_write_status.ok = false; @@ -1385,7 +1629,25 @@ HardwareReadWriteStatus ResourceManager::write( { for (auto & component : components) { - auto ret_val = component.write(time, period); + auto ret_val = return_type::OK; + try + { + ret_val = component.write(time, period); + } + catch (const std::exception & e) + { + RCUTILS_LOG_ERROR_NAMED( + "resource_manager", "Exception thrown during write of the component '%s': %s", + component.get_name().c_str(), e.what()); + ret_val = return_type::ERROR; + } + catch (...) + { + RCUTILS_LOG_ERROR_NAMED( + "resource_manager", "Unknown exception thrown during write of the component '%s'", + component.get_name().c_str()); + ret_val = return_type::ERROR; + } if (ret_val == return_type::ERROR) { read_write_status.ok = false; From fc25478964827d1ae898d60419b2f4dca83a6a45 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Wed, 8 May 2024 21:34:01 +0200 Subject: [PATCH 02/11] allow extra spawner arguments to not declare every argument in launch utils (#1505) --- controller_manager/controller_manager/launch_utils.py | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/controller_manager/controller_manager/launch_utils.py b/controller_manager/controller_manager/launch_utils.py index c7c5974a94..01528552d0 100644 --- a/controller_manager/controller_manager/launch_utils.py +++ b/controller_manager/controller_manager/launch_utils.py @@ -21,7 +21,7 @@ def generate_load_controller_launch_description( - controller_name, controller_type=None, controller_params_file=None + controller_name, controller_type=None, controller_params_file=None, extra_spawner_args=[] ): """ Generate launch description for loading a controller using spawner. @@ -40,7 +40,8 @@ def generate_load_controller_launch_description( 'joint_state_broadcaster', controller_type='joint_state_broadcaster/JointStateBroadcaster', controller_params_file=os.path.join(get_package_share_directory('my_pkg'), - 'config', 'controller_params.yaml') + 'config', 'controller_params.yaml'), + extra_spawner_args=[--load-only] ) """ @@ -86,6 +87,9 @@ def generate_load_controller_launch_description( ) ] + if extra_spawner_args: + spawner_arguments += extra_spawner_args + spawner = Node( package="controller_manager", executable="spawner", From f9d9964c656d32e89a09d3f921c529a7ce6bb0f2 Mon Sep 17 00:00:00 2001 From: Bence Magyar Date: Wed, 8 May 2024 20:37:16 +0100 Subject: [PATCH 03/11] Update changelogs --- controller_interface/CHANGELOG.rst | 5 +++++ controller_manager/CHANGELOG.rst | 9 +++++++++ controller_manager_msgs/CHANGELOG.rst | 3 +++ hardware_interface/CHANGELOG.rst | 9 +++++++++ hardware_interface_testing/CHANGELOG.rst | 3 +++ joint_limits/CHANGELOG.rst | 3 +++ ros2_control/CHANGELOG.rst | 3 +++ ros2_control_test_assets/CHANGELOG.rst | 5 +++++ ros2controlcli/CHANGELOG.rst | 3 +++ rqt_controller_manager/CHANGELOG.rst | 3 +++ transmission_interface/CHANGELOG.rst | 3 +++ 11 files changed, 49 insertions(+) diff --git a/controller_interface/CHANGELOG.rst b/controller_interface/CHANGELOG.rst index 1688434cfc..be6fd4712f 100644 --- a/controller_interface/CHANGELOG.rst +++ b/controller_interface/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package controller_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Working async controllers and components [not synchronized] (`#1041 `_) +* Contributors: Márk Szitanics + 4.9.0 (2024-04-30) ------------------ * return the proper const object of the pointer in the const method (`#1494 `_) diff --git a/controller_manager/CHANGELOG.rst b/controller_manager/CHANGELOG.rst index 74657cd12b..8a2c595139 100644 --- a/controller_manager/CHANGELOG.rst +++ b/controller_manager/CHANGELOG.rst @@ -2,6 +2,15 @@ Changelog for package controller_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* allow extra spawner arguments to not declare every argument in launch utils (`#1505 `_) +* Working async controllers and components [not synchronized] (`#1041 `_) +* Add fallback controllers list to the ControllerInfo (`#1503 `_) +* Add a functionality to look for the controller type in the params file when not parsed (`#1502 `_) +* Add controller exception handling in controller manager (`#1507 `_) +* Contributors: Márk Szitanics, Sai Kishor Kothakota + 4.9.0 (2024-04-30) ------------------ * Deactivate the controllers when they return error similar to hardware (`#1499 `_) diff --git a/controller_manager_msgs/CHANGELOG.rst b/controller_manager_msgs/CHANGELOG.rst index 6491f5e292..7d2ee0fe1b 100644 --- a/controller_manager_msgs/CHANGELOG.rst +++ b/controller_manager_msgs/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package controller_manager_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.9.0 (2024-04-30) ------------------ diff --git a/hardware_interface/CHANGELOG.rst b/hardware_interface/CHANGELOG.rst index 6e1528bc15..dc72ee3071 100644 --- a/hardware_interface/CHANGELOG.rst +++ b/hardware_interface/CHANGELOG.rst @@ -2,6 +2,15 @@ Changelog for package hardware_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Add hardware components exception handling in resource manager (`#1508 `_) +* Working async controllers and components [not synchronized] (`#1041 `_) +* Parse URDF joint hard limits into the HardwareInfo structure (`#1472 `_) +* Add fallback controllers list to the ControllerInfo (`#1503 `_) +* Add more common hardware interface type constants (`#1500 `_) +* Contributors: Márk Szitanics, Sai Kishor Kothakota + 4.9.0 (2024-04-30) ------------------ * Add missing calculate_dynamics (`#1498 `_) diff --git a/hardware_interface_testing/CHANGELOG.rst b/hardware_interface_testing/CHANGELOG.rst index 13161cdd4c..5bc6f05497 100644 --- a/hardware_interface_testing/CHANGELOG.rst +++ b/hardware_interface_testing/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package hardware_interface_testing ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.9.0 (2024-04-30) ------------------ * Component parser: Get mimic information from URDF (`#1256 `_) diff --git a/joint_limits/CHANGELOG.rst b/joint_limits/CHANGELOG.rst index 2bf49a13ec..30877f9b40 100644 --- a/joint_limits/CHANGELOG.rst +++ b/joint_limits/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package joint_limits ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.9.0 (2024-04-30) ------------------ diff --git a/ros2_control/CHANGELOG.rst b/ros2_control/CHANGELOG.rst index aa93e8cc1b..6cd52544ef 100644 --- a/ros2_control/CHANGELOG.rst +++ b/ros2_control/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package ros2_control ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.9.0 (2024-04-30) ------------------ diff --git a/ros2_control_test_assets/CHANGELOG.rst b/ros2_control_test_assets/CHANGELOG.rst index b3ab824fea..42f6ed1b78 100644 --- a/ros2_control_test_assets/CHANGELOG.rst +++ b/ros2_control_test_assets/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package ros2_control_test_assets ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Parse URDF joint hard limits into the HardwareInfo structure (`#1472 `_) +* Contributors: Sai Kishor Kothakota + 4.9.0 (2024-04-30) ------------------ * Component parser: Get mimic information from URDF (`#1256 `_) diff --git a/ros2controlcli/CHANGELOG.rst b/ros2controlcli/CHANGELOG.rst index 16946acdce..34f645ef83 100644 --- a/ros2controlcli/CHANGELOG.rst +++ b/ros2controlcli/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package ros2controlcli ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.9.0 (2024-04-30) ------------------ * [CI] Specify runner/container images and codecov for joint_limits (`#1504 `_) diff --git a/rqt_controller_manager/CHANGELOG.rst b/rqt_controller_manager/CHANGELOG.rst index 1691c2c8d5..4e5577b55d 100644 --- a/rqt_controller_manager/CHANGELOG.rst +++ b/rqt_controller_manager/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package rqt_controller_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.9.0 (2024-04-30) ------------------ diff --git a/transmission_interface/CHANGELOG.rst b/transmission_interface/CHANGELOG.rst index 94e13cd793..88e5092ed4 100644 --- a/transmission_interface/CHANGELOG.rst +++ b/transmission_interface/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package transmission_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.9.0 (2024-04-30) ------------------ * rosdoc2 for transmission_interface (`#1496 `_) From 2a1b2912d01aaa695a48185ff771401d6d02dcbd Mon Sep 17 00:00:00 2001 From: Bence Magyar Date: Wed, 8 May 2024 20:37:31 +0100 Subject: [PATCH 04/11] 4.10.0 --- controller_interface/CHANGELOG.rst | 4 ++-- controller_interface/package.xml | 2 +- controller_manager/CHANGELOG.rst | 4 ++-- controller_manager/package.xml | 2 +- controller_manager_msgs/CHANGELOG.rst | 4 ++-- controller_manager_msgs/package.xml | 2 +- hardware_interface/CHANGELOG.rst | 4 ++-- hardware_interface/package.xml | 2 +- hardware_interface_testing/CHANGELOG.rst | 4 ++-- hardware_interface_testing/package.xml | 2 +- joint_limits/CHANGELOG.rst | 4 ++-- joint_limits/package.xml | 2 +- ros2_control/CHANGELOG.rst | 4 ++-- ros2_control/package.xml | 2 +- ros2_control_test_assets/CHANGELOG.rst | 4 ++-- ros2_control_test_assets/package.xml | 2 +- ros2controlcli/CHANGELOG.rst | 4 ++-- ros2controlcli/package.xml | 2 +- ros2controlcli/setup.py | 2 +- rqt_controller_manager/CHANGELOG.rst | 4 ++-- rqt_controller_manager/package.xml | 2 +- rqt_controller_manager/setup.py | 2 +- transmission_interface/CHANGELOG.rst | 4 ++-- transmission_interface/package.xml | 2 +- 24 files changed, 35 insertions(+), 35 deletions(-) diff --git a/controller_interface/CHANGELOG.rst b/controller_interface/CHANGELOG.rst index be6fd4712f..b8301e0cba 100644 --- a/controller_interface/CHANGELOG.rst +++ b/controller_interface/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package controller_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.10.0 (2024-05-08) +------------------- * Working async controllers and components [not synchronized] (`#1041 `_) * Contributors: Márk Szitanics diff --git a/controller_interface/package.xml b/controller_interface/package.xml index 9e8010eeb9..a4b89265e3 100644 --- a/controller_interface/package.xml +++ b/controller_interface/package.xml @@ -2,7 +2,7 @@ controller_interface - 4.9.0 + 4.10.0 Description of controller_interface Bence Magyar Denis Štogl diff --git a/controller_manager/CHANGELOG.rst b/controller_manager/CHANGELOG.rst index 8a2c595139..4c5e9579ef 100644 --- a/controller_manager/CHANGELOG.rst +++ b/controller_manager/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package controller_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.10.0 (2024-05-08) +------------------- * allow extra spawner arguments to not declare every argument in launch utils (`#1505 `_) * Working async controllers and components [not synchronized] (`#1041 `_) * Add fallback controllers list to the ControllerInfo (`#1503 `_) diff --git a/controller_manager/package.xml b/controller_manager/package.xml index 884ffa9384..ec5b0e4f0e 100644 --- a/controller_manager/package.xml +++ b/controller_manager/package.xml @@ -2,7 +2,7 @@ controller_manager - 4.9.0 + 4.10.0 Description of controller_manager Bence Magyar Denis Štogl diff --git a/controller_manager_msgs/CHANGELOG.rst b/controller_manager_msgs/CHANGELOG.rst index 7d2ee0fe1b..cf752dde2a 100644 --- a/controller_manager_msgs/CHANGELOG.rst +++ b/controller_manager_msgs/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package controller_manager_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.10.0 (2024-05-08) +------------------- 4.9.0 (2024-04-30) ------------------ diff --git a/controller_manager_msgs/package.xml b/controller_manager_msgs/package.xml index 32264bd09e..1f078be2cf 100644 --- a/controller_manager_msgs/package.xml +++ b/controller_manager_msgs/package.xml @@ -2,7 +2,7 @@ controller_manager_msgs - 4.9.0 + 4.10.0 Messages and services for the controller manager. Bence Magyar Denis Štogl diff --git a/hardware_interface/CHANGELOG.rst b/hardware_interface/CHANGELOG.rst index dc72ee3071..a27d097d6e 100644 --- a/hardware_interface/CHANGELOG.rst +++ b/hardware_interface/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package hardware_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.10.0 (2024-05-08) +------------------- * Add hardware components exception handling in resource manager (`#1508 `_) * Working async controllers and components [not synchronized] (`#1041 `_) * Parse URDF joint hard limits into the HardwareInfo structure (`#1472 `_) diff --git a/hardware_interface/package.xml b/hardware_interface/package.xml index b79d280a11..33dea58c73 100644 --- a/hardware_interface/package.xml +++ b/hardware_interface/package.xml @@ -1,7 +1,7 @@ hardware_interface - 4.9.0 + 4.10.0 ros2_control hardware interface Bence Magyar Denis Štogl diff --git a/hardware_interface_testing/CHANGELOG.rst b/hardware_interface_testing/CHANGELOG.rst index 5bc6f05497..cecc4e220c 100644 --- a/hardware_interface_testing/CHANGELOG.rst +++ b/hardware_interface_testing/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package hardware_interface_testing ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.10.0 (2024-05-08) +------------------- 4.9.0 (2024-04-30) ------------------ diff --git a/hardware_interface_testing/package.xml b/hardware_interface_testing/package.xml index df6a035c6b..737d228df3 100644 --- a/hardware_interface_testing/package.xml +++ b/hardware_interface_testing/package.xml @@ -1,7 +1,7 @@ hardware_interface_testing - 4.9.0 + 4.10.0 ros2_control hardware interface testing Bence Magyar Denis Štogl diff --git a/joint_limits/CHANGELOG.rst b/joint_limits/CHANGELOG.rst index 30877f9b40..dba0758112 100644 --- a/joint_limits/CHANGELOG.rst +++ b/joint_limits/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package joint_limits ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.10.0 (2024-05-08) +------------------- 4.9.0 (2024-04-30) ------------------ diff --git a/joint_limits/package.xml b/joint_limits/package.xml index e548387f48..d99ad61016 100644 --- a/joint_limits/package.xml +++ b/joint_limits/package.xml @@ -1,6 +1,6 @@ joint_limits - 4.9.0 + 4.10.0 Interfaces for handling of joint limits for controllers or hardware. Bence Magyar diff --git a/ros2_control/CHANGELOG.rst b/ros2_control/CHANGELOG.rst index 6cd52544ef..a6df0c09e3 100644 --- a/ros2_control/CHANGELOG.rst +++ b/ros2_control/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package ros2_control ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.10.0 (2024-05-08) +------------------- 4.9.0 (2024-04-30) ------------------ diff --git a/ros2_control/package.xml b/ros2_control/package.xml index acb69b2069..1fa309643f 100644 --- a/ros2_control/package.xml +++ b/ros2_control/package.xml @@ -1,7 +1,7 @@ ros2_control - 4.9.0 + 4.10.0 Metapackage for ROS2 control related packages Bence Magyar Denis Štogl diff --git a/ros2_control_test_assets/CHANGELOG.rst b/ros2_control_test_assets/CHANGELOG.rst index 42f6ed1b78..4057ceaa9e 100644 --- a/ros2_control_test_assets/CHANGELOG.rst +++ b/ros2_control_test_assets/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package ros2_control_test_assets ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.10.0 (2024-05-08) +------------------- * Parse URDF joint hard limits into the HardwareInfo structure (`#1472 `_) * Contributors: Sai Kishor Kothakota diff --git a/ros2_control_test_assets/package.xml b/ros2_control_test_assets/package.xml index fe862846c4..a76e1109a8 100644 --- a/ros2_control_test_assets/package.xml +++ b/ros2_control_test_assets/package.xml @@ -2,7 +2,7 @@ ros2_control_test_assets - 4.9.0 + 4.10.0 The package provides shared test resources for ros2_control stack Bence Magyar diff --git a/ros2controlcli/CHANGELOG.rst b/ros2controlcli/CHANGELOG.rst index 34f645ef83..84a64c1fd8 100644 --- a/ros2controlcli/CHANGELOG.rst +++ b/ros2controlcli/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package ros2controlcli ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.10.0 (2024-05-08) +------------------- 4.9.0 (2024-04-30) ------------------ diff --git a/ros2controlcli/package.xml b/ros2controlcli/package.xml index fddcd2a0b4..8e2b02b266 100644 --- a/ros2controlcli/package.xml +++ b/ros2controlcli/package.xml @@ -2,7 +2,7 @@ ros2controlcli - 4.9.0 + 4.10.0 The ROS 2 command line tools for ROS2 Control. diff --git a/ros2controlcli/setup.py b/ros2controlcli/setup.py index 19fb09df99..d3ce54204e 100644 --- a/ros2controlcli/setup.py +++ b/ros2controlcli/setup.py @@ -19,7 +19,7 @@ setup( name=package_name, - version="4.9.0", + version="4.10.0", packages=find_packages(exclude=["test"]), data_files=[ ("share/" + package_name, ["package.xml"]), diff --git a/rqt_controller_manager/CHANGELOG.rst b/rqt_controller_manager/CHANGELOG.rst index 4e5577b55d..33660cc16d 100644 --- a/rqt_controller_manager/CHANGELOG.rst +++ b/rqt_controller_manager/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package rqt_controller_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.10.0 (2024-05-08) +------------------- 4.9.0 (2024-04-30) ------------------ diff --git a/rqt_controller_manager/package.xml b/rqt_controller_manager/package.xml index 3c0e5ce652..c722043890 100644 --- a/rqt_controller_manager/package.xml +++ b/rqt_controller_manager/package.xml @@ -2,7 +2,7 @@ rqt_controller_manager - 4.9.0 + 4.10.0 Graphical frontend for interacting with the controller manager. Bence Magyar Denis Štogl diff --git a/rqt_controller_manager/setup.py b/rqt_controller_manager/setup.py index 107981322a..ae79268335 100644 --- a/rqt_controller_manager/setup.py +++ b/rqt_controller_manager/setup.py @@ -20,7 +20,7 @@ setup( name=package_name, - version="4.9.0", + version="4.10.0", packages=[package_name], data_files=[ ("share/ament_index/resource_index/packages", ["resource/" + package_name]), diff --git a/transmission_interface/CHANGELOG.rst b/transmission_interface/CHANGELOG.rst index 88e5092ed4..8ac4224337 100644 --- a/transmission_interface/CHANGELOG.rst +++ b/transmission_interface/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package transmission_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.10.0 (2024-05-08) +------------------- 4.9.0 (2024-04-30) ------------------ diff --git a/transmission_interface/package.xml b/transmission_interface/package.xml index 36bbbd2a38..83da85a2ef 100644 --- a/transmission_interface/package.xml +++ b/transmission_interface/package.xml @@ -2,7 +2,7 @@ transmission_interface - 4.9.0 + 4.10.0 transmission_interface contains data structures for representing mechanical transmissions, methods for propagating values between actuator and joint spaces and tooling to support this. Bence Magyar Denis Štogl From 736d37981e9f487b6fb2d9d8f52dcdac55c1dd7b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Wed, 8 May 2024 23:56:25 +0200 Subject: [PATCH 05/11] [CI] Add jazzy and other minor updates (#1521) * Add file type filters to workflows * Add jazzy jobs and update readmes * Checkout correct branch for docs * Deactivate jazzy - coverage build * Specify workflow names * Update upstream pre-commit wf * Update coverage build inputs --------- Co-authored-by: Bence Magyar --- .github/workflows/README.md | 1 + .../workflows/humble-abi-compatibility.yml | 8 ++++ .github/workflows/humble-binary-build.yml | 16 +++++++ .github/workflows/humble-check-docs.yml | 18 ++++++++ .github/workflows/humble-coverage-build.yml | 19 +++++++- .github/workflows/humble-debian-build.yml | 8 ++++ .github/workflows/humble-pre-commit.yml | 1 - .../workflows/humble-rhel-binary-build.yml | 8 ++++ .../workflows/humble-semi-binary-build.yml | 16 +++++++ .github/workflows/humble-source-build.yml | 8 ++++ .github/workflows/iron-abi-compatibility.yml | 8 ++++ .github/workflows/iron-binary-build.yml | 16 +++++++ .github/workflows/iron-check-docs.yml | 18 ++++++++ .github/workflows/iron-coverage-build.yml | 19 +++++++- .github/workflows/iron-debian-build.yml | 8 ++++ .github/workflows/iron-pre-commit.yml | 1 - .github/workflows/iron-rhel-binary-build.yml | 8 ++++ .github/workflows/iron-semi-binary-build.yml | 16 +++++++ .github/workflows/iron-source-build.yml | 8 ++++ .github/workflows/jazzy-abi-compatibility.yml | 26 +++++++++++ .github/workflows/jazzy-binary-build.yml | 45 +++++++++++++++++++ .github/workflows/jazzy-check-docs.yml | 18 ++++++++ .github/workflows/jazzy-coverage-build.yml | 35 +++++++++++++++ .github/workflows/jazzy-debian-build.yml | 31 +++++++++++++ .github/workflows/jazzy-pre-commit.yml | 13 ++++++ .github/workflows/jazzy-rhel-binary-build.yml | 30 +++++++++++++ .github/workflows/jazzy-semi-binary-build.yml | 45 +++++++++++++++++++ .github/workflows/jazzy-source-build.yml | 26 +++++++++++ .../workflows/rolling-abi-compatibility.yml | 8 ++++ .github/workflows/rolling-binary-build.yml | 16 +++++++ ...-check-docs.yml => rolling-check-docs.yml} | 8 +++- .github/workflows/rolling-coverage-build.yml | 19 +++++++- .github/workflows/rolling-debian-build.yml | 8 ++++ .github/workflows/rolling-pre-commit.yml | 1 - .../workflows/rolling-rhel-binary-build.yml | 8 ++++ .../workflows/rolling-semi-binary-build.yml | 16 +++++++ .github/workflows/rolling-source-build.yml | 8 ++++ README.md | 1 + ros2_control-not-released.jazzy.repos | 1 + ros2_control.jazzy.repos | 9 ++++ 40 files changed, 570 insertions(+), 7 deletions(-) create mode 100644 .github/workflows/humble-check-docs.yml create mode 100644 .github/workflows/iron-check-docs.yml create mode 100644 .github/workflows/jazzy-abi-compatibility.yml create mode 100644 .github/workflows/jazzy-binary-build.yml create mode 100644 .github/workflows/jazzy-check-docs.yml create mode 100644 .github/workflows/jazzy-coverage-build.yml create mode 100644 .github/workflows/jazzy-debian-build.yml create mode 100644 .github/workflows/jazzy-pre-commit.yml create mode 100644 .github/workflows/jazzy-rhel-binary-build.yml create mode 100644 .github/workflows/jazzy-semi-binary-build.yml create mode 100644 .github/workflows/jazzy-source-build.yml rename .github/workflows/{ci-check-docs.yml => rolling-check-docs.yml} (67%) create mode 100644 ros2_control-not-released.jazzy.repos create mode 100644 ros2_control.jazzy.repos diff --git a/.github/workflows/README.md b/.github/workflows/README.md index ed64bcd94c..62007ffc2d 100644 --- a/.github/workflows/README.md +++ b/.github/workflows/README.md @@ -2,5 +2,6 @@ ROS2 Distro | Branch | Build status | Documentation | Released packages :---------: | :----: | :----------: | :-----------: | :---------------: **Rolling** | [`master`](https://github.com/ros-controls/ros2_control/tree/master) | [![Rolling Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-binary-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-binary-build.yml?branch=master)
[![Rolling Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-semi-binary-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-semi-binary-build.yml?branch=master)
[![Rolling Source Build](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-source-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-source-build.yml?branch=master)
[![Debian Rolling Source Build](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-debian-build.yml/badge.svg)](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-debian-build.yml)
[![RHEL Rolling Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-rhel-binary-build.yml/badge.svg)](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-rhel-binary-build.yml) | [Documentation](https://control.ros.org/master/index.html)
[API Reference](https://control.ros.org/master/doc/api/index.html) | [ros2_control](https://index.ros.org/p/ros2_control/#rolling) +**Jazzy** | [`master`](https://github.com/ros-controls/ros2_control/tree/master) | [![Jazzy Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/jazzy-binary-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/jazzy-binary-build.yml?branch=master)
[![Jazzy Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/jazzy-semi-binary-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/jazzy-semi-binary-build.yml?branch=master)
[![Jazzy Source Build](https://github.com/ros-controls/ros2_control/actions/workflows/jazzy-source-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/jazzy-source-build.yml?branch=master)
[![Debian Jazzy Source Build](https://github.com/ros-controls/ros2_control/actions/workflows/jazzy-debian-build.yml/badge.svg)](https://github.com/ros-controls/ros2_control/actions/workflows/jazzy-debian-build.yml)
[![RHEL Jazzy Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/jazzy-rhel-binary-build.yml/badge.svg)](https://github.com/ros-controls/ros2_control/actions/workflows/jazzy-rhel-binary-build.yml) | [Documentation](https://control.ros.org/jazzy/index.html)
[API Reference](https://control.ros.org/jazzy/doc/api/index.html) | [ros2_control](https://index.ros.org/p/ros2_control/#jazzy) **Iron** | [`iron`](https://github.com/ros-controls/ros2_control/tree/master) | [![Iron Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/iron-binary-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/iron-binary-build.yml?branch=master)
[![Iron Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/iron-semi-binary-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/iron-semi-binary-build.yml?branch=master)
[![Iron Source Build](https://github.com/ros-controls/ros2_control/actions/workflows/iron-source-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/iron-source-build.yml?branch=master)
[![Debian Iron Source Build](https://github.com/ros-controls/ros2_control/actions/workflows/iron-debian-build.yml/badge.svg)](https://github.com/ros-controls/ros2_control/actions/workflows/iron-debian-build.yml)
[![RHEL Iron Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/iron-rhel-binary-build.yml/badge.svg)](https://github.com/ros-controls/ros2_control/actions/workflows/iron-rhel-binary-build.yml) | [Documentation](https://control.ros.org/iron/index.html)
[API Reference](https://control.ros.org/iron/doc/api/index.html) | [ros2_control](https://index.ros.org/p/ros2_control/#iron) **Humble** | [`humble`](https://github.com/ros-controls/ros2_control/tree/humble) | [![Humble Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/humble-binary-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/humble-binary-build.yml?branch=master)
[![Humble Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/humble-semi-binary-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/humble-semi-binary-build.yml?branch=master)
[![Humble Source Build](https://github.com/ros-controls/ros2_control/actions/workflows/humble-source-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/humble-source-build.yml?branch=master)
[![Debian Humble Source Build](https://github.com/ros-controls/ros2_control/actions/workflows/humble-debian-build.yml/badge.svg)](https://github.com/ros-controls/ros2_control/actions/workflows/humble-debian-build.yml)
[![RHEL Humble Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/humble-rhel-binary-build.yml/badge.svg)](https://github.com/ros-controls/ros2_control/actions/workflows/humble-rhel-binary-build.yml) | [Documentation](https://control.ros.org/humble/index.html)
[API Reference](https://control.ros.org/humble/doc/api/index.html) | [ros2_control](https://index.ros.org/p/ros2_control/#humble) diff --git a/.github/workflows/humble-abi-compatibility.yml b/.github/workflows/humble-abi-compatibility.yml index 5c288fabfb..8b1950babc 100644 --- a/.github/workflows/humble-abi-compatibility.yml +++ b/.github/workflows/humble-abi-compatibility.yml @@ -4,6 +4,14 @@ on: pull_request: branches: - humble + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/humble-abi-compatibility.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control-not-released.humble.repos' jobs: abi_check: diff --git a/.github/workflows/humble-binary-build.yml b/.github/workflows/humble-binary-build.yml index 2cf14105f5..18dfae9666 100644 --- a/.github/workflows/humble-binary-build.yml +++ b/.github/workflows/humble-binary-build.yml @@ -7,9 +7,25 @@ on: pull_request: branches: - humble + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/humble-binary-build.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control-not-released.humble.repos' push: branches: - humble + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/humble-binary-build.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control-not-released.humble.repos' schedule: # Run every morning to detect flakiness and broken dependencies - cron: '03 1 * * *' diff --git a/.github/workflows/humble-check-docs.yml b/.github/workflows/humble-check-docs.yml new file mode 100644 index 0000000000..f3c31703cd --- /dev/null +++ b/.github/workflows/humble-check-docs.yml @@ -0,0 +1,18 @@ +name: Humble Check Docs + +on: + workflow_dispatch: + pull_request: + branches: + - humble + paths: + - '**.rst' + - '**.md' + - '**.yaml' + +jobs: + check-docs: + name: Check Docs + uses: ros-controls/control.ros.org/.github/workflows/reusable-sphinx-check-single-version.yml@humble + with: + ROS2_CONTROL_PR: ${{ github.ref }} diff --git a/.github/workflows/humble-coverage-build.yml b/.github/workflows/humble-coverage-build.yml index 0910572227..d699e99278 100644 --- a/.github/workflows/humble-coverage-build.yml +++ b/.github/workflows/humble-coverage-build.yml @@ -4,9 +4,27 @@ on: push: branches: - humble + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/humble-coverage-build.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control.humble.repos' + - 'codecov.yml' pull_request: branches: - humble + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/humble-coverage-build.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control.humble.repos' + - 'codecov.yml' jobs: coverage_humble: @@ -14,4 +32,3 @@ jobs: secrets: inherit with: ros_distro: humble - os_name: ubuntu-22.04 diff --git a/.github/workflows/humble-debian-build.yml b/.github/workflows/humble-debian-build.yml index 3b8a1c6287..5f0c33fa5e 100644 --- a/.github/workflows/humble-debian-build.yml +++ b/.github/workflows/humble-debian-build.yml @@ -4,6 +4,14 @@ on: pull_request: branches: - humble + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/humble-debian-build.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control.humble.repos' schedule: # Run every day to detect flakiness and broken dependencies - cron: '03 1 * * *' diff --git a/.github/workflows/humble-pre-commit.yml b/.github/workflows/humble-pre-commit.yml index be8c84b05b..5bb2408578 100644 --- a/.github/workflows/humble-pre-commit.yml +++ b/.github/workflows/humble-pre-commit.yml @@ -11,4 +11,3 @@ jobs: uses: ros-controls/ros2_control_ci/.github/workflows/reusable-pre-commit.yml@master with: ros_distro: humble - os_name: ubuntu-22.04 diff --git a/.github/workflows/humble-rhel-binary-build.yml b/.github/workflows/humble-rhel-binary-build.yml index 4c00d2f2ad..dacaf8fee5 100644 --- a/.github/workflows/humble-rhel-binary-build.yml +++ b/.github/workflows/humble-rhel-binary-build.yml @@ -4,6 +4,14 @@ on: pull_request: branches: - humble + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/humble-rhel-binary-build.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control.humble.repos' schedule: # Run every day to detect flakiness and broken dependencies - cron: '03 1 * * *' diff --git a/.github/workflows/humble-semi-binary-build.yml b/.github/workflows/humble-semi-binary-build.yml index 19637c4897..ec994cf7ff 100644 --- a/.github/workflows/humble-semi-binary-build.yml +++ b/.github/workflows/humble-semi-binary-build.yml @@ -7,9 +7,25 @@ on: pull_request: branches: - humble + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/humble-semi-binary-build.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control.humble.repos' push: branches: - humble + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/humble-semi-binary-build.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control.humble.repos' schedule: # Run every morning to detect flakiness and broken dependencies - cron: '03 1 * * *' diff --git a/.github/workflows/humble-source-build.yml b/.github/workflows/humble-source-build.yml index 6325fd50d8..5f437f8b0d 100644 --- a/.github/workflows/humble-source-build.yml +++ b/.github/workflows/humble-source-build.yml @@ -4,6 +4,14 @@ on: push: branches: - humble + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/humble-source-build.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control.humble.repos' schedule: # Run every day to detect flakiness and broken dependencies - cron: '03 3 * * *' diff --git a/.github/workflows/iron-abi-compatibility.yml b/.github/workflows/iron-abi-compatibility.yml index ab6642625f..d9476298a2 100644 --- a/.github/workflows/iron-abi-compatibility.yml +++ b/.github/workflows/iron-abi-compatibility.yml @@ -4,6 +4,14 @@ on: pull_request: branches: - iron + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/iron-abi-compatibility.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control-not-released.iron.repos' jobs: abi_check: diff --git a/.github/workflows/iron-binary-build.yml b/.github/workflows/iron-binary-build.yml index 911ccafae5..0fb0adcb1b 100644 --- a/.github/workflows/iron-binary-build.yml +++ b/.github/workflows/iron-binary-build.yml @@ -7,9 +7,25 @@ on: pull_request: branches: - iron + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/iron-binary-build.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control-not-released.iron.repos' push: branches: - iron + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/iron-binary-build.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control-not-released.iron.repos' schedule: # Run every morning to detect flakiness and broken dependencies - cron: '03 1 * * *' diff --git a/.github/workflows/iron-check-docs.yml b/.github/workflows/iron-check-docs.yml new file mode 100644 index 0000000000..e9295dad44 --- /dev/null +++ b/.github/workflows/iron-check-docs.yml @@ -0,0 +1,18 @@ +name: Iron Check Docs + +on: + workflow_dispatch: + pull_request: + branches: + - iron + paths: + - '**.rst' + - '**.md' + - '**.yaml' + +jobs: + check-docs: + name: Check Docs + uses: ros-controls/control.ros.org/.github/workflows/reusable-sphinx-check-single-version.yml@iron + with: + ROS2_CONTROL_PR: ${{ github.ref }} diff --git a/.github/workflows/iron-coverage-build.yml b/.github/workflows/iron-coverage-build.yml index d82c52bf51..c74d66c3fd 100644 --- a/.github/workflows/iron-coverage-build.yml +++ b/.github/workflows/iron-coverage-build.yml @@ -4,9 +4,27 @@ on: push: branches: - iron + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/iron-coverage-build.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control.iron.repos' + - 'codecov.yml' pull_request: branches: - iron + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/iron-coverage-build.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control.iron.repos' + - 'codecov.yml' jobs: coverage_iron: @@ -14,4 +32,3 @@ jobs: secrets: inherit with: ros_distro: iron - os_name: ubuntu-22.04 diff --git a/.github/workflows/iron-debian-build.yml b/.github/workflows/iron-debian-build.yml index ff503d64a9..2e6ba2289c 100644 --- a/.github/workflows/iron-debian-build.yml +++ b/.github/workflows/iron-debian-build.yml @@ -4,6 +4,14 @@ on: pull_request: branches: - iron + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/iron-debian-build.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control.iron.repos' schedule: # Run every day to detect flakiness and broken dependencies - cron: '03 1 * * *' diff --git a/.github/workflows/iron-pre-commit.yml b/.github/workflows/iron-pre-commit.yml index 60ad26d073..a128958031 100644 --- a/.github/workflows/iron-pre-commit.yml +++ b/.github/workflows/iron-pre-commit.yml @@ -11,4 +11,3 @@ jobs: uses: ros-controls/ros2_control_ci/.github/workflows/reusable-pre-commit.yml@master with: ros_distro: iron - os_name: ubuntu-22.04 diff --git a/.github/workflows/iron-rhel-binary-build.yml b/.github/workflows/iron-rhel-binary-build.yml index 981893524d..a45244b336 100644 --- a/.github/workflows/iron-rhel-binary-build.yml +++ b/.github/workflows/iron-rhel-binary-build.yml @@ -4,6 +4,14 @@ on: pull_request: branches: - iron + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/iron-rhel-binary-build.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control.iron.repos' schedule: # Run every day to detect flakiness and broken dependencies - cron: '03 1 * * *' diff --git a/.github/workflows/iron-semi-binary-build.yml b/.github/workflows/iron-semi-binary-build.yml index 59f8f347dd..8392655c35 100644 --- a/.github/workflows/iron-semi-binary-build.yml +++ b/.github/workflows/iron-semi-binary-build.yml @@ -7,9 +7,25 @@ on: pull_request: branches: - iron + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/iron-semi-binary-build.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control.iron.repos' push: branches: - iron + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/iron-semi-binary-build.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control.iron.repos' schedule: # Run every morning to detect flakiness and broken dependencies - cron: '03 1 * * *' diff --git a/.github/workflows/iron-source-build.yml b/.github/workflows/iron-source-build.yml index 2d12734df0..608702ab72 100644 --- a/.github/workflows/iron-source-build.yml +++ b/.github/workflows/iron-source-build.yml @@ -4,6 +4,14 @@ on: push: branches: - iron + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/iron-source-build.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control.iron.repos' schedule: # Run every day to detect flakiness and broken dependencies - cron: '03 3 * * *' diff --git a/.github/workflows/jazzy-abi-compatibility.yml b/.github/workflows/jazzy-abi-compatibility.yml new file mode 100644 index 0000000000..331234d30f --- /dev/null +++ b/.github/workflows/jazzy-abi-compatibility.yml @@ -0,0 +1,26 @@ +name: Jazzy - ABI Compatibility Check +on: + workflow_dispatch: + pull_request: + branches: + - master + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/jazzy-abi-compatibility.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control-not-released.jazzy.repos' + +jobs: + abi_check: + runs-on: ubuntu-latest + steps: + - uses: actions/checkout@v4 + - uses: ros-industrial/industrial_ci@master + env: + ROS_DISTRO: jazzy + ROS_REPO: testing + ABICHECK_URL: github:${{ github.repository }}#${{ github.base_ref }} + NOT_TEST_BUILD: true diff --git a/.github/workflows/jazzy-binary-build.yml b/.github/workflows/jazzy-binary-build.yml new file mode 100644 index 0000000000..ac335c79f4 --- /dev/null +++ b/.github/workflows/jazzy-binary-build.yml @@ -0,0 +1,45 @@ +name: Jazzy Binary Build +# author: Denis Štogl +# description: 'Build & test all dependencies from released (binary) packages.' + +on: + workflow_dispatch: + pull_request: + branches: + - master + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/jazzy-binary-build.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control-not-released.jazzy.repos' + push: + branches: + - master + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/jazzy-binary-build.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control-not-released.jazzy.repos' + schedule: + # Run every morning to detect flakiness and broken dependencies + - cron: '03 1 * * *' + +jobs: + binary: + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-industrial-ci-with-cache.yml@master + strategy: + fail-fast: false + matrix: + ROS_DISTRO: [jazzy] + ROS_REPO: [main, testing] + with: + ros_distro: ${{ matrix.ROS_DISTRO }} + ros_repo: ${{ matrix.ROS_REPO }} + upstream_workspace: ros2_control-not-released.${{ matrix.ROS_DISTRO }}.repos + ref_for_scheduled_build: master diff --git a/.github/workflows/jazzy-check-docs.yml b/.github/workflows/jazzy-check-docs.yml new file mode 100644 index 0000000000..cbdf6c30bd --- /dev/null +++ b/.github/workflows/jazzy-check-docs.yml @@ -0,0 +1,18 @@ +name: Jazzy Check Docs + +on: + workflow_dispatch: + pull_request: + branches: + - master + paths: + - '**.rst' + - '**.md' + - '**.yaml' + +jobs: + check-docs: + name: Check Docs + uses: ros-controls/control.ros.org/.github/workflows/reusable-sphinx-check-single-version.yml@jazzy + with: + ROS2_CONTROL_PR: ${{ github.ref }} diff --git a/.github/workflows/jazzy-coverage-build.yml b/.github/workflows/jazzy-coverage-build.yml new file mode 100644 index 0000000000..aa345d1e80 --- /dev/null +++ b/.github/workflows/jazzy-coverage-build.yml @@ -0,0 +1,35 @@ +name: Coverage Build - Jazzy +on: + workflow_dispatch: + # TODO(anyone) activate when branched for Jazzy + # push: + # branches: + # - master + # paths: + # - '**.hpp' + # - '**.h' + # - '**.cpp' + # - '.github/workflows/jazzy-coverage-build.yml' + # - '**/package.xml' + # - '**/CMakeLists.txt' + # - 'ros2_control.jazzy.repos' + # - 'codecov.yml' + # pull_request: + # branches: + # - master + # paths: + # - '**.hpp' + # - '**.h' + # - '**.cpp' + # - '.github/workflows/jazzy-coverage-build.yml' + # - '**/package.xml' + # - '**/CMakeLists.txt' + # - 'ros2_control.jazzy.repos' + # - 'codecov.yml' + +jobs: + coverage_jazzy: + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-build-coverage.yml@master + secrets: inherit + with: + ros_distro: jazzy diff --git a/.github/workflows/jazzy-debian-build.yml b/.github/workflows/jazzy-debian-build.yml new file mode 100644 index 0000000000..b61f101ae5 --- /dev/null +++ b/.github/workflows/jazzy-debian-build.yml @@ -0,0 +1,31 @@ +name: Debian Jazzy Source Build +on: + workflow_dispatch: + pull_request: + branches: + - master + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/jazzy-debian-build.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control.jazzy.repos' + schedule: + # Run every day to detect flakiness and broken dependencies + - cron: '03 1 * * *' + + +jobs: + debian_source_build: + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-debian-build.yml@master + strategy: + fail-fast: false + matrix: + ROS_DISTRO: [jazzy] + with: + ros_distro: ${{ matrix.ROS_DISTRO }} + upstream_workspace: ros2_control.${{ matrix.ROS_DISTRO }}.repos + ref_for_scheduled_build: master + skip_packages: rqt_controller_manager diff --git a/.github/workflows/jazzy-pre-commit.yml b/.github/workflows/jazzy-pre-commit.yml new file mode 100644 index 0000000000..d9ec610bbc --- /dev/null +++ b/.github/workflows/jazzy-pre-commit.yml @@ -0,0 +1,13 @@ +name: Pre-Commit - Jazzy + +on: + workflow_dispatch: + pull_request: + branches: + - master + +jobs: + pre-commit: + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-pre-commit.yml@master + with: + ros_distro: jazzy diff --git a/.github/workflows/jazzy-rhel-binary-build.yml b/.github/workflows/jazzy-rhel-binary-build.yml new file mode 100644 index 0000000000..1320624345 --- /dev/null +++ b/.github/workflows/jazzy-rhel-binary-build.yml @@ -0,0 +1,30 @@ +name: RHEL Jazzy Semi-Binary Build +on: + workflow_dispatch: + pull_request: + branches: + - master + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/jazzy-rhel-binary-build.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control.jazzy.repos' + schedule: + # Run every day to detect flakiness and broken dependencies + - cron: '03 1 * * *' + +jobs: + rhel_semi_binary_build: + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-rhel-binary-build.yml@master + strategy: + fail-fast: false + matrix: + ROS_DISTRO: [jazzy] + with: + ros_distro: ${{ matrix.ROS_DISTRO }} + upstream_workspace: ros2_control.${{ matrix.ROS_DISTRO }}.repos + ref_for_scheduled_build: master + skip_packages: rqt_controller_manager diff --git a/.github/workflows/jazzy-semi-binary-build.yml b/.github/workflows/jazzy-semi-binary-build.yml new file mode 100644 index 0000000000..b6c669245a --- /dev/null +++ b/.github/workflows/jazzy-semi-binary-build.yml @@ -0,0 +1,45 @@ +name: Jazzy Semi-Binary Build +# author: Denis Štogl +# description: 'Build & test all dependencies from released (binary) packages.' + +on: + workflow_dispatch: + pull_request: + branches: + - master + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/jazzy-semi-binary-build.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control.jazzy.repos' + push: + branches: + - master + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/jazzy-semi-binary-build.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control.jazzy.repos' + schedule: + # Run every morning to detect flakiness and broken dependencies + - cron: '03 1 * * *' + +jobs: + binary: + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-industrial-ci-with-cache.yml@master + strategy: + fail-fast: false + matrix: + ROS_DISTRO: [jazzy] + ROS_REPO: [main, testing] + with: + ros_distro: ${{ matrix.ROS_DISTRO }} + ros_repo: ${{ matrix.ROS_REPO }} + upstream_workspace: ros2_control.${{ matrix.ROS_DISTRO }}.repos + ref_for_scheduled_build: master diff --git a/.github/workflows/jazzy-source-build.yml b/.github/workflows/jazzy-source-build.yml new file mode 100644 index 0000000000..1acadc4a12 --- /dev/null +++ b/.github/workflows/jazzy-source-build.yml @@ -0,0 +1,26 @@ +name: Jazzy Source Build +on: + workflow_dispatch: + push: + branches: + - master + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/jazzy-source-build.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control.jazzy.repos' + schedule: + # Run every day to detect flakiness and broken dependencies + - cron: '03 3 * * *' + +jobs: + source: + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-ros-tooling-source-build.yml@master + with: + ros_distro: jazzy + ref: master + ros2_repo_branch: master + container: ubuntu:24.04 diff --git a/.github/workflows/rolling-abi-compatibility.yml b/.github/workflows/rolling-abi-compatibility.yml index 73055ef3e5..52b3ae8c57 100644 --- a/.github/workflows/rolling-abi-compatibility.yml +++ b/.github/workflows/rolling-abi-compatibility.yml @@ -4,6 +4,14 @@ on: pull_request: branches: - master + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/rolling-abi-compatibility.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control-not-released.rolling.repos' jobs: abi_check: diff --git a/.github/workflows/rolling-binary-build.yml b/.github/workflows/rolling-binary-build.yml index b083cc46fc..f556962d3a 100644 --- a/.github/workflows/rolling-binary-build.yml +++ b/.github/workflows/rolling-binary-build.yml @@ -7,9 +7,25 @@ on: pull_request: branches: - master + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/rolling-binary-build.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control-not-released.rolling.repos' push: branches: - master + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/rolling-binary-build.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control-not-released.rolling.repos' schedule: # Run every morning to detect flakiness and broken dependencies - cron: '03 1 * * *' diff --git a/.github/workflows/ci-check-docs.yml b/.github/workflows/rolling-check-docs.yml similarity index 67% rename from .github/workflows/ci-check-docs.yml rename to .github/workflows/rolling-check-docs.yml index 90a822aa72..80e8287abd 100644 --- a/.github/workflows/ci-check-docs.yml +++ b/.github/workflows/rolling-check-docs.yml @@ -1,8 +1,14 @@ -name: Check Docs +name: Rolling Check Docs on: workflow_dispatch: pull_request: + branches: + - master + paths: + - '**.rst' + - '**.md' + - '**.yaml' jobs: check-docs: diff --git a/.github/workflows/rolling-coverage-build.yml b/.github/workflows/rolling-coverage-build.yml index 8374afe8dc..4c61b47cbc 100644 --- a/.github/workflows/rolling-coverage-build.yml +++ b/.github/workflows/rolling-coverage-build.yml @@ -4,9 +4,27 @@ on: push: branches: - master + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/rolling-coverage-build.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control.rolling.repos' + - 'codecov.yml' pull_request: branches: - master + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/rolling-coverage-build.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control.rolling.repos' + - 'codecov.yml' jobs: coverage_rolling: @@ -14,4 +32,3 @@ jobs: secrets: inherit with: ros_distro: rolling - container: ubuntu:24.04 diff --git a/.github/workflows/rolling-debian-build.yml b/.github/workflows/rolling-debian-build.yml index e792963cc6..38ee0d213a 100644 --- a/.github/workflows/rolling-debian-build.yml +++ b/.github/workflows/rolling-debian-build.yml @@ -4,6 +4,14 @@ on: pull_request: branches: - master + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/rolling-debian-build.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control.rolling.repos' schedule: # Run every day to detect flakiness and broken dependencies - cron: '03 1 * * *' diff --git a/.github/workflows/rolling-pre-commit.yml b/.github/workflows/rolling-pre-commit.yml index 4d91d19100..7bc07ba802 100644 --- a/.github/workflows/rolling-pre-commit.yml +++ b/.github/workflows/rolling-pre-commit.yml @@ -11,4 +11,3 @@ jobs: uses: ros-controls/ros2_control_ci/.github/workflows/reusable-pre-commit.yml@master with: ros_distro: rolling - container: ubuntu:24.04 diff --git a/.github/workflows/rolling-rhel-binary-build.yml b/.github/workflows/rolling-rhel-binary-build.yml index 38f375d6b6..e7e0e93fd1 100644 --- a/.github/workflows/rolling-rhel-binary-build.yml +++ b/.github/workflows/rolling-rhel-binary-build.yml @@ -4,6 +4,14 @@ on: pull_request: branches: - master + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/rolling-rhel-binary-build.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control.jazzy.repos' schedule: # Run every day to detect flakiness and broken dependencies - cron: '03 1 * * *' diff --git a/.github/workflows/rolling-semi-binary-build.yml b/.github/workflows/rolling-semi-binary-build.yml index f5c7885139..07cbcfc2f0 100644 --- a/.github/workflows/rolling-semi-binary-build.yml +++ b/.github/workflows/rolling-semi-binary-build.yml @@ -7,9 +7,25 @@ on: pull_request: branches: - master + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/rolling-semi-binary-build.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control.rolling.repos' push: branches: - master + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/rolling-semi-binary-build.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control.rolling.repos' schedule: # Run every morning to detect flakiness and broken dependencies - cron: '03 1 * * *' diff --git a/.github/workflows/rolling-source-build.yml b/.github/workflows/rolling-source-build.yml index d9f1519ba3..ae6b40a4b4 100644 --- a/.github/workflows/rolling-source-build.yml +++ b/.github/workflows/rolling-source-build.yml @@ -4,6 +4,14 @@ on: push: branches: - master + paths: + - '**.hpp' + - '**.h' + - '**.cpp' + - '.github/workflows/rolling-source-build.yml' + - '**/package.xml' + - '**/CMakeLists.txt' + - 'ros2_control.rolling.repos' schedule: # Run every day to detect flakiness and broken dependencies - cron: '03 3 * * *' diff --git a/README.md b/README.md index e88ca5b7bd..40d2a3c189 100644 --- a/README.md +++ b/README.md @@ -12,6 +12,7 @@ For more, please check the [documentation](https://control.ros.org/). ROS2 Distro | Branch | Build status | Documentation | Released packages :---------: | :----: | :----------: | :-----------: | :---------------: **Rolling** | [`master`](https://github.com/ros-controls/ros2_control/tree/master) | [![Rolling Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-binary-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-binary-build.yml?branch=master)
[![Rolling Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-semi-binary-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-semi-binary-build.yml?branch=master) | [Documentation](https://control.ros.org/master/index.html)
[API Reference](https://control.ros.org/master/doc/api/index.html) | [ros2_control](https://index.ros.org/p/ros2_control/#rolling) +**Jazzy** | [`master`](https://github.com/ros-controls/ros2_control/tree/master) | [![Rolling Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/jazzy-binary-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/jazzy-binary-build.yml?branch=master)
[![Rolling Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/jazzy-semi-binary-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/jazzy-semi-binary-build.yml?branch=master) | [Documentation](https://control.ros.org/jazzy/index.html)
[API Reference](https://control.ros.org/jazzy/doc/api/index.html) | [ros2_control](https://index.ros.org/p/ros2_control/#jazzy) **Iron** | [`iron`](https://github.com/ros-controls/ros2_control/tree/iron) | [![Iron Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/iron-binary-build.yml/badge.svg?branch=iron)](https://github.com/ros-controls/ros2_control/actions/workflows/iron-binary-build.yml?branch=iron)
[![Iron Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/iron-semi-binary-build.yml/badge.svg?branch=iron)](https://github.com/ros-controls/ros2_control/actions/workflows/iron-semi-binary-build.yml?branch=iron) | [Documentation](https://control.ros.org/iron/index.html)
[API Reference](https://control.ros.org/iron/doc/api/index.html) | [ros2_control](https://index.ros.org/p/ros2_control/#iron) **Humble** | [`humble`](https://github.com/ros-controls/ros2_control/tree/humble) | [![Humble Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/humble-binary-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/humble-binary-build.yml?branch=master)
[![Humble Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/humble-semi-binary-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/humble-semi-binary-build.yml?branch=master) | [Documentation](https://control.ros.org/humble/index.html)
[API Reference](https://control.ros.org/humble/doc/api/index.html) | [ros2_control](https://index.ros.org/p/ros2_control/#humble) diff --git a/ros2_control-not-released.jazzy.repos b/ros2_control-not-released.jazzy.repos new file mode 100644 index 0000000000..56f46b6f79 --- /dev/null +++ b/ros2_control-not-released.jazzy.repos @@ -0,0 +1 @@ +repositories: diff --git a/ros2_control.jazzy.repos b/ros2_control.jazzy.repos new file mode 100644 index 0000000000..c93d8f4ef6 --- /dev/null +++ b/ros2_control.jazzy.repos @@ -0,0 +1,9 @@ +repositories: + ros-controls/realtime_tools: + type: git + url: https://github.com/ros-controls/realtime_tools.git + version: master + ros-controls/control_msgs: + type: git + url: https://github.com/ros-controls/control_msgs.git + version: master From edfb971c55f54f26272fbe38ee134859d7938d41 Mon Sep 17 00:00:00 2001 From: adriaroig <45817677+adriaroig@users.noreply.github.com> Date: Thu, 9 May 2024 13:23:46 +0200 Subject: [PATCH 06/11] Parse URDF soft_limits into the HardwareInfo structure (#1488) --- doc/release_notes/Jazzy.rst | 24 ++++++ .../hardware_interface/hardware_info.hpp | 7 ++ hardware_interface/src/component_parser.cpp | 10 +++ .../test/test_component_parser.cpp | 82 +++++++++++++++++++ .../ros2_control_test_assets/descriptions.hpp | 1 + 5 files changed, 124 insertions(+) diff --git a/doc/release_notes/Jazzy.rst b/doc/release_notes/Jazzy.rst index 52fc54a071..4074cbca63 100644 --- a/doc/release_notes/Jazzy.rst +++ b/doc/release_notes/Jazzy.rst @@ -70,6 +70,30 @@ hardware_interface ****************** * A portable version for string-to-double conversion was added: ``hardware_interface::stod`` (`#1257 `_) * ``test_components`` was moved to its own package (`#1325 `_) +* The ``ros2_control`` tag now supports parsing of the limits from the URDF into the ``HardwareInfo`` structure. More conservative limits can be defined using the ``min`` and ``max`` attributes per interface (`#1472 `_) + + .. code:: xml + + + + ros2_control_demo_hardware/RRBotSystemPositionOnlyHardware + 2.0 + 3.0 + 2.0 + + + + -1 + 1 + + + + + + + + +* Soft limits are also parsed from the URDF into the ``HardwareInfo`` structure for the defined joints (`#1488 `_) joint_limits ************ diff --git a/hardware_interface/include/hardware_interface/hardware_info.hpp b/hardware_interface/include/hardware_interface/hardware_info.hpp index cb548b9bf4..d94573bf5e 100644 --- a/hardware_interface/include/hardware_interface/hardware_info.hpp +++ b/hardware_interface/include/hardware_interface/hardware_info.hpp @@ -171,6 +171,13 @@ struct HardwareInfo * The URDF parsed limits of the hardware components joint command interfaces */ std::unordered_map limits; + + /** + * Map of software joint limits used for clamping the command where the key is the joint name. + * Optional If not specified or less restrictive than the JointLimits uses the previous + * JointLimits. + */ + std::unordered_map soft_limits; }; } // namespace hardware_interface diff --git a/hardware_interface/src/component_parser.cpp b/hardware_interface/src/component_parser.cpp index aad1d827ec..14e016df21 100644 --- a/hardware_interface/src/component_parser.cpp +++ b/hardware_interface/src/component_parser.cpp @@ -927,6 +927,16 @@ std::vector parse_control_resources_from_urdf(const std::string & // Take the most restricted one. Also valid for continuous-joint type only detail::update_interface_limits(joint.command_interfaces, limits); hw_info.limits[joint.name] = limits; + joint_limits::SoftJointLimits soft_limits; + if (getSoftJointLimits(urdf_joint, soft_limits)) + { + if (limits.has_position_limits) + { + soft_limits.min_position = std::max(soft_limits.min_position, limits.min_position); + soft_limits.max_position = std::min(soft_limits.max_position, limits.max_position); + } + hw_info.soft_limits[joint.name] = soft_limits; + } } } diff --git a/hardware_interface/test/test_component_parser.cpp b/hardware_interface/test/test_component_parser.cpp index 946fda7c15..6a0c11cf72 100644 --- a/hardware_interface/test/test_component_parser.cpp +++ b/hardware_interface/test/test_component_parser.cpp @@ -141,6 +141,8 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_system_one_interface) // Verify limits parsed from the URDF ASSERT_THAT(hardware_info.limits, SizeIs(2)); + ASSERT_THAT(hardware_info.soft_limits, SizeIs(1)); + char joint2_name[] = "joint2"; for (const auto & joint : {"joint1", "joint2"}) { EXPECT_TRUE(hardware_info.limits.at(joint).has_position_limits); @@ -152,6 +154,13 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_system_one_interface) EXPECT_TRUE(hardware_info.limits.at(joint).has_effort_limits); EXPECT_THAT(hardware_info.limits.at(joint).max_velocity, DoubleNear(0.2, 1e-5)); EXPECT_THAT(hardware_info.limits.at(joint).max_effort, DoubleNear(0.1, 1e-5)); + if (strcmp(joint, joint2_name) == 0) + { + EXPECT_THAT(hardware_info.soft_limits.at(joint).max_position, DoubleNear(0.5, 1e-5)); + EXPECT_THAT(hardware_info.soft_limits.at(joint).min_position, DoubleNear(-1.0, 1e-5)); + EXPECT_THAT(hardware_info.soft_limits.at(joint).k_position, DoubleNear(10.0, 1e-5)); + EXPECT_THAT(hardware_info.soft_limits.at(joint).k_velocity, DoubleNear(20.0, 1e-5)); + } } } @@ -193,6 +202,8 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_system_multi_interface // Verify limits parsed from the URDF ASSERT_THAT(hardware_info.limits, SizeIs(2)); + ASSERT_THAT(hardware_info.soft_limits, SizeIs(1)); + char joint2_name[] = "joint2"; for (const auto & joint : {"joint1", "joint2"}) { EXPECT_TRUE(hardware_info.limits.at(joint).has_position_limits); @@ -205,6 +216,13 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_system_multi_interface // effort and velocity limits won't change as they are above the main URDF hard limits EXPECT_THAT(hardware_info.limits.at(joint).max_velocity, DoubleNear(0.2, 1e-5)); EXPECT_THAT(hardware_info.limits.at(joint).max_effort, DoubleNear(0.1, 1e-5)); + if (strcmp(joint, joint2_name) == 0) + { + EXPECT_THAT(hardware_info.soft_limits.at(joint).max_position, DoubleNear(0.5, 1e-5)); + EXPECT_THAT(hardware_info.soft_limits.at(joint).min_position, DoubleNear(-1.0, 1e-5)); + EXPECT_THAT(hardware_info.soft_limits.at(joint).k_position, DoubleNear(10.0, 1e-5)); + EXPECT_THAT(hardware_info.soft_limits.at(joint).k_velocity, DoubleNear(20.0, 1e-5)); + } } } @@ -253,6 +271,8 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_system_robot_with_sens // Verify limits parsed from the URDF ASSERT_THAT(hardware_info.limits, SizeIs(2)); + ASSERT_THAT(hardware_info.soft_limits, SizeIs(1)); + char joint2_name[] = "joint2"; for (const auto & joint : {"joint1", "joint2"}) { EXPECT_TRUE(hardware_info.limits.at(joint).has_position_limits); @@ -264,6 +284,13 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_system_robot_with_sens EXPECT_TRUE(hardware_info.limits.at(joint).has_effort_limits); EXPECT_THAT(hardware_info.limits.at(joint).max_velocity, DoubleNear(0.2, 1e-5)); EXPECT_THAT(hardware_info.limits.at(joint).max_effort, DoubleNear(0.1, 1e-5)); + if (strcmp(joint, joint2_name) == 0) + { + EXPECT_THAT(hardware_info.soft_limits.at(joint).max_position, DoubleNear(0.5, 1e-5)); + EXPECT_THAT(hardware_info.soft_limits.at(joint).min_position, DoubleNear(-1.0, 1e-5)); + EXPECT_THAT(hardware_info.soft_limits.at(joint).k_position, DoubleNear(10.0, 1e-5)); + EXPECT_THAT(hardware_info.soft_limits.at(joint).k_velocity, DoubleNear(20.0, 1e-5)); + } } } @@ -297,6 +324,8 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_system_robot_with_exte // Verify limits parsed from the URDF ASSERT_THAT(hardware_info.limits, SizeIs(2)); + ASSERT_THAT(hardware_info.soft_limits, SizeIs(1)); + char joint2_name[] = "joint2"; for (const auto & joint : {"joint1", "joint2"}) { EXPECT_TRUE(hardware_info.limits.at(joint).has_position_limits); @@ -308,6 +337,13 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_system_robot_with_exte EXPECT_TRUE(hardware_info.limits.at(joint).has_effort_limits); EXPECT_THAT(hardware_info.limits.at(joint).max_velocity, DoubleNear(0.2, 1e-5)); EXPECT_THAT(hardware_info.limits.at(joint).max_effort, DoubleNear(0.1, 1e-5)); + if (strcmp(joint, joint2_name) == 0) + { + EXPECT_THAT(hardware_info.soft_limits.at(joint).max_position, DoubleNear(0.5, 1e-5)); + EXPECT_THAT(hardware_info.soft_limits.at(joint).min_position, DoubleNear(-1.0, 1e-5)); + EXPECT_THAT(hardware_info.soft_limits.at(joint).k_position, DoubleNear(10.0, 1e-5)); + EXPECT_THAT(hardware_info.soft_limits.at(joint).k_velocity, DoubleNear(20.0, 1e-5)); + } } hardware_info = control_hardware.at(1); @@ -322,6 +358,7 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_system_robot_with_exte EXPECT_EQ(hardware_info.sensors[0].type, "sensor"); EXPECT_EQ(hardware_info.sensors[0].parameters.at("frame_id"), "kuka_tcp"); ASSERT_THAT(hardware_info.limits, SizeIs(0)); + ASSERT_THAT(hardware_info.soft_limits, SizeIs(0)); } TEST_F(TestComponentParser, successfully_parse_valid_urdf_actuator_modular_robot) @@ -346,6 +383,7 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_actuator_modular_robot EXPECT_EQ(hardware_info.joints[0].type, "joint"); // Verify limits parsed from the URDF ASSERT_THAT(hardware_info.limits, SizeIs(1)); + ASSERT_THAT(hardware_info.soft_limits, SizeIs(0)); for (const auto & joint : {"joint1"}) { EXPECT_TRUE(hardware_info.limits.at(joint).has_position_limits); @@ -373,6 +411,8 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_actuator_modular_robot EXPECT_EQ(hardware_info.joints[0].type, "joint"); // Verify limits parsed from the URDF ASSERT_THAT(hardware_info.limits, SizeIs(1)); + ASSERT_THAT(hardware_info.soft_limits, SizeIs(1)); + char joint2_name[] = "joint2"; for (const auto & joint : {"joint2"}) { EXPECT_TRUE(hardware_info.limits.at(joint).has_position_limits); @@ -384,6 +424,13 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_actuator_modular_robot EXPECT_TRUE(hardware_info.limits.at(joint).has_effort_limits); EXPECT_THAT(hardware_info.limits.at(joint).max_velocity, DoubleNear(0.2, 1e-5)); EXPECT_THAT(hardware_info.limits.at(joint).max_effort, DoubleNear(0.1, 1e-5)); + if (strcmp(joint, joint2_name) == 0) + { + EXPECT_THAT(hardware_info.soft_limits.at(joint).max_position, DoubleNear(0.5, 1e-5)); + EXPECT_THAT(hardware_info.soft_limits.at(joint).min_position, DoubleNear(-1.0, 1e-5)); + EXPECT_THAT(hardware_info.soft_limits.at(joint).k_position, DoubleNear(10.0, 1e-5)); + EXPECT_THAT(hardware_info.soft_limits.at(joint).k_velocity, DoubleNear(20.0, 1e-5)); + } } } @@ -421,6 +468,7 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_actuator_modular_robot EXPECT_THAT(hardware_info.transmissions[0].actuators[0].name, "actuator1"); // Verify limits parsed from the URDF ASSERT_THAT(hardware_info.limits, SizeIs(1)); + ASSERT_THAT(hardware_info.soft_limits, SizeIs(0)); for (const auto & joint : {"joint1"}) { EXPECT_TRUE(hardware_info.limits.at(joint).has_position_limits); @@ -451,6 +499,8 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_actuator_modular_robot EXPECT_EQ(hardware_info.joints[0].command_interfaces[0].max, "1"); // Verify limits parsed from the URDF ASSERT_THAT(hardware_info.limits, SizeIs(1)); + ASSERT_THAT(hardware_info.soft_limits, SizeIs(1)); + char joint2_name[] = "joint2"; for (const auto & joint : {"joint2"}) { EXPECT_TRUE(hardware_info.limits.at(joint).has_position_limits); @@ -461,6 +511,13 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_actuator_modular_robot // effort and velocity limits won't change as they are above the main URDF hard limits EXPECT_THAT(hardware_info.limits.at(joint).max_velocity, DoubleNear(0.2, 1e-5)); EXPECT_THAT(hardware_info.limits.at(joint).max_effort, DoubleNear(0.1, 1e-5)); + if (strcmp(joint, joint2_name) == 0) + { + EXPECT_THAT(hardware_info.soft_limits.at(joint).max_position, DoubleNear(0.5, 1e-5)); + EXPECT_THAT(hardware_info.soft_limits.at(joint).min_position, DoubleNear(-1.5, 1e-5)); + EXPECT_THAT(hardware_info.soft_limits.at(joint).k_position, DoubleNear(10.0, 1e-5)); + EXPECT_THAT(hardware_info.soft_limits.at(joint).k_velocity, DoubleNear(20.0, 1e-5)); + } } hardware_info = control_hardware.at(2); @@ -481,6 +538,7 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_actuator_modular_robot EXPECT_EQ(hardware_info.joints[0].state_interfaces[0].name, HW_IF_POSITION); // Verify limits parsed from the URDF ASSERT_THAT(hardware_info.limits, SizeIs(1)); + ASSERT_THAT(hardware_info.soft_limits, SizeIs(0)); for (const auto & joint : {"joint1"}) { EXPECT_TRUE(hardware_info.limits.at(joint).has_position_limits); @@ -511,6 +569,7 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_actuator_modular_robot EXPECT_EQ(hardware_info.joints[0].state_interfaces[0].name, HW_IF_POSITION); // Verify limits parsed from the URDF ASSERT_THAT(hardware_info.limits, SizeIs(1)); + ASSERT_THAT(hardware_info.soft_limits, SizeIs(1)); for (const auto & joint : {"joint2"}) { EXPECT_TRUE(hardware_info.limits.at(joint).has_position_limits); @@ -521,6 +580,13 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_actuator_modular_robot // effort and velocity limits won't change as they are above the main URDF hard limits EXPECT_THAT(hardware_info.limits.at(joint).max_velocity, DoubleNear(0.2, 1e-5)); EXPECT_THAT(hardware_info.limits.at(joint).max_effort, DoubleNear(0.1, 1e-5)); + if (strcmp(joint, joint2_name) == 0) + { + EXPECT_THAT(hardware_info.soft_limits.at(joint).max_position, DoubleNear(0.5, 1e-5)); + EXPECT_THAT(hardware_info.soft_limits.at(joint).min_position, DoubleNear(-1.5, 1e-5)); + EXPECT_THAT(hardware_info.soft_limits.at(joint).k_position, DoubleNear(10.0, 1e-5)); + EXPECT_THAT(hardware_info.soft_limits.at(joint).k_velocity, DoubleNear(20.0, 1e-5)); + } } } @@ -596,6 +662,7 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_sensor_only) EXPECT_EQ(hardware_info.sensors[1].state_interfaces[0].name, "image"); // There will be no limits as the ros2_control tag has only sensor info ASSERT_THAT(hardware_info.limits, SizeIs(0)); + ASSERT_THAT(hardware_info.soft_limits, SizeIs(0)); } TEST_F(TestComponentParser, successfully_parse_valid_urdf_actuator_only) @@ -656,6 +723,7 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_actuator_only) // effort and velocity limits won't change as they are above the main URDF hard limits EXPECT_THAT(hardware_info.limits.at("joint1").max_velocity, DoubleNear(0.2, 1e-5)); EXPECT_THAT(hardware_info.limits.at("joint1").max_effort, DoubleNear(0.1, 1e-5)); + ASSERT_THAT(hardware_info.soft_limits, SizeIs(0)); } TEST_F(TestComponentParser, successfully_parse_locale_independent_double) @@ -727,6 +795,8 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_system_robot_with_gpio // Verify limits parsed from the URDF ASSERT_THAT(hardware_info.limits, SizeIs(2)); + ASSERT_THAT(hardware_info.soft_limits, SizeIs(1)); + char joint2_name[] = "joint2"; for (const auto & joint : {"joint1", "joint2"}) { // Position limits are limited in the ros2_control tag @@ -737,6 +807,13 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_system_robot_with_gpio EXPECT_TRUE(hardware_info.limits.at(joint).has_effort_limits); EXPECT_THAT(hardware_info.limits.at(joint).max_velocity, DoubleNear(0.2, 1e-5)); EXPECT_THAT(hardware_info.limits.at(joint).max_effort, DoubleNear(0.1, 1e-5)); + if (strcmp(joint, joint2_name) == 0) + { + EXPECT_THAT(hardware_info.soft_limits.at(joint).max_position, DoubleNear(0.5, 1e-5)); + EXPECT_THAT(hardware_info.soft_limits.at(joint).min_position, DoubleNear(-1.0, 1e-5)); + EXPECT_THAT(hardware_info.soft_limits.at(joint).k_position, DoubleNear(10.0, 1e-5)); + EXPECT_THAT(hardware_info.soft_limits.at(joint).k_velocity, DoubleNear(20.0, 1e-5)); + } } } @@ -905,6 +982,10 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_system_and_disabled_in EXPECT_FALSE(hardware_info.limits.at("joint2").has_jerk_limits); EXPECT_THAT(hardware_info.limits.at("joint2").max_velocity, DoubleNear(0.2, 1e-5)); EXPECT_THAT(hardware_info.limits.at("joint2").max_effort, DoubleNear(0.1, 1e-5)); + EXPECT_THAT(hardware_info.soft_limits.at("joint2").max_position, DoubleNear(0.5, 1e-5)); + EXPECT_THAT(hardware_info.soft_limits.at("joint2").min_position, DoubleNear(-1.5, 1e-5)); + EXPECT_THAT(hardware_info.soft_limits.at("joint2").k_position, DoubleNear(10.0, 1e-5)); + EXPECT_THAT(hardware_info.soft_limits.at("joint2").k_velocity, DoubleNear(20.0, 1e-5)); EXPECT_TRUE(hardware_info.limits.at("joint3").has_position_limits); EXPECT_THAT(hardware_info.limits.at("joint3").min_position, DoubleNear(-M_PI, 1e-5)); @@ -1169,6 +1250,7 @@ TEST_F(TestComponentParser, successfully_parse_parameter_empty) // Verify limits parsed from the URDF ASSERT_THAT(hardware_info.limits, SizeIs(1)); + ASSERT_THAT(hardware_info.soft_limits, SizeIs(0)); for (const auto & joint : {"joint1"}) { EXPECT_TRUE(hardware_info.limits.at(joint).has_position_limits); diff --git a/ros2_control_test_assets/include/ros2_control_test_assets/descriptions.hpp b/ros2_control_test_assets/include/ros2_control_test_assets/descriptions.hpp index f5f668fd12..31e630059b 100644 --- a/ros2_control_test_assets/include/ros2_control_test_assets/descriptions.hpp +++ b/ros2_control_test_assets/include/ros2_control_test_assets/descriptions.hpp @@ -86,6 +86,7 @@ const auto urdf_head = + From ac5dfb4ba407f2eb77683b0a240ef2eb053d7684 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Sat, 11 May 2024 19:46:46 +0200 Subject: [PATCH 07/11] Add find_package for ament_cmake_gen_version_h (#1534) --- controller_interface/CMakeLists.txt | 1 + controller_manager/CMakeLists.txt | 1 + hardware_interface/CMakeLists.txt | 1 + joint_limits/CMakeLists.txt | 4 +++- joint_limits/package.xml | 3 ++- transmission_interface/CMakeLists.txt | 1 + 6 files changed, 9 insertions(+), 2 deletions(-) diff --git a/controller_interface/CMakeLists.txt b/controller_interface/CMakeLists.txt index 2b7ccb9203..3dc3bc4d0a 100644 --- a/controller_interface/CMakeLists.txt +++ b/controller_interface/CMakeLists.txt @@ -12,6 +12,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS ) find_package(ament_cmake REQUIRED) +find_package(ament_cmake_gen_version_h REQUIRED) foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS}) find_package(${Dependency} REQUIRED) endforeach() diff --git a/controller_manager/CMakeLists.txt b/controller_manager/CMakeLists.txt index d99a7f7330..c3c0de7739 100644 --- a/controller_manager/CMakeLists.txt +++ b/controller_manager/CMakeLists.txt @@ -21,6 +21,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS find_package(ament_cmake REQUIRED) find_package(ament_cmake_python REQUIRED) find_package(ament_cmake_core REQUIRED) +find_package(ament_cmake_gen_version_h REQUIRED) find_package(backward_ros REQUIRED) foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS}) find_package(${Dependency} REQUIRED) diff --git a/hardware_interface/CMakeLists.txt b/hardware_interface/CMakeLists.txt index a5debef3b7..c557a4970f 100644 --- a/hardware_interface/CMakeLists.txt +++ b/hardware_interface/CMakeLists.txt @@ -20,6 +20,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS ) find_package(ament_cmake REQUIRED) +find_package(ament_cmake_gen_version_h REQUIRED) foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS}) find_package(${Dependency} REQUIRED) endforeach() diff --git a/joint_limits/CMakeLists.txt b/joint_limits/CMakeLists.txt index 1139a5248e..316a1ec7a2 100644 --- a/joint_limits/CMakeLists.txt +++ b/joint_limits/CMakeLists.txt @@ -13,6 +13,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS ) find_package(ament_cmake REQUIRED) +find_package(ament_cmake_gen_version_h REQUIRED) foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS}) find_package(${Dependency} REQUIRED) endforeach() @@ -61,4 +62,5 @@ install(TARGETS joint_limits ament_export_targets(export_joint_limits HAS_LIBRARY_TARGET) ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS}) ament_package() -ament_generate_version_header(${PROJECT_NAME}) +# TODO(anyone) uncomment if https://github.com/ament/ament_cmake/pull/526 is merged +# ament_generate_version_header(${PROJECT_NAME}) diff --git a/joint_limits/package.xml b/joint_limits/package.xml index d99ad61016..eba131c851 100644 --- a/joint_limits/package.xml +++ b/joint_limits/package.xml @@ -13,7 +13,8 @@ https://github.com/ros-controls/ros2_control ament_cmake - ament_cmake_gen_version_h + + rclcpp rclcpp_lifecycle diff --git a/transmission_interface/CMakeLists.txt b/transmission_interface/CMakeLists.txt index 98dcdcd192..185fb32d3a 100644 --- a/transmission_interface/CMakeLists.txt +++ b/transmission_interface/CMakeLists.txt @@ -13,6 +13,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS ) find_package(ament_cmake REQUIRED) +find_package(ament_cmake_gen_version_h REQUIRED) foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS}) find_package(${Dependency} REQUIRED) endforeach() From e2600490481092ba2709c5ac9cb1b36b1032a4bc Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Sat, 11 May 2024 19:48:19 +0200 Subject: [PATCH 08/11] Fix dependencies for source build (#1533) * Don't use std::system call inside test * Give launch_ros as explicit dependency * Test the source build on this branch * Revert "Test the source build on this branch" This reverts commit 9884b112257fc2626d1d03ba523d02247c6f258e. --- controller_interface/test/test_controller_interface.cpp | 3 ++- joint_limits/package.xml | 1 + 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/controller_interface/test/test_controller_interface.cpp b/controller_interface/test/test_controller_interface.cpp index 3976b2a81e..03838b1a2e 100644 --- a/controller_interface/test/test_controller_interface.cpp +++ b/controller_interface/test/test_controller_interface.cpp @@ -88,7 +88,8 @@ TEST(TestableControllerInterface, setting_update_rate_in_configure) ASSERT_EQ(controller.get_update_rate(), 2812u); // Test updating of update_rate parameter - EXPECT_EQ(std::system("ros2 param set /testable_controller_interface update_rate 623"), 0); + auto res = controller.get_node()->set_parameter(rclcpp::Parameter("update_rate", 623)); + EXPECT_EQ(res.successful, true); // Keep the same update rate until transition from 'UNCONFIGURED' TO 'INACTIVE' does not happen controller.configure(); // No transition so the update rate should stay intact ASSERT_NE(controller.get_update_rate(), 623u); diff --git a/joint_limits/package.xml b/joint_limits/package.xml index eba131c851..1aa1ac5705 100644 --- a/joint_limits/package.xml +++ b/joint_limits/package.xml @@ -20,6 +20,7 @@ rclcpp_lifecycle urdf + launch_ros launch_testing_ament_cmake ament_cmake_gtest From d07d18f4be619a5d120bfd5fd02ef14e8c90d73a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Tue, 14 May 2024 07:48:11 +0200 Subject: [PATCH 09/11] [CI] Update branch of reusable workflow (#1537) * Update branch of reusable workflow * Include workflow file to paths filter --- .github/workflows/rolling-check-docs.yml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/.github/workflows/rolling-check-docs.yml b/.github/workflows/rolling-check-docs.yml index 80e8287abd..bd83c0caca 100644 --- a/.github/workflows/rolling-check-docs.yml +++ b/.github/workflows/rolling-check-docs.yml @@ -9,10 +9,11 @@ on: - '**.rst' - '**.md' - '**.yaml' + - '.github/workflows/rolling-check-docs.yml' jobs: check-docs: name: Check Docs - uses: ros-controls/control.ros.org/.github/workflows/reusable-sphinx-check-single-version.yml@master + uses: ros-controls/control.ros.org/.github/workflows/reusable-sphinx-check-single-version.yml@rolling with: ROS2_CONTROL_PR: ${{ github.ref }} From d8e276f731dadc1b5c00a97f829526f4012779b7 Mon Sep 17 00:00:00 2001 From: Bence Magyar Date: Tue, 14 May 2024 06:49:02 +0100 Subject: [PATCH 10/11] Update changelogs --- controller_interface/CHANGELOG.rst | 6 ++++++ controller_manager/CHANGELOG.rst | 5 +++++ controller_manager_msgs/CHANGELOG.rst | 3 +++ hardware_interface/CHANGELOG.rst | 6 ++++++ hardware_interface_testing/CHANGELOG.rst | 3 +++ joint_limits/CHANGELOG.rst | 6 ++++++ ros2_control/CHANGELOG.rst | 3 +++ ros2_control_test_assets/CHANGELOG.rst | 5 +++++ ros2controlcli/CHANGELOG.rst | 3 +++ rqt_controller_manager/CHANGELOG.rst | 3 +++ transmission_interface/CHANGELOG.rst | 5 +++++ 11 files changed, 48 insertions(+) diff --git a/controller_interface/CHANGELOG.rst b/controller_interface/CHANGELOG.rst index b8301e0cba..c9e8da8d60 100644 --- a/controller_interface/CHANGELOG.rst +++ b/controller_interface/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package controller_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Fix dependencies for source build (`#1533 `_) +* Add find_package for ament_cmake_gen_version_h (`#1534 `_) +* Contributors: Christoph Fröhlich + 4.10.0 (2024-05-08) ------------------- * Working async controllers and components [not synchronized] (`#1041 `_) diff --git a/controller_manager/CHANGELOG.rst b/controller_manager/CHANGELOG.rst index 4c5e9579ef..d7a2b0a589 100644 --- a/controller_manager/CHANGELOG.rst +++ b/controller_manager/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package controller_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Add find_package for ament_cmake_gen_version_h (`#1534 `_) +* Contributors: Christoph Fröhlich + 4.10.0 (2024-05-08) ------------------- * allow extra spawner arguments to not declare every argument in launch utils (`#1505 `_) diff --git a/controller_manager_msgs/CHANGELOG.rst b/controller_manager_msgs/CHANGELOG.rst index cf752dde2a..df41e0d67e 100644 --- a/controller_manager_msgs/CHANGELOG.rst +++ b/controller_manager_msgs/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package controller_manager_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.10.0 (2024-05-08) ------------------- diff --git a/hardware_interface/CHANGELOG.rst b/hardware_interface/CHANGELOG.rst index a27d097d6e..597a9713bb 100644 --- a/hardware_interface/CHANGELOG.rst +++ b/hardware_interface/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package hardware_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Add find_package for ament_cmake_gen_version_h (`#1534 `_) +* Parse URDF soft_limits into the HardwareInfo structure (`#1488 `_) +* Contributors: Christoph Fröhlich, adriaroig + 4.10.0 (2024-05-08) ------------------- * Add hardware components exception handling in resource manager (`#1508 `_) diff --git a/hardware_interface_testing/CHANGELOG.rst b/hardware_interface_testing/CHANGELOG.rst index cecc4e220c..1aa2f19b81 100644 --- a/hardware_interface_testing/CHANGELOG.rst +++ b/hardware_interface_testing/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package hardware_interface_testing ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.10.0 (2024-05-08) ------------------- diff --git a/joint_limits/CHANGELOG.rst b/joint_limits/CHANGELOG.rst index dba0758112..e74d66ea22 100644 --- a/joint_limits/CHANGELOG.rst +++ b/joint_limits/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package joint_limits ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Fix dependencies for source build (`#1533 `_) +* Add find_package for ament_cmake_gen_version_h (`#1534 `_) +* Contributors: Christoph Fröhlich + 4.10.0 (2024-05-08) ------------------- diff --git a/ros2_control/CHANGELOG.rst b/ros2_control/CHANGELOG.rst index a6df0c09e3..2f80568e7a 100644 --- a/ros2_control/CHANGELOG.rst +++ b/ros2_control/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package ros2_control ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.10.0 (2024-05-08) ------------------- diff --git a/ros2_control_test_assets/CHANGELOG.rst b/ros2_control_test_assets/CHANGELOG.rst index 4057ceaa9e..fccd0d84e0 100644 --- a/ros2_control_test_assets/CHANGELOG.rst +++ b/ros2_control_test_assets/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package ros2_control_test_assets ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Parse URDF soft_limits into the HardwareInfo structure (`#1488 `_) +* Contributors: adriaroig + 4.10.0 (2024-05-08) ------------------- * Parse URDF joint hard limits into the HardwareInfo structure (`#1472 `_) diff --git a/ros2controlcli/CHANGELOG.rst b/ros2controlcli/CHANGELOG.rst index 84a64c1fd8..3c567083ee 100644 --- a/ros2controlcli/CHANGELOG.rst +++ b/ros2controlcli/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package ros2controlcli ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.10.0 (2024-05-08) ------------------- diff --git a/rqt_controller_manager/CHANGELOG.rst b/rqt_controller_manager/CHANGELOG.rst index 33660cc16d..24a443b9cc 100644 --- a/rqt_controller_manager/CHANGELOG.rst +++ b/rqt_controller_manager/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package rqt_controller_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.10.0 (2024-05-08) ------------------- diff --git a/transmission_interface/CHANGELOG.rst b/transmission_interface/CHANGELOG.rst index 8ac4224337..e1808bd2b8 100644 --- a/transmission_interface/CHANGELOG.rst +++ b/transmission_interface/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package transmission_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Add find_package for ament_cmake_gen_version_h (`#1534 `_) +* Contributors: Christoph Fröhlich + 4.10.0 (2024-05-08) ------------------- From 62b32afef6df68f05430f0e89b385473114dd786 Mon Sep 17 00:00:00 2001 From: Bence Magyar Date: Tue, 14 May 2024 06:49:25 +0100 Subject: [PATCH 11/11] 4.11.0 --- controller_interface/CHANGELOG.rst | 4 ++-- controller_interface/package.xml | 2 +- controller_manager/CHANGELOG.rst | 4 ++-- controller_manager/package.xml | 2 +- controller_manager_msgs/CHANGELOG.rst | 4 ++-- controller_manager_msgs/package.xml | 2 +- hardware_interface/CHANGELOG.rst | 4 ++-- hardware_interface/package.xml | 2 +- hardware_interface_testing/CHANGELOG.rst | 4 ++-- hardware_interface_testing/package.xml | 2 +- joint_limits/CHANGELOG.rst | 4 ++-- joint_limits/package.xml | 2 +- ros2_control/CHANGELOG.rst | 4 ++-- ros2_control/package.xml | 2 +- ros2_control_test_assets/CHANGELOG.rst | 4 ++-- ros2_control_test_assets/package.xml | 2 +- ros2controlcli/CHANGELOG.rst | 4 ++-- ros2controlcli/package.xml | 2 +- ros2controlcli/setup.py | 2 +- rqt_controller_manager/CHANGELOG.rst | 4 ++-- rqt_controller_manager/package.xml | 2 +- rqt_controller_manager/setup.py | 2 +- transmission_interface/CHANGELOG.rst | 4 ++-- transmission_interface/package.xml | 2 +- 24 files changed, 35 insertions(+), 35 deletions(-) diff --git a/controller_interface/CHANGELOG.rst b/controller_interface/CHANGELOG.rst index c9e8da8d60..8d77f4203f 100644 --- a/controller_interface/CHANGELOG.rst +++ b/controller_interface/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package controller_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.11.0 (2024-05-14) +------------------- * Fix dependencies for source build (`#1533 `_) * Add find_package for ament_cmake_gen_version_h (`#1534 `_) * Contributors: Christoph Fröhlich diff --git a/controller_interface/package.xml b/controller_interface/package.xml index a4b89265e3..9a99449043 100644 --- a/controller_interface/package.xml +++ b/controller_interface/package.xml @@ -2,7 +2,7 @@ controller_interface - 4.10.0 + 4.11.0 Description of controller_interface Bence Magyar Denis Štogl diff --git a/controller_manager/CHANGELOG.rst b/controller_manager/CHANGELOG.rst index d7a2b0a589..2248f5f668 100644 --- a/controller_manager/CHANGELOG.rst +++ b/controller_manager/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package controller_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.11.0 (2024-05-14) +------------------- * Add find_package for ament_cmake_gen_version_h (`#1534 `_) * Contributors: Christoph Fröhlich diff --git a/controller_manager/package.xml b/controller_manager/package.xml index ec5b0e4f0e..e2aa998332 100644 --- a/controller_manager/package.xml +++ b/controller_manager/package.xml @@ -2,7 +2,7 @@ controller_manager - 4.10.0 + 4.11.0 Description of controller_manager Bence Magyar Denis Štogl diff --git a/controller_manager_msgs/CHANGELOG.rst b/controller_manager_msgs/CHANGELOG.rst index df41e0d67e..6cc2a09a43 100644 --- a/controller_manager_msgs/CHANGELOG.rst +++ b/controller_manager_msgs/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package controller_manager_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.11.0 (2024-05-14) +------------------- 4.10.0 (2024-05-08) ------------------- diff --git a/controller_manager_msgs/package.xml b/controller_manager_msgs/package.xml index 1f078be2cf..ddd840154e 100644 --- a/controller_manager_msgs/package.xml +++ b/controller_manager_msgs/package.xml @@ -2,7 +2,7 @@ controller_manager_msgs - 4.10.0 + 4.11.0 Messages and services for the controller manager. Bence Magyar Denis Štogl diff --git a/hardware_interface/CHANGELOG.rst b/hardware_interface/CHANGELOG.rst index 597a9713bb..77185ecf28 100644 --- a/hardware_interface/CHANGELOG.rst +++ b/hardware_interface/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package hardware_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.11.0 (2024-05-14) +------------------- * Add find_package for ament_cmake_gen_version_h (`#1534 `_) * Parse URDF soft_limits into the HardwareInfo structure (`#1488 `_) * Contributors: Christoph Fröhlich, adriaroig diff --git a/hardware_interface/package.xml b/hardware_interface/package.xml index 33dea58c73..f3aaad3306 100644 --- a/hardware_interface/package.xml +++ b/hardware_interface/package.xml @@ -1,7 +1,7 @@ hardware_interface - 4.10.0 + 4.11.0 ros2_control hardware interface Bence Magyar Denis Štogl diff --git a/hardware_interface_testing/CHANGELOG.rst b/hardware_interface_testing/CHANGELOG.rst index 1aa2f19b81..66d8794675 100644 --- a/hardware_interface_testing/CHANGELOG.rst +++ b/hardware_interface_testing/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package hardware_interface_testing ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.11.0 (2024-05-14) +------------------- 4.10.0 (2024-05-08) ------------------- diff --git a/hardware_interface_testing/package.xml b/hardware_interface_testing/package.xml index 737d228df3..b63e76ec6d 100644 --- a/hardware_interface_testing/package.xml +++ b/hardware_interface_testing/package.xml @@ -1,7 +1,7 @@ hardware_interface_testing - 4.10.0 + 4.11.0 ros2_control hardware interface testing Bence Magyar Denis Štogl diff --git a/joint_limits/CHANGELOG.rst b/joint_limits/CHANGELOG.rst index e74d66ea22..12cfce3bd6 100644 --- a/joint_limits/CHANGELOG.rst +++ b/joint_limits/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package joint_limits ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.11.0 (2024-05-14) +------------------- * Fix dependencies for source build (`#1533 `_) * Add find_package for ament_cmake_gen_version_h (`#1534 `_) * Contributors: Christoph Fröhlich diff --git a/joint_limits/package.xml b/joint_limits/package.xml index 1aa1ac5705..aec1c44b76 100644 --- a/joint_limits/package.xml +++ b/joint_limits/package.xml @@ -1,6 +1,6 @@ joint_limits - 4.10.0 + 4.11.0 Interfaces for handling of joint limits for controllers or hardware. Bence Magyar diff --git a/ros2_control/CHANGELOG.rst b/ros2_control/CHANGELOG.rst index 2f80568e7a..c036c1c914 100644 --- a/ros2_control/CHANGELOG.rst +++ b/ros2_control/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package ros2_control ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.11.0 (2024-05-14) +------------------- 4.10.0 (2024-05-08) ------------------- diff --git a/ros2_control/package.xml b/ros2_control/package.xml index 1fa309643f..3941d9a17e 100644 --- a/ros2_control/package.xml +++ b/ros2_control/package.xml @@ -1,7 +1,7 @@ ros2_control - 4.10.0 + 4.11.0 Metapackage for ROS2 control related packages Bence Magyar Denis Štogl diff --git a/ros2_control_test_assets/CHANGELOG.rst b/ros2_control_test_assets/CHANGELOG.rst index fccd0d84e0..1b475c5c40 100644 --- a/ros2_control_test_assets/CHANGELOG.rst +++ b/ros2_control_test_assets/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package ros2_control_test_assets ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.11.0 (2024-05-14) +------------------- * Parse URDF soft_limits into the HardwareInfo structure (`#1488 `_) * Contributors: adriaroig diff --git a/ros2_control_test_assets/package.xml b/ros2_control_test_assets/package.xml index a76e1109a8..4ed6912f83 100644 --- a/ros2_control_test_assets/package.xml +++ b/ros2_control_test_assets/package.xml @@ -2,7 +2,7 @@ ros2_control_test_assets - 4.10.0 + 4.11.0 The package provides shared test resources for ros2_control stack Bence Magyar diff --git a/ros2controlcli/CHANGELOG.rst b/ros2controlcli/CHANGELOG.rst index 3c567083ee..52ad767224 100644 --- a/ros2controlcli/CHANGELOG.rst +++ b/ros2controlcli/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package ros2controlcli ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.11.0 (2024-05-14) +------------------- 4.10.0 (2024-05-08) ------------------- diff --git a/ros2controlcli/package.xml b/ros2controlcli/package.xml index 8e2b02b266..d37c053413 100644 --- a/ros2controlcli/package.xml +++ b/ros2controlcli/package.xml @@ -2,7 +2,7 @@ ros2controlcli - 4.10.0 + 4.11.0 The ROS 2 command line tools for ROS2 Control. diff --git a/ros2controlcli/setup.py b/ros2controlcli/setup.py index d3ce54204e..a0ee818309 100644 --- a/ros2controlcli/setup.py +++ b/ros2controlcli/setup.py @@ -19,7 +19,7 @@ setup( name=package_name, - version="4.10.0", + version="4.11.0", packages=find_packages(exclude=["test"]), data_files=[ ("share/" + package_name, ["package.xml"]), diff --git a/rqt_controller_manager/CHANGELOG.rst b/rqt_controller_manager/CHANGELOG.rst index 24a443b9cc..a82b6e708f 100644 --- a/rqt_controller_manager/CHANGELOG.rst +++ b/rqt_controller_manager/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package rqt_controller_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.11.0 (2024-05-14) +------------------- 4.10.0 (2024-05-08) ------------------- diff --git a/rqt_controller_manager/package.xml b/rqt_controller_manager/package.xml index c722043890..e2866496ab 100644 --- a/rqt_controller_manager/package.xml +++ b/rqt_controller_manager/package.xml @@ -2,7 +2,7 @@ rqt_controller_manager - 4.10.0 + 4.11.0 Graphical frontend for interacting with the controller manager. Bence Magyar Denis Štogl diff --git a/rqt_controller_manager/setup.py b/rqt_controller_manager/setup.py index ae79268335..1f23378eba 100644 --- a/rqt_controller_manager/setup.py +++ b/rqt_controller_manager/setup.py @@ -20,7 +20,7 @@ setup( name=package_name, - version="4.10.0", + version="4.11.0", packages=[package_name], data_files=[ ("share/ament_index/resource_index/packages", ["resource/" + package_name]), diff --git a/transmission_interface/CHANGELOG.rst b/transmission_interface/CHANGELOG.rst index e1808bd2b8..44c85099dd 100644 --- a/transmission_interface/CHANGELOG.rst +++ b/transmission_interface/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package transmission_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.11.0 (2024-05-14) +------------------- * Add find_package for ament_cmake_gen_version_h (`#1534 `_) * Contributors: Christoph Fröhlich diff --git a/transmission_interface/package.xml b/transmission_interface/package.xml index 83da85a2ef..15c834b838 100644 --- a/transmission_interface/package.xml +++ b/transmission_interface/package.xml @@ -2,7 +2,7 @@ transmission_interface - 4.10.0 + 4.11.0 transmission_interface contains data structures for representing mechanical transmissions, methods for propagating values between actuator and joint spaces and tooling to support this. Bence Magyar Denis Štogl