Skip to content

Commit

Permalink
Merge branch 'master' into semantic_components_cleanup
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich authored Dec 18, 2024
2 parents 03ee6c2 + e7d2fcc commit 441cc60
Show file tree
Hide file tree
Showing 19 changed files with 429 additions and 52 deletions.
49 changes: 49 additions & 0 deletions .github/workflows/humble-semi-binary-downstream-build.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
name: Humble Downstream Build
# description: 'Build & test downstream packages from source.'
# author: Christoph Froehlich <christoph.froehlich@ait.ac.at>

on:
workflow_dispatch:
pull_request:
branches:
- humble
paths:
- '**.hpp'
- '**.h'
- '**.cpp'
- '**.py'
- '**.yaml'
- '.github/workflows/humble-semi-binary-downstream-build.yml'
- '**/package.xml'
- '**/CMakeLists.txt'
- 'ros_controls.humble.repos'

concurrency:
group: ${{ github.workflow }}-${{ github.ref }}
cancel-in-progress: true

jobs:
build-downstream:
uses: ros-controls/ros2_control_ci/.github/workflows/reusable-industrial-ci-with-cache.yml@master
with:
ros_distro: humble
ros_repo: testing
ref_for_scheduled_build: humble
upstream_workspace: ros2_control.humble.repos
# we don't test this repository, we just build it
not_test_build: true
# we test the downstream packages, which are part of our organization
downstream_workspace: ros_controls.humble.repos
not_test_downstream: false
build-downstream-3rd-party:
uses: ros-controls/ros2_control_ci/.github/workflows/reusable-industrial-ci-with-cache.yml@master
with:
ros_distro: humble
ros_repo: testing
ref_for_scheduled_build: humble
upstream_workspace: ros2_control.humble.repos
# we don't test this repository, we just build it
not_test_build: true
# we don't test the downstream packages, which are outside of our organization
downstream_workspace: downstream.humble.repos
not_test_downstream: true
49 changes: 49 additions & 0 deletions .github/workflows/jazzy-semi-binary-downstream-build.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
name: Jazzy Downstream Build
# description: 'Build & test downstream packages from source.'
# author: Christoph Froehlich <christoph.froehlich@ait.ac.at>

on:
workflow_dispatch:
pull_request:
branches:
- master
paths:
- '**.hpp'
- '**.h'
- '**.cpp'
- '**.py'
- '**.yaml'
- '.github/workflows/jazzy-semi-binary-downstream-build.yml'
- '**/package.xml'
- '**/CMakeLists.txt'
- 'ros_controls.jazzy.repos'

concurrency:
group: ${{ github.workflow }}-${{ github.ref }}
cancel-in-progress: true

jobs:
build-downstream:
uses: ros-controls/ros2_control_ci/.github/workflows/reusable-industrial-ci-with-cache.yml@master
with:
ros_distro: jazzy
ros_repo: testing
ref_for_scheduled_build: master
upstream_workspace: ros2_control.jazzy.repos
# we don't test this repository, we just build it
not_test_build: true
# we test the downstream packages, which are part of our organization
downstream_workspace: ros_controls.jazzy.repos
not_test_downstream: false
build-downstream-3rd-party:
uses: ros-controls/ros2_control_ci/.github/workflows/reusable-industrial-ci-with-cache.yml@master
with:
ros_distro: jazzy
ros_repo: testing
ref_for_scheduled_build: master
upstream_workspace: ros2_control.jazzy.repos
# we don't test this repository, we just build it
not_test_build: true
# we don't test the downstream packages, which are outside of our organization
downstream_workspace: downstream.jazzy.repos
not_test_downstream: true
57 changes: 57 additions & 0 deletions .github/workflows/rolling-semi-binary-downstream-build.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,57 @@
name: Rolling Downstream Build
# description: 'Build & test downstream packages from source.'
# author: Christoph Froehlich <christoph.froehlich@ait.ac.at>

on:
workflow_dispatch:
pull_request:
branches:
- master
paths:
- '**.hpp'
- '**.h'
- '**.cpp'
- '**.py'
- '**.yaml'
- '.github/workflows/rolling-semi-binary-downstream-build.yml'
- '**/package.xml'
- '**/CMakeLists.txt'
- 'ros_controls.rolling.repos'

