Skip to content

Commit

Permalink
Merge branch 'master' into fix/spawner/on/resource/conflict
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich authored Dec 19, 2024
2 parents 39c67da + 612b30b commit b436a4e
Show file tree
Hide file tree
Showing 39 changed files with 989 additions and 145 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 <[email protected]>

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 <[email protected]>

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 <[email protected]>

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 @@ -58,10 +58,12 @@ target_link_libraries(ros2_control_node PRIVATE
if(BUILD_TESTING)
find_package(ament_cmake_gmock REQUIRED)
find_package(ros2_control_test_assets REQUIRED)
find_package(example_interfaces REQUIRED)

# Plugin Libraries that are built and installed for use in testing
add_library(test_controller SHARED test/test_controller/test_controller.cpp)
target_link_libraries(test_controller PUBLIC controller_manager)
ament_target_dependencies(test_controller PUBLIC example_interfaces)
target_compile_definitions(test_controller PRIVATE "CONTROLLER_MANAGER_BUILDING_DLL")
pluginlib_export_plugin_description_file(controller_interface test/test_controller/test_controller.xml)
install(
Expand Down Expand Up @@ -210,6 +212,7 @@ if(BUILD_TESTING)
)
target_link_libraries(test_hardware_spawner
controller_manager
test_controller
ros2_control_test_assets::ros2_control_test_assets
)

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
17 changes: 17 additions & 0 deletions controller_manager/controller_manager/spawner.py
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
load_controller,
switch_controllers,
unload_controller,
set_controller_parameters,
set_controller_parameters_from_param_files,
bcolors,
)
Expand Down Expand Up @@ -145,6 +146,12 @@ def main(args=None):
action="store_true",
required=False,
)
parser.add_argument(
"--controller-ros-args",
help="The --ros-args to be passed to the controller node for remapping topics etc",
default=None,
required=False,
)

command_line_args = rclpy.utilities.remove_ros_args(args=sys.argv)[1:]
args = parser.parse_args(command_line_args)
Expand Down Expand Up @@ -203,6 +210,15 @@ def main(args=None):
+ bcolors.ENDC
)
else:
if controller_ros_args := args.controller_ros_args:
if not set_controller_parameters(
node,
controller_manager_name,
controller_name,
"node_options_args",
controller_ros_args.split(),
):
return 1
if param_files:
if not set_controller_parameters_from_param_files(
node,
Expand Down Expand Up @@ -342,6 +358,7 @@ def main(args=None):
node.get_logger().fatal(str(err))
return 1
finally:
node.destroy_node()
rclpy.shutdown()


Expand Down
4 changes: 3 additions & 1 deletion controller_manager/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -142,7 +142,7 @@ There are two scripts to interact with controller manager from launch files:
$ ros2 run controller_manager spawner -h
usage: spawner [-h] [-c CONTROLLER_MANAGER] [-p PARAM_FILE] [-n NAMESPACE] [--load-only] [--inactive] [-u] [--controller-manager-timeout CONTROLLER_MANAGER_TIMEOUT]
[--switch-timeout SWITCH_TIMEOUT] [--activate-as-group] [--service-call-timeout SERVICE_CALL_TIMEOUT]
[--switch-timeout SWITCH_TIMEOUT] [--activate-as-group] [--service-call-timeout SERVICE_CALL_TIMEOUT] [--controller-ros-args CONTROLLER_ROS_ARGS]
controller_names [controller_names ...]
positional arguments:
Expand All @@ -167,6 +167,8 @@ There are two scripts to interact with controller manager from launch files:
Time to wait for a successful state switch of controllers. Useful if controllers cannot be switched immediately, e.g., paused
simulations at startup
--activate-as-group Activates all the parsed controllers list together instead of one by one. Useful for activating all chainable controllers altogether
--controller-ros-args CONTROLLER_ROS_ARGS
The --ros-args to be passed to the controller node for remapping topics etc
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:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -222,15 +222,6 @@ class ControllerManager : public rclcpp::Node
CONTROLLER_MANAGER_PUBLIC
unsigned int get_update_rate() const;

/// Deletes all async controllers and components.
/**
* Needed to join the threads immediately after the control loop is ended
* to avoid unnecessary iterations. Otherwise
* the threads will be joined only when the controller manager gets destroyed.
*/
CONTROLLER_MANAGER_PUBLIC
void shutdown_async_controllers_and_components();

protected:
CONTROLLER_MANAGER_PUBLIC
void init_services();
Expand Down
1 change: 1 addition & 0 deletions controller_manager/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@
<test_depend>python3-coverage</test_depend>
<test_depend>hardware_interface_testing</test_depend>
<test_depend>ros2_control_test_assets</test_depend>
<test_depend>example_interfaces</test_depend>

<export>
<build_type>ament_cmake</build_type>
Expand Down
40 changes: 35 additions & 5 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -616,6 +616,17 @@ controller_interface::ControllerInterfaceBaseSharedPtr ControllerManager::load_c
controller_spec.info.fallback_controllers_names = fallback_controllers;
}

