Skip to content

Commit

Permalink
Merge branch 'master' into make/assign_and_release_interfaces/virtual
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor committed Sep 11, 2024
2 parents f38fbcb + 4472287 commit a288f57
Show file tree
Hide file tree
Showing 44 changed files with 354 additions and 191 deletions.
5 changes: 5 additions & 0 deletions controller_interface/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,11 @@
Changelog for package controller_interface
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

4.17.0 (2024-09-11)
-------------------
* Rename `get_state` and `set_state` Functions to `get/set_lifecylce_state` (variant support) (`#1683 <https://github.com/ros-controls/ros2_control/issues/1683>`_)
* Contributors: Manuel Muth

4.16.1 (2024-08-24)
-------------------

Expand Down
2 changes: 1 addition & 1 deletion controller_interface/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="2">
<name>controller_interface</name>
<version>4.16.1</version>
<version>4.17.0</version>
<description>Description of controller_interface</description>
<maintainer email="bence.magyar.robotics@gmail.com">Bence Magyar</maintainer>
<maintainer email="denis@stoglrobotics.de">Denis Štogl</maintainer>
Expand Down
9 changes: 9 additions & 0 deletions controller_manager/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,15 @@
Changelog for package controller_manager
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

4.17.0 (2024-09-11)
-------------------
* Log exception type when catching the exception (`#1749 <https://github.com/ros-controls/ros2_control/issues/1749>`_)
* [CM] Handle other exceptions while loading the controller plugin (`#1731 <https://github.com/ros-controls/ros2_control/issues/1731>`_)
* remove unnecessary log of the CM args (`#1720 <https://github.com/ros-controls/ros2_control/issues/1720>`_)
* Fix unload of controllers when spawned with `--unload-on-kill` (`#1717 <https://github.com/ros-controls/ros2_control/issues/1717>`_)
* Rename `get_state` and `set_state` Functions to `get/set_lifecylce_state` (variant support) (`#1683 <https://github.com/ros-controls/ros2_control/issues/1683>`_)
* Contributors: Manuel Muth, Sai Kishor Kothakota