concurrency:
group: ${{ github.workflow }}-${{ github.ref }}
cancel-in-progress: true

jobs:
build-downstream:
uses: ros-controls/ros2_control_ci/.github/workflows/reusable-industrial-ci-with-cache.yml@master
strategy:
fail-fast: false
matrix:
ROS_DISTRO: [rolling]
with:
ros_distro: ${{ matrix.ROS_DISTRO }}
ros_repo: testing
ref_for_scheduled_build: master
upstream_workspace: ros2_control.${{ matrix.ROS_DISTRO }}.repos
# we don't test this repository, we just build it
not_test_build: true
# we test the downstream packages, which are part of our organization
downstream_workspace: ros_controls.${{ matrix.ROS_DISTRO }}.repos
not_test_downstream: false
build-downstream-3rd-party:
uses: ros-controls/ros2_control_ci/.github/workflows/reusable-industrial-ci-with-cache.yml@master
strategy:
fail-fast: false
matrix:
ROS_DISTRO: [rolling]
with:
ros_distro: ${{ matrix.ROS_DISTRO }}
ros_repo: testing
ref_for_scheduled_build: master
upstream_workspace: ros2_control.${{ matrix.ROS_DISTRO }}.repos
# we don't test this repository, we just build it
not_test_build: true
# we don't test the downstream packages, which are outside of our organization
downstream_workspace: downstream.${{ matrix.ROS_DISTRO }}.repos
not_test_downstream: true
3 changes: 3 additions & 0 deletions controller_manager/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -222,6 +222,9 @@ if(BUILD_TESTING)
install(FILES test/test_controller_overriding_parameters.yaml
DESTINATION test)

install(FILES test/test_controller_spawner_wildcard_entries.yaml
DESTINATION test)

ament_add_gmock(test_hardware_management_srvs
test/test_hardware_management_srvs.cpp
)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,35 @@ class ServiceNotFoundError(Exception):
pass


class SingletonServiceCaller:
"""
Singleton class to call services of controller manager.
This class is used to create a service client for a given service name.
If the service client already exists, it returns the existing client.
It is used to avoid creating multiple service clients for the same service name.
It needs Node object, service type and fully qualified service name to create a service client.
"""

_clients = {}

def __new__(cls, node, service_type, fully_qualified_service_name):
if (node, fully_qualified_service_name) not in cls._clients:
cls._clients[(node, fully_qualified_service_name)] = node.create_client(
service_type, fully_qualified_service_name
)
node.get_logger().debug(
f"{bcolors.MAGENTA}Creating a new service client : {fully_qualified_service_name} with node : {node.get_name()}{bcolors.ENDC}"
)

node.get_logger().debug(
f"{bcolors.OKBLUE}Returning the existing service client : {fully_qualified_service_name} for node : {node.get_name()}{bcolors.ENDC}"
)
return cls._clients[(node, fully_qualified_service_name)]


