Skip to content

Commit

Permalink
Fix/spawner interrupt (#1666)
Browse files Browse the repository at this point in the history
* [ResourceManager] Make destructor virtual for use in derived classes (#1607)

* Fix typos in test_resource_manager.cpp (#1609)

* [CM] Remove support for the description parameter and use only `robot_description` topic (#1358)

---------

Co-authored-by: Felix Exner <exner@fzi.de>
Co-authored-by: Christoph Froehlich <christoph.froehlich@ait.ac.at>

* move critical variables to the private context (#1623)

* Fix controller starting with later load of robot description test (#1624)

* Fix the duplicated restart of the controller_manager services initialization

* Scope the ControllerManagerRunner to avoid malloc and other test issues

* reorder the tests for consistent log at the end

* Remove noqa (#1626)

* Unused header cleanup (#1627)

* Create debugging.rst (#1625)


---------

Co-authored-by: Sai Kishor Kothakota <saisastra3@gmail.com>
Co-authored-by: Christoph Froehlich <christoph.froehlich@ait.ac.at>

* Update changelogs

* 4.14.0

* add missing rclcpp logging include for Humble compatibility build (#1635)

* [CM] Remove deprecated spawner args (#1639)

* Add a pytest launch file to test ros2_control_node (#1636)

* Fix rst markup (#1642)

* Fix rqt_cm paragraph

* Fix indent

* CM: Add missing includes (#1641)

* [RM] Add `get_hardware_info` method to the Hardware Components (#1643)

* Fix the namespaced controller_manager spawner + added tests (#1640)

* Bump version of pre-commit hooks (#1649)

Co-authored-by: christophfroehlich <3367244+christophfroehlich@users.noreply.github.com>

* Add missing include for executors (#1653)

* Update changelogs

* 4.15.0

* refactor SwitchParams to fix the incosistencies in the spawner tests (#1638)

* Modify test with missing CM to have a timeout

* Catch exception when CM services are not found

And print the error and exit in the application

* Exit with code 1 on unreached CM

---------

Co-authored-by: Sai Kishor Kothakota <sai.kishor@pal-robotics.com>
Co-authored-by: Parker Drouillard <parker@pepcorp.ca>
Co-authored-by: Dr. Denis <denis@stoglrobotics.de>
Co-authored-by: Christoph Froehlich <christoph.froehlich@ait.ac.at>
Co-authored-by: Christoph Fröhlich <christophfroehlich@users.noreply.github.com>
Co-authored-by: Henry Moore <henry.moore@picknik.ai>
Co-authored-by: Lennart Nachtigall <firesurfer127@gmail.com>
Co-authored-by: Sai Kishor Kothakota <saisastra3@gmail.com>
Co-authored-by: Bence Magyar <bence.magyar.robotics@gmail.com>
Co-authored-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com>
Co-authored-by: christophfroehlich <3367244+christophfroehlich@users.noreply.github.com>
  • Loading branch information
12 people authored Aug 12, 2024
1 parent ea7d4ca commit 4044fc2
Show file tree
Hide file tree
Showing 125 changed files with 1,250 additions and 959 deletions.
4 changes: 2 additions & 2 deletions .pre-commit-config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ repos:

# Python hooks
- repo: https://github.com/asottile/pyupgrade
rev: v3.16.0
rev: v3.17.0
hooks:
- id: pyupgrade
args: [--py36-plus]
Expand Down Expand Up @@ -133,7 +133,7 @@ repos:
exclude: CHANGELOG\.rst|\.(svg|pyc|drawio)$

- repo: https://github.com/python-jsonschema/check-jsonschema
rev: 0.28.6
rev: 0.29.1
hooks:
- id: check-github-workflows
args: ["--verbose"]
Expand Down
9 changes: 9 additions & 0 deletions controller_interface/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,15 @@
Changelog for package controller_interface
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

4.15.0 (2024-08-05)
-------------------

4.14.0 (2024-07-23)
-------------------
* Unused header cleanup (`#1627 <https://github.com/ros-controls/ros2_control/issues/1627>`_)
* move critical variables to the private context (`#1623 <https://github.com/ros-controls/ros2_control/issues/1623>`_)
* Contributors: Henry Moore, Sai Kishor Kothakota

4.13.0 (2024-07-08)
-------------------
* [ControllerChaining] Export state interfaces from chainable controllers (`#1021 <https://github.com/ros-controls/ros2_control/issues/1021>`_)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@
#define CONTROLLER_INTERFACE__CONTROLLER_INTERFACE_HPP_

#include <memory>
#include <string>
#include <vector>

#include "controller_interface/controller_interface_base.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,6 @@
#include "hardware_interface/loaned_command_interface.hpp"
#include "hardware_interface/loaned_state_interface.hpp"

#include "rclcpp/rclcpp.hpp"
#include "rclcpp/version.h"
#include "rclcpp_lifecycle/lifecycle_node.hpp"

Expand Down Expand Up @@ -258,12 +257,12 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
protected:
std::vector<hardware_interface::LoanedCommandInterface> command_interfaces_;
std::vector<hardware_interface::LoanedStateInterface> state_interfaces_;
unsigned int update_rate_ = 0;
bool is_async_ = false;
std::string urdf_ = "";

private:
std::shared_ptr<rclcpp_lifecycle::LifecycleNode> node_;
unsigned int update_rate_ = 0;
bool is_async_ = false;
std::string urdf_ = "";
};

using ControllerInterfaceBaseSharedPtr = std::shared_ptr<ControllerInterfaceBase>;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@
#ifndef SEMANTIC_COMPONENTS__RANGE_SENSOR_HPP_
#define SEMANTIC_COMPONENTS__RANGE_SENSOR_HPP_

#include <limits>
#include <string>
#include <vector>

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.13.0</version>
<version>4.15.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
6 changes: 0 additions & 6 deletions controller_interface/src/controller_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,14 +14,8 @@

#include "controller_interface/controller_interface.hpp"

#include <memory>
#include <string>
#include <utility>
#include <vector>

#include "hardware_interface/types/lifecycle_state_names.hpp"
#include "lifecycle_msgs/msg/state.hpp"

namespace controller_interface
{
ControllerInterface::ControllerInterface() : ControllerInterfaceBase() {}
Expand Down
1 change: 0 additions & 1 deletion controller_interface/src/controller_interface_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@
#include <utility>
#include <vector>

#include "hardware_interface/types/lifecycle_state_names.hpp"
#include "lifecycle_msgs/msg/state.hpp"

namespace controller_interface
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,14 +15,13 @@
#ifndef TEST_CHAINABLE_CONTROLLER_INTERFACE_HPP_
#define TEST_CHAINABLE_CONTROLLER_INTERFACE_HPP_

#include <gmock/gmock.h>

#include <string>
#include <vector>

#include "gmock/gmock.h"

#include "controller_interface/chainable_controller_interface.hpp"
#include "hardware_interface/handle.hpp"
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"

constexpr char TEST_CONTROLLER_NAME[] = "testable_chainable_controller";
constexpr double INTERFACE_VALUE = 1989.0;
Expand Down
1 change: 0 additions & 1 deletion controller_interface/test/test_controller_interface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@
#define TEST_CONTROLLER_INTERFACE_HPP_

#include "controller_interface/controller_interface.hpp"
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"

constexpr char TEST_CONTROLLER_NAME[] = "testable_controller_interface";

Expand Down
1 change: 0 additions & 1 deletion controller_interface/test/test_controller_with_options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@
#include <gtest/gtest.h>
#include <string>
#include "ament_index_cpp/get_package_prefix.hpp"
#include "rclcpp/rclcpp.hpp"

class FriendControllerWithOptions : public controller_with_options::ControllerWithOptions
{
Expand Down
2 changes: 0 additions & 2 deletions controller_interface/test/test_controller_with_options.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,11 +16,9 @@
#define TEST_CONTROLLER_WITH_OPTIONS_HPP_

#include <map>
#include <memory>
#include <string>

#include "controller_interface/controller_interface.hpp"
#include "hardware_interface/types/lifecycle_state_names.hpp"

namespace controller_with_options
{
Expand Down
4 changes: 2 additions & 2 deletions controller_interface/test/test_force_torque_sensor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,12 +19,12 @@
#ifndef TEST_FORCE_TORQUE_SENSOR_HPP_
#define TEST_FORCE_TORQUE_SENSOR_HPP_

#include <gmock/gmock.h>

#include <memory>
#include <string>
#include <vector>

#include "gmock/gmock.h"

#include "semantic_components/force_torque_sensor.hpp"

// implementing and friending so we can access member variables
Expand Down
4 changes: 2 additions & 2 deletions controller_interface/test/test_imu_sensor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,12 +19,12 @@
#ifndef TEST_IMU_SENSOR_HPP_
#define TEST_IMU_SENSOR_HPP_

#include <gmock/gmock.h>

#include <memory>
#include <string>
#include <vector>

#include "gmock/gmock.h"

#include "semantic_components/imu_sensor.hpp"

// implementing and friending so we can access member variables
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,11 +19,12 @@
#ifndef TEST_SEMANTIC_COMPONENT_INTERFACE_HPP_
#define TEST_SEMANTIC_COMPONENT_INTERFACE_HPP_

#include <gmock/gmock.h>

#include <memory>
#include <string>

#include "geometry_msgs/msg/wrench.hpp"
#include "gmock/gmock.h"
#include "semantic_components/semantic_component_interface.hpp"

// implementing and friending so we can access member variables
Expand Down
18 changes: 18 additions & 0 deletions controller_manager/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,24 @@
Changelog for package controller_manager
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

4.15.0 (2024-08-05)
-------------------
* Add missing include for executors (`#1653 <https://github.com/ros-controls/ros2_control/issues/1653>`_)
* Fix the namespaced controller_manager spawner + added tests (`#1640 <https://github.com/ros-controls/ros2_control/issues/1640>`_)
* CM: Add missing includes (`#1641 <https://github.com/ros-controls/ros2_control/issues/1641>`_)
* Fix rst markup (`#1642 <https://github.com/ros-controls/ros2_control/issues/1642>`_)
* Add a pytest launch file to test ros2_control_node (`#1636 <https://github.com/ros-controls/ros2_control/issues/1636>`_)
* [CM] Remove deprecated spawner args (`#1639 <https://github.com/ros-controls/ros2_control/issues/1639>`_)
* Contributors: Christoph Fröhlich, Sai Kishor Kothakota

4.14.0 (2024-07-23)
-------------------
* Unused header cleanup (`#1627 <https://github.com/ros-controls/ros2_control/issues/1627>`_)
* Remove noqa (`#1626 <https://github.com/ros-controls/ros2_control/issues/1626>`_)
* Fix controller starting with later load of robot description test (`#1624 <https://github.com/ros-controls/ros2_control/issues/1624>`_)
* [CM] Remove support for the description parameter and use only `robot_description` topic (`#1358 <https://github.com/ros-controls/ros2_control/issues/1358>`_)
* Contributors: Christoph Fröhlich, Dr. Denis, Henry Moore, Sai Kishor Kothakota

4.13.0 (2024-07-08)
-------------------
* Change the spamming checking interface ERROR to DEBUG (`#1605 <https://github.com/ros-controls/ros2_control/issues/1605>`_)
Expand Down
7 changes: 7 additions & 0 deletions controller_manager/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -152,6 +152,7 @@ if(BUILD_TESTING)
)
target_link_libraries(test_controller_manager_urdf_passing
controller_manager
test_controller
ros2_control_test_assets::ros2_control_test_assets
)
ament_target_dependencies(test_controller_manager_urdf_passing
Expand Down Expand Up @@ -184,6 +185,7 @@ if(BUILD_TESTING)

ament_add_gmock(test_spawner_unspawner
test/test_spawner_unspawner.cpp
TIMEOUT 120
)
target_link_libraries(test_spawner_unspawner
controller_manager
Expand All @@ -208,6 +210,11 @@ if(BUILD_TESTING)
ament_target_dependencies(test_hardware_management_srvs
controller_manager_msgs
)

find_package(ament_cmake_pytest REQUIRED)
install(FILES test/test_ros2_control_node.yaml
DESTINATION test)
ament_add_pytest_test(test_ros2_control_node test/test_ros2_control_node_launch.py)
endif()

install(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,15 +28,18 @@
import rclpy


class ServiceNotFoundError(Exception):
pass


def service_caller(node, service_name, service_type, request, service_timeout=0.0):
cli = node.create_client(service_type, service_name)

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

Expand Down
19 changes: 4 additions & 15 deletions controller_manager/controller_manager/launch_utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,6 @@
# See the License for the specific language governing permissions and
# limitations under the License.

import warnings
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration, PythonExpression
Expand All @@ -21,7 +20,7 @@


def generate_load_controller_launch_description(
controller_name, controller_type=None, controller_params_file=None, extra_spawner_args=[]
controller_name, controller_params_file=None, extra_spawner_args=[]
):
"""
Generate launch description for loading a controller using spawner.
Expand All @@ -30,15 +29,14 @@ def generate_load_controller_launch_description(
'unload_on_kill' LaunchArguments and a Node action that runs the controller_manager
spawner node to load and activate a controller
Examples # noqa: D416
Examples
--------
# Assuming the controller type and controller parameters are known to the controller_manager
# Assuming the controller parameters are known to the controller_manager
generate_load_controller_launch_description('joint_state_broadcaster')
# Passing controller type and controller parameter file to load
# Passing controller parameter file to load the controller (Controller type is retrieved from config file)
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'),
extra_spawner_args=[--load-only]
Expand All @@ -62,15 +60,6 @@ def generate_load_controller_launch_description(
LaunchConfiguration("controller_manager_name"),
]

if controller_type:
warnings.warn(
"The 'controller_type' argument is deprecated and will be removed in future releases."
" Declare the controller type parameter in the param file instead.",
DeprecationWarning,
stacklevel=2,
)
spawner_arguments += ["--controller-type", controller_type]

if controller_params_file:
spawner_arguments += ["--param-file", controller_params_file]

Expand Down
Loading

0 comments on commit 4044fc2

Please sign in to comment.