const std::string node_options_args_param = controller_name + ".node_options_args";
std::vector<std::string> node_options_args;
if (!has_parameter(node_options_args_param))
{
declare_parameter(node_options_args_param, rclcpp::ParameterType::PARAMETER_STRING_ARRAY);
}
if (get_parameter(node_options_args_param, node_options_args) && !node_options_args.empty())
{
controller_spec.info.node_options_args = node_options_args;
}

return add_controller_impl(controller_spec);
}

Expand Down Expand Up @@ -2714,11 +2725,6 @@ std::pair<std::string, std::string> ControllerManager::split_command_interface(

unsigned int ControllerManager::get_update_rate() const { return update_rate_; }

void ControllerManager::shutdown_async_controllers_and_components()
{
resource_manager_->shutdown_async_components();
}

void ControllerManager::propagate_deactivation_of_chained_mode(
const std::vector<ControllerSpec> & controllers)
{
Expand Down Expand Up @@ -3486,6 +3492,18 @@ rclcpp::NodeOptions ControllerManager::determine_controller_node_options(
node_options_arguments.push_back(arg);
}

// Add deprecation notice if the arguments are from the controller_manager node
if (
check_for_element(node_options_arguments, RCL_REMAP_FLAG) ||
check_for_element(node_options_arguments, RCL_SHORT_REMAP_FLAG))
{
RCLCPP_WARN(
get_logger(),
"The use of remapping arguments to the controller_manager node is deprecated. Please use the "
"'--controller-ros-args' argument of the spawner to pass remapping arguments to the "
"controller node.");
}

for (const auto & parameters_file : controller.info.parameters_files)
{
if (!check_for_element(node_options_arguments, RCL_ROS_ARGS_FLAG))
Expand All @@ -3508,6 +3526,18 @@ rclcpp::NodeOptions ControllerManager::determine_controller_node_options(
node_options_arguments.push_back("use_sim_time:=true");
}

// Add options parsed through the spawner
if (
!controller.info.node_options_args.empty() &&
!check_for_element(controller.info.node_options_args, RCL_ROS_ARGS_FLAG))
{
node_options_arguments.push_back(RCL_ROS_ARGS_FLAG);
}
for (const auto & arg : controller.info.node_options_args)
{
node_options_arguments.push_back(arg);
}

std::string arguments;
arguments.reserve(1000);
for (const auto & arg : node_options_arguments)
Expand Down
2 changes: 0 additions & 2 deletions controller_manager/src/ros2_control_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -147,8 +147,6 @@ int main(int argc, char ** argv)
std::this_thread::sleep_until(next_iteration_time);
}
}

cm->shutdown_async_controllers_and_components();
});

executor->add_node(cm);
Expand Down
Loading

0 comments on commit b436a4e

Please sign in to comment.