def service_caller(
node,
service_name,
Expand Down Expand Up @@ -92,7 +121,7 @@ def service_caller(
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)
cli = SingletonServiceCaller(node, service_type, fully_qualified_service_name)

while not cli.service_is_ready():
node.get_logger().info(
Expand Down Expand Up @@ -296,6 +325,7 @@ def get_params_files_with_controller_parameters(
f"/{controller_name}" if namespace == "/" else f"{namespace}/{controller_name}"
)
WILDCARD_KEY = "/**"
ROS_PARAMS_KEY = "ros__parameters"
parameters = yaml.safe_load(f)
# check for the parameter in 'controller_name' or 'namespaced_controller' or '/**/namespaced_controller' or '/**/controller_name'
for key in [
Expand All @@ -304,6 +334,8 @@ def get_params_files_with_controller_parameters(
f"{WILDCARD_KEY}/{controller_name}",
f"{WILDCARD_KEY}{namespaced_controller}",
]:
if parameter_file in controller_parameter_files:
break
if key in parameters:
if key == controller_name and namespace != "/":
node.get_logger().fatal(
Expand All @@ -314,6 +346,8 @@ def get_params_files_with_controller_parameters(

if WILDCARD_KEY in parameters and key in parameters[WILDCARD_KEY]:
controller_parameter_files.append(parameter_file)
if WILDCARD_KEY in parameters and ROS_PARAMS_KEY in parameters[WILDCARD_KEY]:
controller_parameter_files.append(parameter_file)
return controller_parameter_files


Expand Down Expand Up @@ -346,6 +380,8 @@ def get_parameter_from_param_files(

if WILDCARD_KEY in parameters and key in parameters[WILDCARD_KEY]:
controller_param_dict = parameters[WILDCARD_KEY][key]
if WILDCARD_KEY in parameters and ROS_PARAMS_KEY in parameters[WILDCARD_KEY]:
controller_param_dict = parameters[WILDCARD_KEY]

if controller_param_dict and (
not isinstance(controller_param_dict, dict)
Expand Down
1 change: 1 addition & 0 deletions controller_manager/controller_manager/spawner.py
Original file line number Diff line number Diff line change
Expand Up @@ -342,6 +342,7 @@ def main(args=None):
node.get_logger().fatal(str(err))
return 1
finally:
node.destroy_node()
rclpy.shutdown()


Expand Down
86 changes: 53 additions & 33 deletions controller_manager/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -171,57 +171,77 @@ There are two scripts to interact with controller manager from launch files:
The parsed controller config file can follow the same conventions as the typical ROS 2 parameter file format. Now, the spawner can handle config files with wildcard entries and also the controller name in the absolute namespace. See the following examples on the config files:

.. code-block:: yaml
/**:
ros__parameters:
type: joint_trajectory_controller/JointTrajectoryController
command_interfaces:
- position
.....
position_trajectory_controller_joint1:
ros__parameters:
joints:
- joint1
position_trajectory_controller_joint2:
ros__parameters:
joints:
- joint2
.. code-block:: yaml
/**/position_trajectory_controller:
ros__parameters:
type: joint_trajectory_controller/JointTrajectoryController
joints:
- joint1
- joint2
ros__parameters:
type: joint_trajectory_controller/JointTrajectoryController
joints:
- joint1
- joint2
command_interfaces:
- position
.....
command_interfaces:
- position
.....
.. code-block:: yaml
/position_trajectory_controller:
ros__parameters:
type: joint_trajectory_controller/JointTrajectoryController
joints:
- joint1
- joint2
ros__parameters:
type: joint_trajectory_controller/JointTrajectoryController
joints:
- joint1
- joint2
command_interfaces:
- position
.....
command_interfaces:
- position
.....
.. code-block:: yaml
position_trajectory_controller:
ros__parameters:
type: joint_trajectory_controller/JointTrajectoryController
joints:
- joint1
- joint2
ros__parameters:
type: joint_trajectory_controller/JointTrajectoryController
joints:
- joint1
- joint2
command_interfaces:
- position
.....
command_interfaces:
- position
.....
.. code-block:: yaml
/rrbot_1/position_trajectory_controller:
ros__parameters:
type: joint_trajectory_controller/JointTrajectoryController
joints:
- joint1
- joint2
command_interfaces:
- position
.....
ros__parameters:
type: joint_trajectory_controller/JointTrajectoryController
joints:
- joint1
- joint2
command_interfaces:
- position
.....
``unspawner``
^^^^^^^^^^^^^^^^
Expand Down
19 changes: 9 additions & 10 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2367,17 +2367,16 @@ controller_interface::return_type ControllerManager::update(
update_loop_counter_ %= update_rate_;

// Check for valid time
if (
!get_clock()->started() &&
time == rclcpp::Time(0, 0, this->get_node_clock_interface()->get_clock()->get_clock_type()))
{
throw std::runtime_error(
"No clock received, and time argument is zero. Check your controller_manager node's "
"clock configuration (use_sim_time parameter) and if a valid clock source is "
"available. Also pass a proper time argument to the update method.");
}
else
if (!get_clock()->started())
{
if (time == rclcpp::Time(0, 0, this->get_node_clock_interface()->get_clock()->get_clock_type()))
{
throw std::runtime_error(
"No clock received, and time argument is zero. Check your controller_manager node's "
"clock configuration (use_sim_time parameter) and if a valid clock source is "
"available. Also pass a proper time argument to the update method.");
}

// this can happen with use_sim_time=true until the /clock is received
rclcpp::Clock clock = rclcpp::Clock();
RCLCPP_WARN_THROTTLE(
Expand Down
Loading

0 comments on commit 441cc60

Please sign in to comment.