4.16.1 (2024-08-24)
-------------------
* propage a portion of global args to the controller nodes (`#1712 <https://github.com/ros-controls/ros2_control/issues/1712>`_)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -88,15 +88,23 @@ def service_caller(
@return The service response
"""
cli = node.create_client(service_type, service_name)
namespace = "" if node.get_namespace() == "/" else node.get_namespace()
fully_qualified_service_name = (
f"{namespace}/{service_name}" if not service_name.startswith("/") else service_name
)
cli = node.create_client(service_type, fully_qualified_service_name)

while not cli.service_is_ready():
node.get_logger().info(f"waiting for service {service_name} to become available...")
node.get_logger().info(
f"waiting for service {fully_qualified_service_name} to become available..."
)
if service_timeout:
if not cli.wait_for_service(service_timeout):
raise ServiceNotFoundError(f"Could not contact service {service_name}")
raise ServiceNotFoundError(
f"Could not contact service {fully_qualified_service_name}"
)
elif not cli.wait_for_service(10.0):
node.get_logger().warn(f"Could not contact service {service_name}")
node.get_logger().warn(f"Could not contact service {fully_qualified_service_name}")

node.get_logger().debug(f"requester: making request: {request}\n")
future = None
Expand All @@ -105,13 +113,13 @@ def service_caller(
rclpy.spin_until_future_complete(node, future, timeout_sec=call_timeout)
if future.result() is None:
node.get_logger().warning(
f"Failed getting a result from calling {service_name} in "
f"Failed getting a result from calling {fully_qualified_service_name} in "
f"{service_timeout}. (Attempt {attempt+1} of {max_attempts}.)"
)
else:
return future.result()
raise RuntimeError(
f"Could not successfully call service {service_name} after {max_attempts} attempts."
f"Could not successfully call service {fully_qualified_service_name} after {max_attempts} attempts."
)


Expand Down
2 changes: 1 addition & 1 deletion controller_manager/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="2">
<name>controller_manager</name>
<version>4.16.1</version>
<version>4.17.0</version>
<description>Description of controller_manager</description>
<maintainer email="bence.magyar.robotics@gmail.com">Bence Magyar</maintainer>
<maintainer email="denis@stoglrobotics.de">Denis Štogl</maintainer>
Expand Down
40 changes: 24 additions & 16 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -470,8 +470,9 @@ controller_interface::ControllerInterfaceBaseSharedPtr ControllerManager::load_c
catch (const std::exception & e)
{
RCLCPP_ERROR(
get_logger(), "Caught exception while loading the controller '%s' of plugin type '%s':\n%s",
controller_name.c_str(), controller_type.c_str(), e.what());
get_logger(),
"Caught exception of type : %s while loading the controller '%s' of plugin type '%s':\n%s",
typeid(e).name(), controller_name.c_str(), controller_type.c_str(), e.what());
return nullptr;
}
catch (...)
Expand Down Expand Up @@ -615,8 +616,9 @@ controller_interface::return_type ControllerManager::unload_controller(
catch (const std::exception & e)
{
RCLCPP_ERROR(
get_logger(), "Failed to clean-up the controller '%s' before unloading: %s",
controller_name.c_str(), e.what());
get_logger(),
"Caught exception of type : %s while cleaning up the controller '%s' before unloading: %s",
typeid(e).name(), controller_name.c_str(), e.what());
}
catch (...)
{
Expand Down Expand Up @@ -720,8 +722,8 @@ controller_interface::return_type ControllerManager::configure_controller(
catch (const std::exception & e)
{
RCLCPP_ERROR(
get_logger(), "Caught exception while configuring controller '%s': %s",
controller_name.c_str(), e.what());
get_logger(), "Caught exception of type : %s while configuring controller '%s': %s",
typeid(e).name(), controller_name.c_str(), e.what());
return controller_interface::return_type::ERROR;
}
catch (...)
Expand Down Expand Up @@ -1432,8 +1434,8 @@ controller_interface::ControllerInterfaceBaseSharedPtr ControllerManager::add_co
{
to.clear();
RCLCPP_ERROR(
get_logger(), "Caught exception while initializing controller '%s': %s",
controller.info.name.c_str(), e.what());
get_logger(), "Caught exception of type : %s while initializing controller '%s': %s",
typeid(e).name(), controller.info.name.c_str(), e.what());
return nullptr;
}
catch (...)
Expand Down Expand Up @@ -1508,8 +1510,8 @@ void ControllerManager::deactivate_controllers(
catch (const std::exception & e)
{
RCLCPP_ERROR(
get_logger(), "Caught exception while deactivating the controller '%s': %s",
controller_name.c_str(), e.what());
get_logger(), "Caught exception of type : %s while deactivating the controller '%s': %s",
typeid(e).name(), controller_name.c_str(), e.what());
continue;
}
catch (...)
Expand Down Expand Up @@ -1626,7 +1628,10 @@ void ControllerManager::activate_controllers(
catch (const std::exception & e)
{
RCLCPP_ERROR(
get_logger(), "Can't activate controller '%s': %s", controller_name.c_str(), e.what());
get_logger(),
"Caught exception of type : %s while claiming the command interfaces. Can't activate "
"controller '%s': %s",
typeid(e).name(), controller_name.c_str(), e.what());
assignment_successful = false;
break;
}
Expand Down Expand Up @@ -1661,7 +1666,10 @@ void ControllerManager::activate_controllers(
catch (const std::exception & e)
{
RCLCPP_ERROR(
get_logger(), "Can't activate controller '%s': %s", controller_name.c_str(), e.what());
get_logger(),
"Caught exception of type : %s while claiming the state interfaces. Can't activate "
"controller '%s': %s",
typeid(e).name(), controller_name.c_str(), e.what());
assignment_successful = false;
break;
}
Expand Down Expand Up @@ -1689,8 +1697,8 @@ void ControllerManager::activate_controllers(
catch (const std::exception & e)
{
RCLCPP_ERROR(
get_logger(), "Caught exception while activating the controller '%s': %s",
controller_name.c_str(), e.what());
get_logger(), "Caught exception of type : %s while activating the controller '%s': %s",
typeid(e).name(), controller_name.c_str(), e.what());
continue;
}
catch (...)
Expand Down Expand Up @@ -2295,8 +2303,8 @@ controller_interface::return_type ControllerManager::update(
catch (const std::exception & e)
{
RCLCPP_ERROR(
get_logger(), "Caught exception while updating controller '%s': %s",
loaded_controller.info.name.c_str(), e.what());
get_logger(), "Caught exception of type : %s while updating controller '%s': %s",
typeid(e).name(), loaded_controller.info.name.c_str(), e.what());
controller_ret = controller_interface::return_type::ERROR;
}
catch (...)
Expand Down
3 changes: 3 additions & 0 deletions controller_manager_msgs/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package controller_manager_msgs
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

4.17.0 (2024-09-11)
-------------------

4.16.1 (2024-08-24)
-------------------

Expand Down
2 changes: 1 addition & 1 deletion controller_manager_msgs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>controller_manager_msgs</name>
<version>4.16.1</version>
<version>4.17.0</version>
<description>Messages and services for the controller manager.</description>
<maintainer email="bence.magyar.robotics@gmail.com">Bence Magyar</maintainer>
<maintainer email="denis@stoglrobotics.de">Denis Štogl</maintainer>
Expand Down
12 changes: 12 additions & 0 deletions doc/release_notes.rst
Original file line number Diff line number Diff line change
Expand Up @@ -119,3 +119,15 @@ ros2controlcli
.. code-block:: bash
ros2 control set_hardware_component_state <hardware_component_name> <state>
* The ``load_controller`` now supports parsing of the params file (`#1703 <https://github.com/ros-controls/ros2_control/pull/1703>`_).

.. code-block:: bash
ros2 control load_controller <controller_name> <realtive_or_absolute_file_path>
* All the ros2controlcli verbs now support the namespacing through the ROS 2 standard way (`#1703 <https://github.com/ros-controls/ros2_control/pull/1703>`_).

.. code-block:: bash
ros2 control <verb> <arguments> --ros-args -r __ns:=<namespace>
8 changes: 8 additions & 0 deletions hardware_interface/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,14 @@
Changelog for package hardware_interface
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

4.17.0 (2024-09-11)
-------------------
* Log exception type when catching the exception (`#1749 <https://github.com/ros-controls/ros2_control/issues/1749>`_)
* Fix spam of logs on failed hardware component initialization (`#1719 <https://github.com/ros-controls/ros2_control/issues/1719>`_)
* [HWItfs] Add key-value-storage to the InterfaceInfo (`#1421 <https://github.com/ros-controls/ros2_control/issues/1421>`_)
* Rename `get_state` and `set_state` Functions to `get/set_lifecylce_state` (variant support) (`#1683 <https://github.com/ros-controls/ros2_control/issues/1683>`_)
* Contributors: Manuel Muth, Sai Kishor Kothakota

4.16.1 (2024-08-24)
-------------------

Expand Down
2 changes: 1 addition & 1 deletion hardware_interface/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="2">
<name>hardware_interface</name>
<version>4.16.1</version>
<version>4.17.0</version>
<description>ros2_control hardware interface</description>
<maintainer email="bence.magyar.robotics@gmail.com">Bence Magyar</maintainer>
<maintainer email="denis@stoglrobotics.de">Denis Štogl</maintainer>
Expand Down
4 changes: 3 additions & 1 deletion hardware_interface/src/actuator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -183,7 +183,9 @@ const rclcpp_lifecycle::State & Actuator::deactivate()
const rclcpp_lifecycle::State & Actuator::error()
{
std::unique_lock<std::recursive_mutex> lock(actuators_mutex_);
if (impl_->get_lifecycle_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN)
if (
impl_->get_lifecycle_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN &&
impl_->get_lifecycle_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED)
{
switch (impl_->on_error(impl_->get_lifecycle_state()))
{
Expand Down
Loading

0 comments on commit a288f57

Please sign in to comment.