Skip to content

Commit

Permalink
Merge branch 'master' into tpo-add_semantic_cmd_interface
Browse files Browse the repository at this point in the history
  • Loading branch information
tpoignonec authored Dec 18, 2024
2 parents 2e2798f + b039baa commit 6c8b092
Show file tree
Hide file tree
Showing 11 changed files with 268 additions and 1 deletion.
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
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
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
13 changes: 13 additions & 0 deletions downstream.humble.repos
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
repositories:
UniversalRobots/Universal_Robots_ROS2_Driver:
type: git
url: https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver.git
version: humble
webots/webots_ros2:
type: git
url: https://github.com/cyberbotics/webots_ros2.git
version: master
PickNikRobotics/topic_based_ros2_control:
type: git
url: https://github.com/PickNikRobotics/topic_based_ros2_control.git
version: main
13 changes: 13 additions & 0 deletions downstream.jazzy.repos
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
repositories:
UniversalRobots/Universal_Robots_ROS2_Driver:
type: git
url: https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver.git
version: main
webots/webots_ros2:
type: git
url: https://github.com/cyberbotics/webots_ros2.git
version: master
PickNikRobotics/topic_based_ros2_control:
type: git
url: https://github.com/PickNikRobotics/topic_based_ros2_control.git
version: main
13 changes: 13 additions & 0 deletions downstream.rolling.repos
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
repositories:
UniversalRobots/Universal_Robots_ROS2_Driver:
type: git
url: https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver.git
version: main
webots/webots_ros2:
type: git
url: https://github.com/cyberbotics/webots_ros2.git
version: master
PickNikRobotics/topic_based_ros2_control:
type: git
url: https://github.com/PickNikRobotics/topic_based_ros2_control.git
version: main
17 changes: 17 additions & 0 deletions ros_controls.humble.repos
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
repositories:
ros-controls/gazebo_ros2_control:
type: git
url: https://github.com/ros-controls/gazebo_ros2_control.git
version: humble
ros-controls/gz_ros2_control:
type: git
url: https://github.com/ros-controls/gz_ros2_control.git
version: humble
ros-controls/ros2_control_demos:
type: git
url: https://github.com/ros-controls/ros2_control_demos.git
version: humble
ros-controls/ros2_controllers:
type: git
url: https://github.com/ros-controls/ros2_controllers.git
version: humble
13 changes: 13 additions & 0 deletions ros_controls.jazzy.repos
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
repositories:
ros-controls/gz_ros2_control:
type: git
url: https://github.com/ros-controls/gz_ros2_control.git
version: jazzy
ros-controls/ros2_control_demos:
type: git
url: https://github.com/ros-controls/ros2_control_demos.git
version: master
ros-controls/ros2_controllers:
type: git
url: https://github.com/ros-controls/ros2_controllers.git
version: master
13 changes: 13 additions & 0 deletions ros_controls.rolling.repos
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
repositories:
ros-controls/gz_ros2_control:
type: git
url: https://github.com/ros-controls/gz_ros2_control.git
version: rolling
ros-controls/ros2_control_demos:
type: git
url: https://github.com/ros-controls/ros2_control_demos.git
version: master
ros-controls/ros2_controllers:
type: git
url: https://github.com/ros-controls/ros2_controllers.git
version: master

0 comments on commit 6c8b092

Please sign in to comment.