From 730f5f92368d8acf237ee9dfc131ce7dbc7f3495 Mon Sep 17 00:00:00 2001 From: Kalana Ratnayake Date: Fri, 22 Aug 2025 13:15:49 +1000 Subject: [PATCH 1/5] moved capability interfaces,providers and semantic interfaces together --- .../capabilities2_launch/__init__.py | 0 .../capabilities2_launch.py | 146 --------- capabilities2_launch/launch/server.launch.py | 37 --- .../launch_server/__init__.py | 0 .../launch_server/launch_process.py | 140 --------- capabilities2_launch/launch_server/server.py | 65 ---- capabilities2_launch/package.xml | 23 -- .../resource/capabilities2_launch | 0 capabilities2_launch/setup.cfg | 4 - capabilities2_launch/setup.py | 29 -- capabilities2_launch/test/test_copyright.py | 25 -- capabilities2_launch/test/test_flake8.py | 25 -- capabilities2_launch/test/test_pep257.py | 23 -- .../capabilities2_launch_proxy/__init__.py | 0 .../capabilities_launch_proxy.py | 280 ------------------ capabilities2_launch_proxy/package.xml | 19 -- capabilities2_launch_proxy/readme.md | 46 --- .../resource/capabilities2_launch_proxy | 0 capabilities2_launch_proxy/setup.cfg | 4 - capabilities2_launch_proxy/setup.py | 26 -- .../test/call_use_launch_runner.py | 94 ------ capabilities2_runner_audio/.clang-format | 64 ---- capabilities2_runner_audio/CMakeLists.txt | 64 ---- .../listen_runner.hpp | 96 ------ .../speak_runner.hpp | 75 ----- capabilities2_runner_audio/package.xml | 38 --- capabilities2_runner_audio/plugins.xml | 12 - .../src/audio_runners.cpp | 8 - capabilities2_runner_bt/.clang-format | 64 ---- capabilities2_runner_bt/CMakeLists.txt | 62 ---- .../bt_factory_runner.hpp | 87 ------ .../bt_runner_base.hpp | 109 ------- capabilities2_runner_bt/package.xml | 36 --- capabilities2_runner_bt/plugins.xml | 6 - capabilities2_runner_bt/readme.md | 35 --- capabilities2_runner_bt/src/bt_runners.cpp | 5 - .../CMakeLists.txt | 8 + .../interfaces/CapabilityGetRunner.yaml | 34 +++ capabilities2_runner_capabilities/package.xml | 9 + .../providers/CapabilityGetRunner.yaml | 9 + capabilities2_runner_fabric/.clang-format | 64 ---- capabilities2_runner_fabric/CMakeLists.txt | 63 ---- .../set_plan_runner.hpp | 61 ---- capabilities2_runner_fabric/package.xml | 34 --- capabilities2_runner_fabric/plugins.xml | 7 - .../src/fabric_runners.cpp | 6 - capabilities2_runner_nav2/.clang-format | 64 ---- capabilities2_runner_nav2/CMakeLists.txt | 69 ----- .../occupancygrid_runner.hpp | 132 --------- .../robotpose_runner.hpp | 207 ------------- .../waypoint_runner.hpp | 97 ------ capabilities2_runner_nav2/package.xml | 34 --- capabilities2_runner_nav2/plugins.xml | 17 -- .../src/nav2_runners.cpp | 10 - capabilities2_runner_prompt/.clang-format | 64 ---- capabilities2_runner_prompt/CMakeLists.txt | 63 ---- .../prompt_capability_runner.hpp | 44 --- .../prompt_occupancy_runner.hpp | 47 --- .../prompt_plan_runner.hpp | 93 ------ .../prompt_pose_runner.hpp | 46 --- .../prompt_service_runner.hpp | 91 ------ .../prompt_text_runner.hpp | 45 --- capabilities2_runner_prompt/package.xml | 33 --- capabilities2_runner_prompt/plugins.xml | 27 -- .../src/prompt_runners.cpp | 14 - capabilities2_runner_system/CMakeLists.txt | 8 + .../interfaces/CompletionRunner.yaml | 0 .../interfaces/InputMultiplexAllRunner.yaml | 0 .../interfaces/InputMultiplexAnyRunner.yaml | 0 capabilities2_runner_system/package.xml | 28 ++ .../providers/CompletionRunner.yaml | 0 .../providers/InputMultiplexAllRunner.yaml | 0 .../providers/InputMultiplexAnyRunner.yaml | 0 system_capabilities/CMakeLists.txt | 16 - system_capabilities/LICENSE | 17 -- system_capabilities/package.xml | 48 --- 76 files changed, 96 insertions(+), 3260 deletions(-) delete mode 100644 capabilities2_launch/capabilities2_launch/__init__.py delete mode 100644 capabilities2_launch/capabilities2_launch/capabilities2_launch.py delete mode 100644 capabilities2_launch/launch/server.launch.py delete mode 100644 capabilities2_launch/launch_server/__init__.py delete mode 100644 capabilities2_launch/launch_server/launch_process.py delete mode 100644 capabilities2_launch/launch_server/server.py delete mode 100644 capabilities2_launch/package.xml delete mode 100644 capabilities2_launch/resource/capabilities2_launch delete mode 100644 capabilities2_launch/setup.cfg delete mode 100644 capabilities2_launch/setup.py delete mode 100644 capabilities2_launch/test/test_copyright.py delete mode 100644 capabilities2_launch/test/test_flake8.py delete mode 100644 capabilities2_launch/test/test_pep257.py delete mode 100644 capabilities2_launch_proxy/capabilities2_launch_proxy/__init__.py delete mode 100755 capabilities2_launch_proxy/capabilities2_launch_proxy/capabilities_launch_proxy.py delete mode 100644 capabilities2_launch_proxy/package.xml delete mode 100644 capabilities2_launch_proxy/readme.md delete mode 100644 capabilities2_launch_proxy/resource/capabilities2_launch_proxy delete mode 100644 capabilities2_launch_proxy/setup.cfg delete mode 100644 capabilities2_launch_proxy/setup.py delete mode 100644 capabilities2_launch_proxy/test/call_use_launch_runner.py delete mode 100644 capabilities2_runner_audio/.clang-format delete mode 100644 capabilities2_runner_audio/CMakeLists.txt delete mode 100644 capabilities2_runner_audio/include/capabilities2_runner_audio/listen_runner.hpp delete mode 100644 capabilities2_runner_audio/include/capabilities2_runner_audio/speak_runner.hpp delete mode 100644 capabilities2_runner_audio/package.xml delete mode 100644 capabilities2_runner_audio/plugins.xml delete mode 100644 capabilities2_runner_audio/src/audio_runners.cpp delete mode 100644 capabilities2_runner_bt/.clang-format delete mode 100644 capabilities2_runner_bt/CMakeLists.txt delete mode 100644 capabilities2_runner_bt/include/capabilities2_runner_bt/bt_factory_runner.hpp delete mode 100644 capabilities2_runner_bt/include/capabilities2_runner_bt/bt_runner_base.hpp delete mode 100644 capabilities2_runner_bt/package.xml delete mode 100644 capabilities2_runner_bt/plugins.xml delete mode 100644 capabilities2_runner_bt/readme.md delete mode 100644 capabilities2_runner_bt/src/bt_runners.cpp create mode 100644 capabilities2_runner_capabilities/interfaces/CapabilityGetRunner.yaml create mode 100644 capabilities2_runner_capabilities/providers/CapabilityGetRunner.yaml delete mode 100644 capabilities2_runner_fabric/.clang-format delete mode 100644 capabilities2_runner_fabric/CMakeLists.txt delete mode 100644 capabilities2_runner_fabric/include/capabilities2_runner_fabric/set_plan_runner.hpp delete mode 100644 capabilities2_runner_fabric/package.xml delete mode 100644 capabilities2_runner_fabric/plugins.xml delete mode 100644 capabilities2_runner_fabric/src/fabric_runners.cpp delete mode 100644 capabilities2_runner_nav2/.clang-format delete mode 100644 capabilities2_runner_nav2/CMakeLists.txt delete mode 100644 capabilities2_runner_nav2/include/capabilities2_runner_nav2/occupancygrid_runner.hpp delete mode 100644 capabilities2_runner_nav2/include/capabilities2_runner_nav2/robotpose_runner.hpp delete mode 100644 capabilities2_runner_nav2/include/capabilities2_runner_nav2/waypoint_runner.hpp delete mode 100644 capabilities2_runner_nav2/package.xml delete mode 100644 capabilities2_runner_nav2/plugins.xml delete mode 100644 capabilities2_runner_nav2/src/nav2_runners.cpp delete mode 100644 capabilities2_runner_prompt/.clang-format delete mode 100644 capabilities2_runner_prompt/CMakeLists.txt delete mode 100644 capabilities2_runner_prompt/include/capabilities2_runner_prompt/prompt_capability_runner.hpp delete mode 100644 capabilities2_runner_prompt/include/capabilities2_runner_prompt/prompt_occupancy_runner.hpp delete mode 100644 capabilities2_runner_prompt/include/capabilities2_runner_prompt/prompt_plan_runner.hpp delete mode 100644 capabilities2_runner_prompt/include/capabilities2_runner_prompt/prompt_pose_runner.hpp delete mode 100644 capabilities2_runner_prompt/include/capabilities2_runner_prompt/prompt_service_runner.hpp delete mode 100644 capabilities2_runner_prompt/include/capabilities2_runner_prompt/prompt_text_runner.hpp delete mode 100644 capabilities2_runner_prompt/package.xml delete mode 100644 capabilities2_runner_prompt/plugins.xml delete mode 100644 capabilities2_runner_prompt/src/prompt_runners.cpp rename {system_capabilities => capabilities2_runner_system}/interfaces/CompletionRunner.yaml (100%) rename {system_capabilities => capabilities2_runner_system}/interfaces/InputMultiplexAllRunner.yaml (100%) rename {system_capabilities => capabilities2_runner_system}/interfaces/InputMultiplexAnyRunner.yaml (100%) rename {system_capabilities => capabilities2_runner_system}/providers/CompletionRunner.yaml (100%) rename {system_capabilities => capabilities2_runner_system}/providers/InputMultiplexAllRunner.yaml (100%) rename {system_capabilities => capabilities2_runner_system}/providers/InputMultiplexAnyRunner.yaml (100%) delete mode 100644 system_capabilities/CMakeLists.txt delete mode 100644 system_capabilities/LICENSE delete mode 100644 system_capabilities/package.xml diff --git a/capabilities2_launch/capabilities2_launch/__init__.py b/capabilities2_launch/capabilities2_launch/__init__.py deleted file mode 100644 index e69de29..0000000 diff --git a/capabilities2_launch/capabilities2_launch/capabilities2_launch.py b/capabilities2_launch/capabilities2_launch/capabilities2_launch.py deleted file mode 100644 index 854c232..0000000 --- a/capabilities2_launch/capabilities2_launch/capabilities2_launch.py +++ /dev/null @@ -1,146 +0,0 @@ -import os -import signal -import rclpy -from rclpy.node import Node -from capabilities2_msgs.srv import Launch -from multiprocessing.connection import Client - -class LaunchServer(Node): - def __init__(self): - super().__init__('capabilities2_launch_server') - self.address = ('localhost', 6000) - self.client = Client(self.address, authkey=b'capabilities2') - - # Service for starting a launch file - self.start_server = self.create_service( - Launch, - '/capabilities/launch/start', - self.start_request - ) - - # Service for stopping a launch file - self.stop_server = self.create_service( - Launch, - '/capabilities/launch/stop', - self.stop_request - ) - - # Service for stopping a launch file - self.stop_server = self.create_service( - Launch, - '/capabilities/launch/status', - self.status_request - ) - - self.get_logger().info('Capabilities2 LaunchServer is ready.') - - def start_request(self, request, response): - package_name = request.package_name - launch_file_name = request.launch_file_name - - self.get_logger().info(f'[{package_name}/{launch_file_name}] received start request') - - message_outgoing = {} - message_outgoing["command"] = "start" - message_outgoing["package"] = package_name - message_outgoing["launch_file"] = launch_file_name - - self.get_logger().info(f'[{package_name}/{launch_file_name}] sending start request to Launch Server') - - self.client.send(message_outgoing) - - self.get_logger().info(f'[{package_name}/{launch_file_name}] waiting for response from Launch Server') - - message_incoming = self.client.recv() - response_content = message_incoming["status"] - - self.get_logger().info(f'[{package_name}/{launch_file_name}] received response : {response_content}') - - response.status = response_content - - return response - - def stop_request(self, request, response): - package_name = request.package_name - launch_file_name = request.launch_file_name - - self.get_logger().info(f'[{package_name}/{launch_file_name}] received stop request') - - message_outgoing = {} - message_outgoing["command"] = "stop" - message_outgoing["package"] = package_name - message_outgoing["launch_file"] = launch_file_name - - self.get_logger().info(f'[{package_name}/{launch_file_name}] sending stop request to Launch Server') - - self.client.send(message_outgoing) - - self.get_logger().info(f'[{package_name}/{launch_file_name}] waiting for response from Launch Server') - - message_incoming = self.client.recv() - response_content = message_incoming["status"] - - self.get_logger().info(f'[{package_name}/{launch_file_name}] received response : {response_content}') - - response.status = response_content - - return response - - - def status_request(self, request, response): - package_name = request.package_name - launch_file_name = request.launch_file_name - - self.get_logger().info(f'[{package_name}/{launch_file_name}] received status request') - - message_outgoing = {} - message_outgoing["command"] = "status" - message_outgoing["package"] = package_name - message_outgoing["launch_file"] = launch_file_name - - self.get_logger().info(f'[{package_name}/{launch_file_name}] sending status request to Launch Server') - - self.client.send(message_outgoing) - - self.get_logger().info(f'[{package_name}/{launch_file_name}] waiting for response from Launch Server') - - message_incoming = self.client.recv() - response_content = message_incoming["status"] - - self.get_logger().info(f'[{package_name}/{launch_file_name}] received response : {response_content}') - - response.status = response_content - - return response - - def shutdown(self): - - self.get_logger().info(f'Shutting down LaunchFileServer...') - - message_outgoing = {} - message_outgoing["command"] = "exit" - message_outgoing["package"] = "" - message_outgoing["launch_file"] = "" - - self.get_logger().info(f'[sending shutdown request to Launch Server') - - self.client.send(message_outgoing) - - -def main(args=None): - rclpy.init(args=args) - - # Create the LaunchServer node - launch_server = LaunchServer() - - # Keep the node running - try: - rclpy.spin(launch_server) - except KeyboardInterrupt: - launch_server.shutdown() - finally: - rclpy.shutdown() - - -if __name__ == '__main__': - main() \ No newline at end of file diff --git a/capabilities2_launch/launch/server.launch.py b/capabilities2_launch/launch/server.launch.py deleted file mode 100644 index 8ce3c51..0000000 --- a/capabilities2_launch/launch/server.launch.py +++ /dev/null @@ -1,37 +0,0 @@ -''' -capabilities2_server launch file -''' - -import os -from launch import LaunchDescription -from launch.actions import ExecuteProcess -from launch_ros.actions import Node -from launch.substitutions import FindExecutable -from ament_index_python.packages import get_package_share_directory - - -def generate_launch_description(): - """Generate launch description for capabilities2 server - - Returns: - LaunchDescription: The launch description for capabilities2 server - """ - - filePath = os.path.join(get_package_share_directory('capabilities2_launch'), 'launch_server', 'server.py') - - # create launch proxy node - launch_interface = Node( - package='capabilities2_launch', - executable='capabilities2_launch', - name='capabilities2_launch', - output='screen', - arguments=['--ros-args', '--log-level', 'info'] - ) - - server_process = ExecuteProcess(cmd=[[FindExecutable(name='python3'), ' ', filePath]], shell=True, output='screen') - - # return - return LaunchDescription([ - launch_interface, - server_process - ]) diff --git a/capabilities2_launch/launch_server/__init__.py b/capabilities2_launch/launch_server/__init__.py deleted file mode 100644 index e69de29..0000000 diff --git a/capabilities2_launch/launch_server/launch_process.py b/capabilities2_launch/launch_server/launch_process.py deleted file mode 100644 index 04af439..0000000 --- a/capabilities2_launch/launch_server/launch_process.py +++ /dev/null @@ -1,140 +0,0 @@ -from multiprocessing import Process -import launch -from ros2launch.api.api import parse_launch_arguments -from ros2launch.api import get_share_file_path_from_package -from ament_index_python.packages import PackageNotFoundError -from ros2launch.api import MultipleLaunchFilesError - -class LaunchProcess(Process): - - def __init__( - self, - package_name, - launch_file_name, - launch_file_arguments=[], - option_extensions={}, - noninteractive=True, - debug=False, - args=None - ): - """ - LaunchProcess objects represent ros2 launch files that need to be started is run in a separate process - - :param: package_name name of the package where launch file resides - :param: launch_file_name name of the launch file - :param: launch_file_arguments launch file arguments as a list - :param: option_extensions option extensions as a dictionary - :param: noninteractive flag for non-interactiveness - :param: debug flag for enabling debug info - :param: args additional arguments - """ - super().__init__() - self.package_name = package_name - self.launch_file_name = launch_file_name - self.launch_file_arguments = launch_file_arguments - self.noninteractive = noninteractive - self.debug = debug - self.option_extensions=option_extensions - self.args = args - self.path = None - - try: - self.path = get_share_file_path_from_package( - package_name=self.package_name, - file_name=self.launch_file_name) - - except PackageNotFoundError as exc: - raise RuntimeError(f"Package '{self.package_name}' not found: {exc}") - except (FileNotFoundError, MultipleLaunchFilesError) as exc: - raise RuntimeError(str(exc)) - - def run(self): - print(f"Launch file {self.launch_file_name} from package {self.package_name} started with pid [{self.pid}") - - launch_service = launch.LaunchService( - argv=self.launch_file_arguments, - noninteractive=self.noninteractive, - debug=self.debug) - - parsed_launch_arguments = parse_launch_arguments(self.launch_file_arguments) - - launch_description = launch.LaunchDescription([ - launch.actions.IncludeLaunchDescription( - launch.launch_description_sources.AnyLaunchDescriptionSource( - self.path - ), - launch_arguments=parsed_launch_arguments, - ), - ]) - - for name in sorted(self.option_extensions.keys()): - result = self.option_extensions[name].prelaunch(launch_description, self.args) - launch_description = result[0] - - launch_service.include_launch_description(launch_description) - - launch_service.run() - - def stop(self): - print(f"Stopping Launch file {self.launch_file_name} from package {self.package_name}") - self.kill() - -class LaunchManager: - def __init__(self): - self.processes = {} - - def start(self, package_name, launch_file_name): - name = package_name + "/" + launch_file_name - - if name not in self.processes: - try: - self.processes[name] = LaunchProcess(package_name=package_name, launch_file_name=launch_file_name) - self.processes[name].start() - except: - return {"status": "error occured"} - else: - return {"status": "successfuly started"} - else: - return {"status": "already started. ignoring"} - - def status(self, package_name, launch_file_name): - name = package_name + "/" + launch_file_name - - if name in self.processes: - if self.processes[name].is_alive(): - return {"status": "running"} - else: - return {"status": "failed"} - else: - return {"status": "stopped"} - - - def stop(self, package_name, launch_file_name): - name = package_name + "/" + launch_file_name - - if name in self.processes: - try: - self.processes[name].stop() - self.processes[name].join() - except: - return {"status": "error occured"} - else: - return {"status": "successfuly stopped"} - else: - return {"status": "already stopped. ignoring"} - - -if __name__ == "__main__": - launch_process = LaunchProcess( - package_name="nav_stack", - launch_file_name="system.launch.py" - ) - - launch_process.start() # Start the process - - import time - time.sleep(10) # Let the process run for 10 seconds - - launch_process.stop() # Signal the process to stop - launch_process.join() # Wait for the process to terminate - print("Launch process has exited.") \ No newline at end of file diff --git a/capabilities2_launch/launch_server/server.py b/capabilities2_launch/launch_server/server.py deleted file mode 100644 index beb0251..0000000 --- a/capabilities2_launch/launch_server/server.py +++ /dev/null @@ -1,65 +0,0 @@ -from launch_server.launch_process import LaunchManager -from multiprocessing.connection import Listener - -class LaunchServer: - def __init__(self): - self.address = ('localhost', 6000) - self.listener = Listener(self.address, authkey=b'capabilities2') - self.manager = LaunchManager() - - def initialize(self): - self.connection = self.listener.accept() - print("[Launch Server] connection Accepted from {self.listener.last_accepted}") - - def run(self): - while True: - # message would be a dictionary with the format of {"command": , "package": , "launch_file": } - message_incoming = self.connection.recv() - - command = message_incoming["command"] - - if ((command=="start") or (command=="stop") or (command=="status")): - package_name = message_incoming["package"] - launch_file_name = message_incoming["launch_file"] - else: - package_name = "" - launch_file_name = "" - - if (command=="start"): - print("[Launch Server] start request for {package_name}/{launch_file_name}") - status = self.manager.start(package_name=package_name, launch_file_name=launch_file_name) - result = status["status"] - - print("[Launch Server] start response of {package_name}/{launch_file_name}: {result}") - - elif (command=="stop"): - print("[Launch Server] stop request for {package_name}/{launch_file_name}") - status = self.manager.stop(package_name=package_name, launch_file_name=launch_file_name) - result = status["status"] - - print("[Launch Server] stop response of {package_name}/{launch_file_name}: {result}") - - elif (command=="status"): - print("[Launch Server] status request for {package_name}/{launch_file_name}") - status = self.manager.status(package_name=package_name, launch_file_name=launch_file_name) - result = status["status"] - - print("[Launch Server] status response of {package_name}/{launch_file_name}: {result}") - - elif (command=="exit"): - break - - else: - print("[Launch Server] does not support command of type : {command}") - break - - self.connection.send(status) - - self.listener.close - - -if __name__ == "__main__": - - server = LaunchServer() - server.initialize() - server.run() \ No newline at end of file diff --git a/capabilities2_launch/package.xml b/capabilities2_launch/package.xml deleted file mode 100644 index 8b0c6fa..0000000 --- a/capabilities2_launch/package.xml +++ /dev/null @@ -1,23 +0,0 @@ - - - - capabilities2_launch - 0.0.0 - TODO: Package description - kalana - TODO: License declaration - - rclcpp - capabilities2_msgs - - ros2launch - - ament_copyright - ament_flake8 - ament_pep257 - python3-pytest - - - ament_python - - diff --git a/capabilities2_launch/resource/capabilities2_launch b/capabilities2_launch/resource/capabilities2_launch deleted file mode 100644 index e69de29..0000000 diff --git a/capabilities2_launch/setup.cfg b/capabilities2_launch/setup.cfg deleted file mode 100644 index 9844c9c..0000000 --- a/capabilities2_launch/setup.cfg +++ /dev/null @@ -1,4 +0,0 @@ -[develop] -script_dir=$base/lib/capabilities2_launch -[install] -install_scripts=$base/lib/capabilities2_launch diff --git a/capabilities2_launch/setup.py b/capabilities2_launch/setup.py deleted file mode 100644 index 856147b..0000000 --- a/capabilities2_launch/setup.py +++ /dev/null @@ -1,29 +0,0 @@ -from setuptools import find_packages, setup -import os -from glob import glob - -package_name = 'capabilities2_launch' - -setup( - name=package_name, - version='0.1.0', - packages=find_packages(exclude=['test']), - data_files=[ - ('share/ament_index/resource_index/packages', ['resource/' + package_name]), - ('share/' + package_name, ['package.xml']), - (os.path.join('share', package_name, 'launch'), glob(os.path.join('launch', '*launch.[pxy][yma]*'))), - (os.path.join('share', package_name, 'launch_server'), glob(os.path.join('launch_server', '*.py'))), - ], - install_requires=['setuptools'], - zip_safe=True, - maintainer='kalana', - maintainer_email='kalanaratnayake95@gmail.com', - description='A ROS 2 package to manage starting and stopping ROS 2 launch files through services.', - license='TODO: License declaration', - tests_require=['pytest'], - entry_points={ - 'console_scripts': [ - 'capabilities2_launch = capabilities2_launch.capabilities2_launch:main', - ], - }, -) diff --git a/capabilities2_launch/test/test_copyright.py b/capabilities2_launch/test/test_copyright.py deleted file mode 100644 index 97a3919..0000000 --- a/capabilities2_launch/test/test_copyright.py +++ /dev/null @@ -1,25 +0,0 @@ -# Copyright 2015 Open Source Robotics Foundation, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -from ament_copyright.main import main -import pytest - - -# Remove the `skip` decorator once the source file(s) have a copyright header -@pytest.mark.skip(reason='No copyright header has been placed in the generated source file.') -@pytest.mark.copyright -@pytest.mark.linter -def test_copyright(): - rc = main(argv=['.', 'test']) - assert rc == 0, 'Found errors' diff --git a/capabilities2_launch/test/test_flake8.py b/capabilities2_launch/test/test_flake8.py deleted file mode 100644 index 27ee107..0000000 --- a/capabilities2_launch/test/test_flake8.py +++ /dev/null @@ -1,25 +0,0 @@ -# Copyright 2017 Open Source Robotics Foundation, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -from ament_flake8.main import main_with_errors -import pytest - - -@pytest.mark.flake8 -@pytest.mark.linter -def test_flake8(): - rc, errors = main_with_errors(argv=[]) - assert rc == 0, \ - 'Found %d code style errors / warnings:\n' % len(errors) + \ - '\n'.join(errors) diff --git a/capabilities2_launch/test/test_pep257.py b/capabilities2_launch/test/test_pep257.py deleted file mode 100644 index b234a38..0000000 --- a/capabilities2_launch/test/test_pep257.py +++ /dev/null @@ -1,23 +0,0 @@ -# Copyright 2015 Open Source Robotics Foundation, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -from ament_pep257.main import main -import pytest - - -@pytest.mark.linter -@pytest.mark.pep257 -def test_pep257(): - rc = main(argv=['.', 'test']) - assert rc == 0, 'Found code style errors / warnings' diff --git a/capabilities2_launch_proxy/capabilities2_launch_proxy/__init__.py b/capabilities2_launch_proxy/capabilities2_launch_proxy/__init__.py deleted file mode 100644 index e69de29..0000000 diff --git a/capabilities2_launch_proxy/capabilities2_launch_proxy/capabilities_launch_proxy.py b/capabilities2_launch_proxy/capabilities2_launch_proxy/capabilities_launch_proxy.py deleted file mode 100755 index b1773c0..0000000 --- a/capabilities2_launch_proxy/capabilities2_launch_proxy/capabilities_launch_proxy.py +++ /dev/null @@ -1,280 +0,0 @@ -''' -capabilities launch proxy server - -implements a launch server responding to messages to launch and shutdown launch files -use in conjunction with capabilities2_server to launch capabilities - -acts like ros2 launch command but from an action interface -''' - -import os -import threading -from typing import Set -from typing import Text -from typing import Optional -import rclpy -from rclpy.executors import MultiThreadedExecutor -from rclpy.executors import ExternalShutdownException -import rclpy.logging -from rclpy.node import Node -from rclpy.action import ActionServer -from rclpy.action import CancelResponse -from rclpy.action.server import ServerGoalHandle -from launch import LaunchService -from launch import LaunchContext -from launch.event import Event -from launch.events.process import ShutdownProcess -from launch.event_handler import EventHandler -from launch.event_handlers import OnProcessStart -from launch.actions import ExecuteProcess -from launch.actions import EmitEvent -from launch.actions import RegisterEventHandler -from launch.launch_description_sources import AnyLaunchDescriptionSource -# from launch.some_entities_type import SomeEntitiesType -from capabilities2_msgs.action import Launch - - -class CancelLaunchGoalEvent(Event): - """ - Launch goal cancel event - - used when a launch goal is canceled - the result should be that the launch description associated with a goal - is shutdown in the running LaunchService - other goals should not be affected - """ - - name = 'launch.event.CancelLaunchGoal' - - def __init__(self, *, goal_handle: ServerGoalHandle) -> None: - """ - Create a LaunchGoalCancelEvent - """ - self.goal_handle = goal_handle - - -class CancelEventHandler(EventHandler): - """ - Cancel event handler - - handle cancel launch goal events - cancels a launch goal if it matches the goal handle passed in - """ - - def __init__(self, goal_handle: ServerGoalHandle, pids: Set[int]): - super().__init__(matcher=lambda event: isinstance(event, CancelLaunchGoalEvent)) - self.goal_handle = goal_handle - self.pids = pids - - def handle(self, event: Event, context: LaunchContext): - """ - handle event - """ - - super().handle(event, context) - - # check if event is a cancel launch goal event - if not isinstance(event, CancelLaunchGoalEvent): - return None - - # if the goals match then cancel - if event.goal_handle == self.goal_handle: - return EmitEvent(event=ShutdownProcess( - process_matcher=lambda action: action.process_details['pid'] in self.pids - )) - - return None - - -class CapabilitiesLaunchProxy(Node): - """ - Capabilities Launch proxy server - """ - - def __init__(self, node_name='capabilities_launch_proxy'): - # super class init - super().__init__(node_name) - - # active files set - self.active_launch_files: Set[Text] = set() - self.launch_set_lock = threading.Lock() - - # create launch action server - self.launch_sub = ActionServer( - self, - Launch, - '~/launch', - handle_accepted_callback=self.handle_accepted_cb, - execute_callback=self.execute_cb, - cancel_callback=self.cancel_cb - ) - - # create launch service - self.launch_service = LaunchService() - - # log start - self.get_logger().info('capabilities launch proxy started') - - # service interface - def get_active_launch_files_cb(self): - """ - get active launch files - """ - return self.active_launch_files - - # action interface - def handle_accepted_cb(self, goal_handle: ServerGoalHandle) -> None: - """ - handle accepted callback - """ - # start execution and detach - threading.Thread(target=goal_handle.execute).start() - - # execute callback is main launch feature - def execute_cb(self, goal_handle: ServerGoalHandle) -> Launch.Result: - """ - launch execute callback - """ - - # check if file exists - if not os.path.isfile(goal_handle.request.launch_file_path): - # file does not exist - self.get_logger().error("file does not exist: '{}'".format( - goal_handle.request.launch_file_path)) - - # abort goal - goal_handle.abort() - return Launch.Result() - - with self.launch_set_lock: - # launch context already exists guard - if goal_handle.request.launch_file_path in self.active_launch_files: - self.get_logger().error("launch already exists for source '{}'".format( - goal_handle.request.launch_file_path)) - - goal_handle.abort() - return Launch.Result() - - # add context to active files - self.active_launch_files.add(goal_handle.request.launch_file_path) - - # get launch description from file - description = AnyLaunchDescriptionSource( - goal_handle.request.launch_file_path).get_launch_description(self.launch_service.context) - - # set up process id get event handler - description_process_ids: Set[int] = set() - - # go through all actions and collect all processes (mostly nodes) in the description - for e in description.entities: - # check the type of entity is an execute process action - if isinstance(e, ExecuteProcess): - # register event handler for process start event - # on process start store the pid - description.add_action( - RegisterEventHandler(OnProcessStart( - target_action=e, - on_start=lambda event, context: description_process_ids.add( - event.pid) - )) - ) - - # add shutdown event to launch description - # add shutdown event handler to launch description - # this uses the cancel goal event handler and cancel goal event - description.add_action(RegisterEventHandler(CancelEventHandler( - goal_handle, - description_process_ids - ))) - - # add to launch service - self.launch_service.include_launch_description(description) - - # bind request to this thread - self.get_logger().info('launching: {}'.format( - goal_handle.request.launch_file_path - )) - - # sleep rate for holding this action open - rate = self.create_rate(1.0) - - # loop while not canceled - while rclpy.ok(): - # if cancelled - if goal_handle.is_cancel_requested: - self.get_logger().warn("launch canceled: '{}'".format( - goal_handle.request.launch_file_path - )) - - # shutdown context - self.launch_service.emit_event( - CancelLaunchGoalEvent(goal_handle=goal_handle)) - - # delete context from active files - with self.launch_set_lock: - self.active_launch_files.remove( - goal_handle.request.launch_file_path) - - goal_handle.canceled() - return Launch.Result() - - # send event feedback - feedback = Launch.Feedback() - feedback.event.type = 'launched' - goal_handle.publish_feedback(feedback) - - # spin indefinitely (sleep loop this thread) - rate.sleep() - - goal_handle.succeed() - return Launch.Result() - - def cancel_cb(self, goal_handle: ServerGoalHandle) -> CancelResponse: - """ - accept all cancellations - """ - return CancelResponse.ACCEPT - - -# main function -def main(): - """ - main function - """ - - try: - # init node - rclpy.init() - - # instantiate the capabilities launch server - capabilities_launch_proxy = CapabilitiesLaunchProxy() - - # spin node in new thread - executor = MultiThreadedExecutor() - executor.add_node(capabilities_launch_proxy) - - executor_thread = threading.Thread(target=executor.spin) - executor_thread.start() - - # run the launch service - capabilities_launch_proxy.get_logger().info('running LaunchService') - capabilities_launch_proxy.launch_service.run( - shutdown_when_idle=False) - - # cancel the launch services - capabilities_launch_proxy.launch_service.shutdown() - - executor.shutdown() - executor_thread.join() - capabilities_launch_proxy.destroy_node() - - # rclpy.shutdown() - - except ExternalShutdownException: - pass - - -# main -if __name__ == '__main__': - # run the proxy - main() diff --git a/capabilities2_launch_proxy/package.xml b/capabilities2_launch_proxy/package.xml deleted file mode 100644 index ab70338..0000000 --- a/capabilities2_launch_proxy/package.xml +++ /dev/null @@ -1,19 +0,0 @@ - - - - capabilities2_launch_proxy - 0.0.1 - ros2 launch proxy to support launching capabilities similar to ros1 capabilities - mik-p - - MIT - - rclpy - launch - std_msgs - capabilities2_msgs - - - ament_python - - diff --git a/capabilities2_launch_proxy/readme.md b/capabilities2_launch_proxy/readme.md deleted file mode 100644 index e749a41..0000000 --- a/capabilities2_launch_proxy/readme.md +++ /dev/null @@ -1,46 +0,0 @@ -# capabilities2_launch_proxy - -Provides an Action API proxy to the ros2 launch framework. Implements features that are only available in python since the `launch` API is not available in C++. - -Contains the essential features to implement the ros1 [`capabilities`](https://wiki.ros.org/capabilities) package launch functionality in ros2. - -Use in conjunction with `capabilities2_server` package, to provide a full capabilities server. - -## how it works - -Implements three main functions: - -| Function | Description | -| --- | --- | -| `launch` | Run a launch file requested a runtime via a network request | -| `shutdown` | shutdown a launch file that has been started | -| `events` | send capability events during operation | - -The lifecylce of these functions are typically handled by the capabilities server but could be used for other things. - -## Use without capabilities2 server - -The proxy provides an action called `~/launch`. The `goal` is a file path to launch from. The feedback provides events about the launch status. - -### Add to a launch file - -```python -from launch import LaunchDescription -from launch_ros.actions import Node - -def generate_launch_description(): - return LaunchDescription([ - # create launch proxy node - Node( - package='capabilities2_launch_proxy', - executable='capabilities_launch_proxy', - name='capabilities_launch_proxy' - ) - ]) -``` - -### Run standalone - -```bash -ros2 run capabilities2_launch_proxy capabilities_launch_proxy -``` diff --git a/capabilities2_launch_proxy/resource/capabilities2_launch_proxy b/capabilities2_launch_proxy/resource/capabilities2_launch_proxy deleted file mode 100644 index e69de29..0000000 diff --git a/capabilities2_launch_proxy/setup.cfg b/capabilities2_launch_proxy/setup.cfg deleted file mode 100644 index d3f4af5..0000000 --- a/capabilities2_launch_proxy/setup.cfg +++ /dev/null @@ -1,4 +0,0 @@ -[develop] -script_dir=$base/lib/capabilities2_launch_proxy -[install] -install_scripts=$base/lib/capabilities2_launch_proxy diff --git a/capabilities2_launch_proxy/setup.py b/capabilities2_launch_proxy/setup.py deleted file mode 100644 index 1707673..0000000 --- a/capabilities2_launch_proxy/setup.py +++ /dev/null @@ -1,26 +0,0 @@ -from setuptools import find_packages, setup - -package_name = 'capabilities2_launch_proxy' - -setup( - name=package_name, - version='0.0.1', - packages=find_packages(exclude=['test']), - data_files=[ - ('share/ament_index/resource_index/packages', - ['resource/' + package_name]), - ('share/' + package_name, ['package.xml']), - ], - install_requires=['setuptools'], - zip_safe=True, - maintainer='mik-p', - maintainer_email='mppritchard3@hotmail.com', - description='ros2 launch proxy to support launching capabilities similar to ros1 capabilities', - license='MIT', - tests_require=['pytest'], - entry_points={ - 'console_scripts': [ - 'capabilities_launch_proxy = capabilities2_launch_proxy.capabilities_launch_proxy:main', - ], - }, -) diff --git a/capabilities2_launch_proxy/test/call_use_launch_runner.py b/capabilities2_launch_proxy/test/call_use_launch_runner.py deleted file mode 100644 index f8d3f9c..0000000 --- a/capabilities2_launch_proxy/test/call_use_launch_runner.py +++ /dev/null @@ -1,94 +0,0 @@ -''' test call cap services ''' - -from bondpy import bondpy -import rclpy -from capabilities2_msgs.srv import EstablishBond -from capabilities2_msgs.srv import GetRunningCapabilities -from capabilities2_msgs.srv import UseCapability - - -def test_get_running_capabilities(n): - # get running capabilities - client = n.create_client( - GetRunningCapabilities, - '/capabilities/get_running_capabilities' - ) - - # wait for service - client.wait_for_service() - - # send request - request = GetRunningCapabilities.Request() - future = client.call_async(request) - rclpy.spin_until_future_complete(n, future) - - # print result - for s in future.result().running_capabilities: - print(s) - - -# main -if __name__ == '__main__': - - rclpy.init() - - node = rclpy.create_node('test_call_cap_srvs') - - # do tests - # test_get_interfaces_srv(node) - # test_get_semantic_interfaces_srv(node) - # test_get_providers_srv(node) - # test_get_capability_specs_srv(node) - - print("test use capability") - # get a bond - bond_cli = node.create_client( - EstablishBond, - '/capabilities/establish_bond' - ) - - # wait for service - bond_cli.wait_for_service() - - # send request - request = EstablishBond.Request() - future = bond_cli.call_async(request) - rclpy.spin_until_future_complete(node, future) - - # print result - print(future.result()) - # keep bond id - bond_id = future.result().bond_id - - # create a use capability request - use_client = node.create_client( - UseCapability, - '/capabilities/use_capability' - ) - - # wait for service - use_client.wait_for_service() - - # send request - request = UseCapability.Request() - request.capability = 'std_capabilities/empty' - request.preferred_provider = 'std_capabilities/empty' - request.bond_id = future.result().bond_id - future = use_client.call_async(request) - rclpy.spin_until_future_complete(node, future) - - # print result - print(future.result()) - - # get running capabilities - test_get_running_capabilities(node) - - # keep bond alive - bond = bondpy.Bond(node, "/capabilities/bonds", bond_id) - bond.start() - rclpy.spin(node) - - node.destroy_node() - rclpy.shutdown() - - exit(0) diff --git a/capabilities2_runner_audio/.clang-format b/capabilities2_runner_audio/.clang-format deleted file mode 100644 index d36804f..0000000 --- a/capabilities2_runner_audio/.clang-format +++ /dev/null @@ -1,64 +0,0 @@ - -BasedOnStyle: Google -AccessModifierOffset: -2 -ConstructorInitializerIndentWidth: 2 -AlignEscapedNewlinesLeft: false -AlignTrailingComments: true -AllowAllParametersOfDeclarationOnNextLine: false -AllowShortIfStatementsOnASingleLine: false -AllowShortLoopsOnASingleLine: false -AllowShortFunctionsOnASingleLine: None -AlwaysBreakTemplateDeclarations: true -AlwaysBreakBeforeMultilineStrings: false -BreakBeforeBinaryOperators: false -BreakBeforeTernaryOperators: false -BreakConstructorInitializersBeforeComma: true -BinPackParameters: true -ColumnLimit: 120 -ConstructorInitializerAllOnOneLineOrOnePerLine: true -DerivePointerBinding: false -PointerBindsToType: true -ExperimentalAutoDetectBinPacking: false -IndentCaseLabels: true -MaxEmptyLinesToKeep: 1 -NamespaceIndentation: None -ObjCSpaceBeforeProtocolList: true -PenaltyBreakBeforeFirstCallParameter: 19 -PenaltyBreakComment: 60 -PenaltyBreakString: 1 -PenaltyBreakFirstLessLess: 1000 -PenaltyExcessCharacter: 1000 -PenaltyReturnTypeOnItsOwnLine: 90 -SpacesBeforeTrailingComments: 2 -Cpp11BracedListStyle: false -Standard: Auto -IndentWidth: 2 -TabWidth: 2 -UseTab: Never -IndentFunctionDeclarationAfterType: false -SpacesInParentheses: false -SpacesInAngles: false -SpaceInEmptyParentheses: false -SpacesInCStyleCastParentheses: false -SpaceAfterControlStatementKeyword: true -SpaceBeforeAssignmentOperators: true -ContinuationIndentWidth: 4 -SortIncludes: false -SpaceAfterCStyleCast: false - -# Configure each individual brace in BraceWrapping -BreakBeforeBraces: Custom - -# Control of individual brace wrapping cases -BraceWrapping: { - AfterClass: 'true' - AfterControlStatement: 'true' - AfterEnum : 'true' - AfterFunction : 'true' - AfterNamespace : 'true' - AfterStruct : 'true' - AfterUnion : 'true' - BeforeCatch : 'true' - BeforeElse : 'true' - IndentBraces : 'false' -} diff --git a/capabilities2_runner_audio/CMakeLists.txt b/capabilities2_runner_audio/CMakeLists.txt deleted file mode 100644 index c03dd00..0000000 --- a/capabilities2_runner_audio/CMakeLists.txt +++ /dev/null @@ -1,64 +0,0 @@ -cmake_minimum_required(VERSION 3.8) -project(capabilities2_runner_audio) - -# Default to C++17 -if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 17) -endif() - -if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic) -endif() - -# find dependencies -find_package(ament_cmake REQUIRED) -find_package(rclcpp REQUIRED) -find_package(rclcpp_action REQUIRED) -find_package(pluginlib REQUIRED) -find_package(hri_audio_msgs REQUIRED) -find_package(capabilities2_msgs REQUIRED) -find_package(capabilities2_runner REQUIRED) -find_package(capabilities2_utils REQUIRED) -find_package(event_logger REQUIRED) -find_package(event_logger_msgs REQUIRED) -find_package(tinyxml2_vendor REQUIRED) -find_package(TinyXML2 REQUIRED) # provided by tinyxml2 upstream, or tinyxml2_vendor - -include_directories( - include -) - -add_library(${PROJECT_NAME} SHARED - src/audio_runners.cpp -) - -ament_target_dependencies(${PROJECT_NAME} - rclcpp - rclcpp_action - pluginlib - hri_audio_msgs - capabilities2_msgs - capabilities2_runner - capabilities2_utils - event_logger - event_logger_msgs - TinyXML2 -) - -pluginlib_export_plugin_description_file(capabilities2_runner plugins.xml) - -install(TARGETS ${PROJECT_NAME} - EXPORT ${PROJECT_NAME} - ARCHIVE DESTINATION lib - LIBRARY DESTINATION lib - RUNTIME DESTINATION bin -) - -install(DIRECTORY include/ - DESTINATION include -) - -ament_export_include_directories(include) -ament_export_libraries(${PROJECT_NAME}) - -ament_package() diff --git a/capabilities2_runner_audio/include/capabilities2_runner_audio/listen_runner.hpp b/capabilities2_runner_audio/include/capabilities2_runner_audio/listen_runner.hpp deleted file mode 100644 index ad86511..0000000 --- a/capabilities2_runner_audio/include/capabilities2_runner_audio/listen_runner.hpp +++ /dev/null @@ -1,96 +0,0 @@ -#pragma once - -#include - -#include -#include -#include - -#include - -#include - -namespace capabilities2_runner -{ - -/** - * @brief action runner base class - * - * Class to run speech_to_text action based capability - */ -class ListenerRunner : public ActionRunner -{ -public: - ListenerRunner() : ActionRunner() - { - } - - /** - * @brief Starter function for starting the action runner - * - * @param node shared pointer to the capabilities node. Allows to use ros node related functionalities - * @param run_config runner configuration loaded from the yaml file - */ - virtual void start(rclcpp::Node::SharedPtr node, const runner_opts& run_config) override - { - init_action(node, run_config, "speech_to_text"); - } - -protected: - /** - * @brief This generate goal function overrides the generate_goal() function from ActionRunner() - * - * @param parameters XMLElement that contains parameters in the format '' - * @return ActionT::Goal the generated goal - */ - virtual hri_audio_msgs::action::SpeechToText::Goal generate_goal(tinyxml2::XMLElement* parameters, int id) override - { - hri_audio_msgs::action::SpeechToText::Goal goal_msg; - - goal_msg.header.stamp = node_->get_clock()->now(); - - return goal_msg; - } - - /** - * @brief This generate feedback function overrides the generate_feedback() function from ActionRunner() - * - * @param msg feedback message from the action server - * @return std::string of feedback information - */ - virtual std::string - generate_feedback(const typename hri_audio_msgs::action::SpeechToText::Feedback::ConstSharedPtr msg) override - { - std::string feedback = ""; - return feedback; - } - - /** - * @brief Update on_success event parameters with new data if avaible. - * - * This function is used to inject new data into the XMLElement containing - * parameters related to the on_success trigger event - * - * A pattern needs to be implemented in the derived class - * - * @param parameters pointer to the XMLElement containing parameters - * @return pointer to the XMLElement containing updated parameters - */ - virtual std::string update_on_success(std::string& parameters) - { - tinyxml2::XMLElement* element = convert_to_xml(parameters); - - // Create the Pose element as a child of the existing parameters element - tinyxml2::XMLElement* textElement = element->GetDocument()->NewElement("Text"); - element->InsertEndChild(textElement); - textElement->SetText(result_->stt_text.c_str()); - - // Return the updated parameters element with Pose added as string - std::string result = convert_to_string(element); - - return result; - }; -}; - -} // namespace capabilities2_runner diff --git a/capabilities2_runner_audio/include/capabilities2_runner_audio/speak_runner.hpp b/capabilities2_runner_audio/include/capabilities2_runner_audio/speak_runner.hpp deleted file mode 100644 index bd2d623..0000000 --- a/capabilities2_runner_audio/include/capabilities2_runner_audio/speak_runner.hpp +++ /dev/null @@ -1,75 +0,0 @@ -#pragma once - -#include - -#include -#include -#include - -#include - -#include - -namespace capabilities2_runner -{ - -/** - * @brief action runner base class - * - * Class to run text_to_speech action based capability - */ -class SpeakerRunner : public ActionRunner -{ -public: - SpeakerRunner() : ActionRunner() - { - } - - /** - * @brief Starter function for starting the action runner - * - * @param node shared pointer to the capabilities node. Allows to use ros node related functionalities - * @param run_config runner configuration loaded from the yaml file - */ - virtual void start(rclcpp::Node::SharedPtr node, const runner_opts& run_config) override - { - init_action(node, run_config, "text_to_speech"); - } - -protected: - /** - * @brief This generate goal function overrides the generate_goal() function from ActionRunner() - * - * @param parameters XMLElement that contains parameters in the format '' - * @return ActionT::Goal the generated goal - */ - virtual hri_audio_msgs::action::TextToSpeech::Goal generate_goal(tinyxml2::XMLElement* parameters, int id) override - { - const char** text; - parameters->QueryStringAttribute("text", text); - std::string tts_text(*text); - - hri_audio_msgs::action::TextToSpeech::Goal goal_msg; - - goal_msg.header.stamp = node_->get_clock()->now(); - goal_msg.tts_text = tts_text; - - return goal_msg; - } - - /** - * @brief This generate feedback function overrides the generate_feedback() function from ActionRunner() - * - * @param msg feedback message from the action server - * @return std::string of feedback information - */ - virtual std::string - generate_feedback(const typename hri_audio_msgs::action::TextToSpeech::Feedback::ConstSharedPtr msg) override - { - std::string feedback = ""; - return feedback; - } -}; - -} // namespace capabilities2_runner \ No newline at end of file diff --git a/capabilities2_runner_audio/package.xml b/capabilities2_runner_audio/package.xml deleted file mode 100644 index edccb72..0000000 --- a/capabilities2_runner_audio/package.xml +++ /dev/null @@ -1,38 +0,0 @@ - - - - capabilities2_runner_audio - 0.0.0 - TODO: Package description - - Kalana Ratnayake - Kalana Ratnayake - - Kalana Ratnayake - - MIT - - ament_cmake - - rclcpp - rclcpp_action - pluginlib - std_msgs - hri_audio_msgs - capabilities2_msgs - capabilities2_runner - capabilities2_utils - event_logger - event_logger_msgs - tinyxml2_vendor - - - ros2launch - - ament_lint_auto - ament_lint_common - - - ament_cmake - - diff --git a/capabilities2_runner_audio/plugins.xml b/capabilities2_runner_audio/plugins.xml deleted file mode 100644 index a1355d0..0000000 --- a/capabilities2_runner_audio/plugins.xml +++ /dev/null @@ -1,12 +0,0 @@ - - - - A plugin that provide speech to text capability - - - - - A plugin that provide text to speech capability - - - \ No newline at end of file diff --git a/capabilities2_runner_audio/src/audio_runners.cpp b/capabilities2_runner_audio/src/audio_runners.cpp deleted file mode 100644 index 5fb11f4..0000000 --- a/capabilities2_runner_audio/src/audio_runners.cpp +++ /dev/null @@ -1,8 +0,0 @@ -#include -#include -#include -#include - -// register runner plugins -PLUGINLIB_EXPORT_CLASS(capabilities2_runner::ListenerRunner, capabilities2_runner::RunnerBase) -PLUGINLIB_EXPORT_CLASS(capabilities2_runner::SpeakerRunner, capabilities2_runner::RunnerBase) diff --git a/capabilities2_runner_bt/.clang-format b/capabilities2_runner_bt/.clang-format deleted file mode 100644 index d36804f..0000000 --- a/capabilities2_runner_bt/.clang-format +++ /dev/null @@ -1,64 +0,0 @@ - -BasedOnStyle: Google -AccessModifierOffset: -2 -ConstructorInitializerIndentWidth: 2 -AlignEscapedNewlinesLeft: false -AlignTrailingComments: true -AllowAllParametersOfDeclarationOnNextLine: false -AllowShortIfStatementsOnASingleLine: false -AllowShortLoopsOnASingleLine: false -AllowShortFunctionsOnASingleLine: None -AlwaysBreakTemplateDeclarations: true -AlwaysBreakBeforeMultilineStrings: false -BreakBeforeBinaryOperators: false -BreakBeforeTernaryOperators: false -BreakConstructorInitializersBeforeComma: true -BinPackParameters: true -ColumnLimit: 120 -ConstructorInitializerAllOnOneLineOrOnePerLine: true -DerivePointerBinding: false -PointerBindsToType: true -ExperimentalAutoDetectBinPacking: false -IndentCaseLabels: true -MaxEmptyLinesToKeep: 1 -NamespaceIndentation: None -ObjCSpaceBeforeProtocolList: true -PenaltyBreakBeforeFirstCallParameter: 19 -PenaltyBreakComment: 60 -PenaltyBreakString: 1 -PenaltyBreakFirstLessLess: 1000 -PenaltyExcessCharacter: 1000 -PenaltyReturnTypeOnItsOwnLine: 90 -SpacesBeforeTrailingComments: 2 -Cpp11BracedListStyle: false -Standard: Auto -IndentWidth: 2 -TabWidth: 2 -UseTab: Never -IndentFunctionDeclarationAfterType: false -SpacesInParentheses: false -SpacesInAngles: false -SpaceInEmptyParentheses: false -SpacesInCStyleCastParentheses: false -SpaceAfterControlStatementKeyword: true -SpaceBeforeAssignmentOperators: true -ContinuationIndentWidth: 4 -SortIncludes: false -SpaceAfterCStyleCast: false - -# Configure each individual brace in BraceWrapping -BreakBeforeBraces: Custom - -# Control of individual brace wrapping cases -BraceWrapping: { - AfterClass: 'true' - AfterControlStatement: 'true' - AfterEnum : 'true' - AfterFunction : 'true' - AfterNamespace : 'true' - AfterStruct : 'true' - AfterUnion : 'true' - BeforeCatch : 'true' - BeforeElse : 'true' - IndentBraces : 'false' -} diff --git a/capabilities2_runner_bt/CMakeLists.txt b/capabilities2_runner_bt/CMakeLists.txt deleted file mode 100644 index 25bace3..0000000 --- a/capabilities2_runner_bt/CMakeLists.txt +++ /dev/null @@ -1,62 +0,0 @@ -cmake_minimum_required(VERSION 3.10) -project(capabilities2_runner_bt) - -# Default to C++17 -if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 17) -endif() - -if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic) -endif() - -find_package(ament_cmake REQUIRED) -find_package(rclcpp REQUIRED) -find_package(rclcpp_action REQUIRED) -find_package(pluginlib REQUIRED) -find_package(capabilities2_msgs REQUIRED) -find_package(capabilities2_runner REQUIRED) -find_package(capabilities2_utils REQUIRED) -find_package(event_logger REQUIRED) -find_package(event_logger_msgs REQUIRED) -find_package(behaviortree_cpp REQUIRED) -find_package(tinyxml2_vendor REQUIRED) -find_package(TinyXML2 REQUIRED) # provided by tinyxml2 upstream, or tinyxml2_vendor - -include_directories( - include -) - -add_library(${PROJECT_NAME} SHARED - src/bt_runners.cpp -) - -ament_target_dependencies(${PROJECT_NAME} - rclcpp - rclcpp_action - pluginlib - capabilities2_msgs - capabilities2_runner - capabilities2_utils - event_logger - event_logger_msgs - behaviortree_cpp - TinyXML2 -) - -pluginlib_export_plugin_description_file(capabilities2_runner plugins.xml) - -install(TARGETS ${PROJECT_NAME} - EXPORT ${PROJECT_NAME} - ARCHIVE DESTINATION lib - LIBRARY DESTINATION lib - RUNTIME DESTINATION bin -) - -install(DIRECTORY include/ - DESTINATION include -) - -ament_export_include_directories(include) -ament_export_libraries(${PROJECT_NAME}) -ament_package() diff --git a/capabilities2_runner_bt/include/capabilities2_runner_bt/bt_factory_runner.hpp b/capabilities2_runner_bt/include/capabilities2_runner_bt/bt_factory_runner.hpp deleted file mode 100644 index 846f1a8..0000000 --- a/capabilities2_runner_bt/include/capabilities2_runner_bt/bt_factory_runner.hpp +++ /dev/null @@ -1,87 +0,0 @@ -#pragma once - -#include -#include -#include - -namespace capabilities2_runner -{ - -/** - * @brief base runner class for a behaviortree factory - * - * The runner implements a behaviour defined by a behaviourtree - * and executes it in a behaviortree - * - */ -class BTRunnerBase : public RunnerBase, public BT::BehaviorTreeFactory -{ -public: - BTRunnerBase() : RunnerBase(), BT::BehaviorTreeFactory() - { - } - - virtual void start(rclcpp::Node::SharedPtr node, const runner_opts& run_config) - { - // init the runner base - init_base(node, run_config); - - // register (bt)actions from ROS plugins - try - { - this->registerFromROSPlugins(); - } - catch (const std::exception& e) // TODO: add more specific exception - { - throw runner_exception(e.what()); - } - } - - virtual void stop() - { - // reset the tree (this destroys the nodes) - tree_.reset(); - } - -protected: - /** - * @brief trigger the behaviour factory with the input data - * - * @param parameters - * @return std::optional)>> - */ - virtual void trigger(const std::string& parameters) override - { - tinyxml2::XMLElement* parameters_xml = convert_to_xml(parameters); - - // if parameters are not provided then cannot proceed - if (!parameters_xml) - throw runner_exception("cannot trigger action without parameters"); - - // create the tree (ptr) - tree_ = std::make_shared(this->createTreeFromText(parameters_xml->GetText())); - - // return the tick function - // // the caller can call this function to tick the tree - // std::function)> result_callback = - // [this](std::shared_ptr result) { - // // tick the tree - // BT::NodeStatus status = tree_->tickWhileRunning(); - - // // fill the result - // if (status == BT::NodeStatus::SUCCESS) - // result->SetText("OK"); - // else - // result->SetText("FAIL"); - - // return; - // }; - - // return result_callback; - } - - // the tree - std::shared_ptr tree_; -}; - -} // namespace capabilities2_runner diff --git a/capabilities2_runner_bt/include/capabilities2_runner_bt/bt_runner_base.hpp b/capabilities2_runner_bt/include/capabilities2_runner_bt/bt_runner_base.hpp deleted file mode 100644 index 8bf4dea..0000000 --- a/capabilities2_runner_bt/include/capabilities2_runner_bt/bt_runner_base.hpp +++ /dev/null @@ -1,109 +0,0 @@ -#pragma once - -/** - * @file bt_runner_base.hpp - * @brief This file is heavily inspired by the nav2_behavior_tree::BtActionNode implementation - * as it performs almost the same functionality - * - * The nav2_behavior_tree::BtActionNode is part of navigation2 - * which is licensed under the Apache 2.0 license. see the following - * license file for more details: - * - */ - -// Copyright (c) 2018 Intel Corporation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include -#include - -namespace capabilities2_runner -{ - -/** - * @brief base class for a behaviortree action - * - * This class is heavily inspired by the nav2_behavior_tree::BtActionNode - * - * The action implements a action runner and an action node to combine the two - * domain definitions of 'action' - * - * Through this class, an action can be run in a behaviortree which implements a ROS action - * - * @tparam ActionT - */ -template -class BTRunnerBase : public ActionRunner, public BT::ActionNodeBase -{ -public: - BTRunnerBase() : ActionRunner(), BT::ActionNodeBase() - { - } - - // init pattern for bt and runner - /** - * @brief initializer function for initializing the action runner in place of constructor due to plugin semantics - * - * TODO: this is getting pretty messy - * - * @param node - * @param run_config - * @param action_name - * @param on_started - * @param on_terminated - * @param on_stopped - * @param bt_tag_name - * @param conf - */ - virtual void init_bt(rclcpp::Node::SharedPtr node, const runner_opts& run_config, const std::string& action_name, - const std::string& bt_tag_name, const BT::NodeConfiguration& conf, - std::function on_started = nullptr, - std::function on_terminated = nullptr, - std::function on_stopped = nullptr) - { - ActionRunner::init_action(node, run_config, action_name, on_started, on_terminated, on_stopped); - - // FIXME: no init in action base - // BT::ActionNodeBase::init(bt_tag_name, conf); - } - - // bt methods that need to be overridden - BT::NodeStatus tick() override - { - // TODO: run the action client? - } - - void halt() override - { - // cancel the action client if it is running - // can be implemented with the stop virtual method - // from action runner - ActionRunner::stop(); - } - - // the action runner methods that need to be overridden - // these can be overridden when this class is inherited and the action runner - // action template is resolved - // - // see runner_base.hpp for more details - // - // virtual void start(rclcpp::Node::SharedPtr node, const runner_opts& run_config, - // std::function on_started = nullptr, - // std::function on_terminated = nullptr, - // std::function on_stopped = nullptr) override - // - // virtual void trigger(std::shared_ptr parameters = nullptr) override -}; - -} // namespace capabilities2_runner diff --git a/capabilities2_runner_bt/package.xml b/capabilities2_runner_bt/package.xml deleted file mode 100644 index 07668d9..0000000 --- a/capabilities2_runner_bt/package.xml +++ /dev/null @@ -1,36 +0,0 @@ - - - capabilities2_runner_bt - 0.0.1 - - Package for behaviour tree based capabilities2 runners - - - Michael Pritchard - mik-p - - Michael Pritchard - - MIT - - ament_cmake - - rclcpp - rclcpp_action - pluginlib - std_msgs - capabilities2_msgs - capabilities2_runner - capabilities2_utils - event_logger - event_logger_msgs - tinyxml2_vendor - behaviortree_cpp - - - uuid - - - ament_cmake - - diff --git a/capabilities2_runner_bt/plugins.xml b/capabilities2_runner_bt/plugins.xml deleted file mode 100644 index 0763f3e..0000000 --- a/capabilities2_runner_bt/plugins.xml +++ /dev/null @@ -1,6 +0,0 @@ - - - - - - diff --git a/capabilities2_runner_bt/readme.md b/capabilities2_runner_bt/readme.md deleted file mode 100644 index 16d8543..0000000 --- a/capabilities2_runner_bt/readme.md +++ /dev/null @@ -1,35 +0,0 @@ -# capabilities2_runner_bt - -Behavior tree runners for [capabilities2](../readme.md). This package provides a runner for the capabilities2 package that uses behavior trees to combine and execute composite runners in the capabilities framework. - -## Runners - -| Runner | Description | -| ------ | ----------- | -| `BTRunnerBase` | A base class for behavior tree runners. This class is used to implement the behavior tree runner for the capabilities2 package. It inherits from the [`ActionRunner`](../capabilities2_runner/readme.md) to join ROS action and behavior tree action concepts. | -| `BTFactoryRunner` | Load a behavior tree and run it as a capabilities2 runner (this just means that it runs in the capabilities2_server node). | - -### Provider Example - -The following example demonstrates how to use the `BTFactoryRunner` to load a behavior tree from a file and run it as a capabilities2 runner. - -```yaml -name: bt_ask_help -spec_version: "1.1" -spec_type: provider -implements: std_capabilities/ask_help -runner: capabilities2_runner_bt/BTFactoryRunner - -# the tree to load -definition: | - - - - - - - - - - -``` diff --git a/capabilities2_runner_bt/src/bt_runners.cpp b/capabilities2_runner_bt/src/bt_runners.cpp deleted file mode 100644 index 2f1582c..0000000 --- a/capabilities2_runner_bt/src/bt_runners.cpp +++ /dev/null @@ -1,5 +0,0 @@ -#include -#include - - -// PLUGINLIB_EXPORT_CLASS(capabilities2_runner::BTRunnerBase, capabilities2_runner::RunnerBase) diff --git a/capabilities2_runner_capabilities/CMakeLists.txt b/capabilities2_runner_capabilities/CMakeLists.txt index 6dc43ee..6aa29c9 100644 --- a/capabilities2_runner_capabilities/CMakeLists.txt +++ b/capabilities2_runner_capabilities/CMakeLists.txt @@ -55,6 +55,14 @@ install(DIRECTORY include/ DESTINATION include ) +install(DIRECTORY interfaces + DESTINATION share/${PROJECT_NAME} +) + +install(DIRECTORY providers + DESTINATION share/${PROJECT_NAME} +) + ament_export_include_directories(include) ament_export_libraries(${PROJECT_NAME}) diff --git a/capabilities2_runner_capabilities/interfaces/CapabilityGetRunner.yaml b/capabilities2_runner_capabilities/interfaces/CapabilityGetRunner.yaml new file mode 100644 index 0000000..79535fc --- /dev/null +++ b/capabilities2_runner_capabilities/interfaces/CapabilityGetRunner.yaml @@ -0,0 +1,34 @@ +%YAML 1.1 +--- +name: CapabilityGetRunner +spec_version: 1.1 +spec_type: interface +description: "This capability depends on the capabilities2 server functionalities and allows an decision making authority such as an + LLM extract capabilities of the robot. The capability can be trigged with an command such as + ''. This is included in + the default starting plan and the decision making authority such as an LLM does not need to include this in any generated + plans. The details for the Capaiblities are stored in a format as follows, + ' + + + name: Navigation + dependencies: + - MapServer + - PathPlanner + + + + + name: ObjectDetection + dependencies: + - Camera + - ImageProcessor + + + ' " + +interface: + services: + "/capabilities/get_capability_specs": + type: "capabilities2_msgs::srv::GetCapabilitySpecs" + description: "This capability focuses on extracting robot's capabilities and transfering them to decision making authority." \ No newline at end of file diff --git a/capabilities2_runner_capabilities/package.xml b/capabilities2_runner_capabilities/package.xml index c97cfee..53bff7d 100644 --- a/capabilities2_runner_capabilities/package.xml +++ b/capabilities2_runner_capabilities/package.xml @@ -30,5 +30,14 @@ ament_cmake + + + + interfaces/CapabilityGetRunner.yaml + + + + providers/CapabilityGetRunner.yaml + diff --git a/capabilities2_runner_capabilities/providers/CapabilityGetRunner.yaml b/capabilities2_runner_capabilities/providers/CapabilityGetRunner.yaml new file mode 100644 index 0000000..7202ee7 --- /dev/null +++ b/capabilities2_runner_capabilities/providers/CapabilityGetRunner.yaml @@ -0,0 +1,9 @@ +# the empty provider +%YAML 1.1 +--- +name: CapabilityGetRunner +spec_type: provider +spec_version: 1.1 +description: "The capability provider for extracting capabilities from server. This is used to identify the capabilities of the robot" +implements: std_capabilities/CapabilityGetRunner +runner: capabilities2_runner::CapabilityGetRunner \ No newline at end of file diff --git a/capabilities2_runner_fabric/.clang-format b/capabilities2_runner_fabric/.clang-format deleted file mode 100644 index d36804f..0000000 --- a/capabilities2_runner_fabric/.clang-format +++ /dev/null @@ -1,64 +0,0 @@ - -BasedOnStyle: Google -AccessModifierOffset: -2 -ConstructorInitializerIndentWidth: 2 -AlignEscapedNewlinesLeft: false -AlignTrailingComments: true -AllowAllParametersOfDeclarationOnNextLine: false -AllowShortIfStatementsOnASingleLine: false -AllowShortLoopsOnASingleLine: false -AllowShortFunctionsOnASingleLine: None -AlwaysBreakTemplateDeclarations: true -AlwaysBreakBeforeMultilineStrings: false -BreakBeforeBinaryOperators: false -BreakBeforeTernaryOperators: false -BreakConstructorInitializersBeforeComma: true -BinPackParameters: true -ColumnLimit: 120 -ConstructorInitializerAllOnOneLineOrOnePerLine: true -DerivePointerBinding: false -PointerBindsToType: true -ExperimentalAutoDetectBinPacking: false -IndentCaseLabels: true -MaxEmptyLinesToKeep: 1 -NamespaceIndentation: None -ObjCSpaceBeforeProtocolList: true -PenaltyBreakBeforeFirstCallParameter: 19 -PenaltyBreakComment: 60 -PenaltyBreakString: 1 -PenaltyBreakFirstLessLess: 1000 -PenaltyExcessCharacter: 1000 -PenaltyReturnTypeOnItsOwnLine: 90 -SpacesBeforeTrailingComments: 2 -Cpp11BracedListStyle: false -Standard: Auto -IndentWidth: 2 -TabWidth: 2 -UseTab: Never -IndentFunctionDeclarationAfterType: false -SpacesInParentheses: false -SpacesInAngles: false -SpaceInEmptyParentheses: false -SpacesInCStyleCastParentheses: false -SpaceAfterControlStatementKeyword: true -SpaceBeforeAssignmentOperators: true -ContinuationIndentWidth: 4 -SortIncludes: false -SpaceAfterCStyleCast: false - -# Configure each individual brace in BraceWrapping -BreakBeforeBraces: Custom - -# Control of individual brace wrapping cases -BraceWrapping: { - AfterClass: 'true' - AfterControlStatement: 'true' - AfterEnum : 'true' - AfterFunction : 'true' - AfterNamespace : 'true' - AfterStruct : 'true' - AfterUnion : 'true' - BeforeCatch : 'true' - BeforeElse : 'true' - IndentBraces : 'false' -} diff --git a/capabilities2_runner_fabric/CMakeLists.txt b/capabilities2_runner_fabric/CMakeLists.txt deleted file mode 100644 index b813db7..0000000 --- a/capabilities2_runner_fabric/CMakeLists.txt +++ /dev/null @@ -1,63 +0,0 @@ -cmake_minimum_required(VERSION 3.8) -project(capabilities2_runner_fabric) - -# Default to C++17 -if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 17) -endif() - -if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic) -endif() - -find_package(ament_cmake REQUIRED) -find_package(rclcpp REQUIRED) -find_package(rclcpp_action REQUIRED) -find_package(pluginlib REQUIRED) -find_package(fabric_msgs REQUIRED) -find_package(capabilities2_msgs REQUIRED) -find_package(capabilities2_runner REQUIRED) -find_package(capabilities2_utils REQUIRED) -find_package(event_logger REQUIRED) -find_package(event_logger_msgs REQUIRED) -find_package(tinyxml2_vendor REQUIRED) -find_package(TinyXML2 REQUIRED) # provided by tinyxml2 upstream, or tinyxml2_vendor - -include_directories( - include -) - -add_library(${PROJECT_NAME} SHARED - src/fabric_runners.cpp -) - -ament_target_dependencies(${PROJECT_NAME} - rclcpp - rclcpp_action - pluginlib - fabric_msgs - capabilities2_msgs - capabilities2_runner - capabilities2_utils - event_logger - event_logger_msgs - TinyXML2 -) - -pluginlib_export_plugin_description_file(capabilities2_runner plugins.xml) - -install(TARGETS ${PROJECT_NAME} - EXPORT ${PROJECT_NAME} - ARCHIVE DESTINATION lib - LIBRARY DESTINATION lib - RUNTIME DESTINATION bin -) - -install(DIRECTORY include/ - DESTINATION include -) - -ament_export_include_directories(include) -ament_export_libraries(${PROJECT_NAME}) - -ament_package() diff --git a/capabilities2_runner_fabric/include/capabilities2_runner_fabric/set_plan_runner.hpp b/capabilities2_runner_fabric/include/capabilities2_runner_fabric/set_plan_runner.hpp deleted file mode 100644 index 20eec05..0000000 --- a/capabilities2_runner_fabric/include/capabilities2_runner_fabric/set_plan_runner.hpp +++ /dev/null @@ -1,61 +0,0 @@ -#pragma once - -#include - -#include -#include -#include - -#include -#include - -namespace capabilities2_runner -{ - -/** - * @brief Executor runner class - * - * Class to run capabilities2 executor action based capability - * - */ -class FabricSetPlanRunner : public ServiceRunner -{ -public: - FabricSetPlanRunner() : ServiceRunner() - { - } - - /** - * @brief Starter function for starting the action runner - * - * @param node shared pointer to the capabilities node. Allows to use ros node related functionalities - * @param run_config runner configuration loaded from the yaml file - */ - virtual void start(rclcpp::Node::SharedPtr node, const runner_opts& run_config) override - { - init_service(node, run_config, "/fabric/set_plan"); - } - -protected: - /** - * @brief This generate goal function overrides the generate_goal() function from ActionRunner() - * @param parameters XMLElement that contains parameters in the format - * @return ActionT::Goal the generated goal - */ - virtual fabric_msgs::srv::SetFabricPlan::Request generate_request(tinyxml2::XMLElement* parameters, int id) override - { - tinyxml2::XMLElement* planElement = parameters->FirstChildElement("ReceievdPlan"); - - fabric_msgs::srv::SetFabricPlan::Request request; - - // Check if the element was found and has text content - if (planElement && planElement->GetText()) - { - request.plan = std::string(planElement->GetText()); - } - - return request; - } -}; - -} // namespace capabilities2_runner diff --git a/capabilities2_runner_fabric/package.xml b/capabilities2_runner_fabric/package.xml deleted file mode 100644 index d2b1197..0000000 --- a/capabilities2_runner_fabric/package.xml +++ /dev/null @@ -1,34 +0,0 @@ - - - - capabilities2_runner_fabric - 0.0.0 - TODO: Package description - - - Kalana Ratnayake - Kalana Ratnayake - - Kalana Ratnayake - - TODO: License declaration - - ament_cmake - - ament_lint_auto - ament_lint_common - - rclcpp - rclcpp_action - pluginlib - std_msgs - fabric_msgs - capabilities2_runner - event_logger - event_logger_msgs - tinyxml2_vendor - - - ament_cmake - - diff --git a/capabilities2_runner_fabric/plugins.xml b/capabilities2_runner_fabric/plugins.xml deleted file mode 100644 index 07e8a06..0000000 --- a/capabilities2_runner_fabric/plugins.xml +++ /dev/null @@ -1,7 +0,0 @@ - - - - A plugin that sets a new Fabric plan to the Fabric - - - diff --git a/capabilities2_runner_fabric/src/fabric_runners.cpp b/capabilities2_runner_fabric/src/fabric_runners.cpp deleted file mode 100644 index 703c1e1..0000000 --- a/capabilities2_runner_fabric/src/fabric_runners.cpp +++ /dev/null @@ -1,6 +0,0 @@ -#include -#include -#include - -// register runner plugins -PLUGINLIB_EXPORT_CLASS(capabilities2_runner::FabricSetPlanRunner, capabilities2_runner::RunnerBase) diff --git a/capabilities2_runner_nav2/.clang-format b/capabilities2_runner_nav2/.clang-format deleted file mode 100644 index d36804f..0000000 --- a/capabilities2_runner_nav2/.clang-format +++ /dev/null @@ -1,64 +0,0 @@ - -BasedOnStyle: Google -AccessModifierOffset: -2 -ConstructorInitializerIndentWidth: 2 -AlignEscapedNewlinesLeft: false -AlignTrailingComments: true -AllowAllParametersOfDeclarationOnNextLine: false -AllowShortIfStatementsOnASingleLine: false -AllowShortLoopsOnASingleLine: false -AllowShortFunctionsOnASingleLine: None -AlwaysBreakTemplateDeclarations: true -AlwaysBreakBeforeMultilineStrings: false -BreakBeforeBinaryOperators: false -BreakBeforeTernaryOperators: false -BreakConstructorInitializersBeforeComma: true -BinPackParameters: true -ColumnLimit: 120 -ConstructorInitializerAllOnOneLineOrOnePerLine: true -DerivePointerBinding: false -PointerBindsToType: true -ExperimentalAutoDetectBinPacking: false -IndentCaseLabels: true -MaxEmptyLinesToKeep: 1 -NamespaceIndentation: None -ObjCSpaceBeforeProtocolList: true -PenaltyBreakBeforeFirstCallParameter: 19 -PenaltyBreakComment: 60 -PenaltyBreakString: 1 -PenaltyBreakFirstLessLess: 1000 -PenaltyExcessCharacter: 1000 -PenaltyReturnTypeOnItsOwnLine: 90 -SpacesBeforeTrailingComments: 2 -Cpp11BracedListStyle: false -Standard: Auto -IndentWidth: 2 -TabWidth: 2 -UseTab: Never -IndentFunctionDeclarationAfterType: false -SpacesInParentheses: false -SpacesInAngles: false -SpaceInEmptyParentheses: false -SpacesInCStyleCastParentheses: false -SpaceAfterControlStatementKeyword: true -SpaceBeforeAssignmentOperators: true -ContinuationIndentWidth: 4 -SortIncludes: false -SpaceAfterCStyleCast: false - -# Configure each individual brace in BraceWrapping -BreakBeforeBraces: Custom - -# Control of individual brace wrapping cases -BraceWrapping: { - AfterClass: 'true' - AfterControlStatement: 'true' - AfterEnum : 'true' - AfterFunction : 'true' - AfterNamespace : 'true' - AfterStruct : 'true' - AfterUnion : 'true' - BeforeCatch : 'true' - BeforeElse : 'true' - IndentBraces : 'false' -} diff --git a/capabilities2_runner_nav2/CMakeLists.txt b/capabilities2_runner_nav2/CMakeLists.txt deleted file mode 100644 index 01483a7..0000000 --- a/capabilities2_runner_nav2/CMakeLists.txt +++ /dev/null @@ -1,69 +0,0 @@ -cmake_minimum_required(VERSION 3.10) -project(capabilities2_runner_nav2) - -# Default to C++17 -if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 17) -endif() - -if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic) -endif() - -find_package(ament_cmake REQUIRED) -find_package(rclcpp REQUIRED) -find_package(rclcpp_action REQUIRED) -find_package(pluginlib REQUIRED) -find_package(nav2_msgs REQUIRED) -find_package(tf2 REQUIRED) -find_package(tf2_ros REQUIRED) -find_package(geometry_msgs REQUIRED) -find_package(capabilities2_msgs REQUIRED) -find_package(capabilities2_runner REQUIRED) -find_package(capabilities2_utils REQUIRED) -find_package(event_logger REQUIRED) -find_package(event_logger_msgs REQUIRED) -find_package(tinyxml2_vendor REQUIRED) -find_package(TinyXML2 REQUIRED) # provided by tinyxml2 upstream, or tinyxml2_vendor - -include_directories( - include -) - -add_library(${PROJECT_NAME} SHARED - src/nav2_runners.cpp -) - -ament_target_dependencies(${PROJECT_NAME} - rclcpp - rclcpp_action - pluginlib - nav2_msgs - tf2 - tf2_ros - geometry_msgs - capabilities2_msgs - capabilities2_runner - capabilities2_utils - event_logger - event_logger_msgs - TinyXML2 -) - -pluginlib_export_plugin_description_file(capabilities2_runner plugins.xml) - -install(TARGETS ${PROJECT_NAME} - EXPORT ${PROJECT_NAME} - ARCHIVE DESTINATION lib - LIBRARY DESTINATION lib - RUNTIME DESTINATION bin -) - -install(DIRECTORY include/ - DESTINATION include -) - -ament_export_include_directories(include) -ament_export_libraries(${PROJECT_NAME}) - -ament_package() diff --git a/capabilities2_runner_nav2/include/capabilities2_runner_nav2/occupancygrid_runner.hpp b/capabilities2_runner_nav2/include/capabilities2_runner_nav2/occupancygrid_runner.hpp deleted file mode 100644 index f979f28..0000000 --- a/capabilities2_runner_nav2/include/capabilities2_runner_nav2/occupancygrid_runner.hpp +++ /dev/null @@ -1,132 +0,0 @@ -#pragma once - -#include - -#include -#include - -#include - -namespace capabilities2_runner -{ - -/** - * @brief odometry runner class - * - * Capability Class to grab occupancy grid data - * - */ -class OccupancyGridRunner : public TopicRunner -{ -public: - OccupancyGridRunner() : TopicRunner() - { - } - - /** - * @brief Starter function for starting the subscription runner - * - * @param node shared pointer to the capabilities node. Allows to use ros node related functionalities - * @param run_config runner configuration loaded from the yaml file - */ - virtual void start(rclcpp::Node::SharedPtr node, const runner_opts& run_config) override - { - init_subscriber(node, run_config, "/map"); - } - -protected: - /** - * @brief Update on_success event parameters with new data from an OccupancyGrid message if avaible. - * - * This function is used to inject new data into the XMLElement containing - * parameters related to the on_success trigger event - * - -
- -
- - - - - - - - 0 100 -1 50 25 75 0 0 100 50 -
- * - * @param parameters pointer to the XMLElement containing parameters - * @return pointer to the XMLElement containing updated parameters - */ - virtual std::string update_on_success(std::string& parameters) - { - tinyxml2::XMLElement* element = convert_to_xml(parameters); - - // Create the OccupancyGrid element as a child of the existing parameters element - tinyxml2::XMLElement* occupancyGridElement = element->GetDocument()->NewElement("OccupancyGrid"); - element->InsertEndChild(occupancyGridElement); - - // Header element with attributes - tinyxml2::XMLElement* headerElement = element->GetDocument()->NewElement("header"); - headerElement->SetAttribute("frame_id", latest_message_->header.frame_id.c_str()); - - tinyxml2::XMLElement* stampElement = element->GetDocument()->NewElement("stamp"); - stampElement->SetAttribute("secs", latest_message_->header.stamp.sec); - stampElement->SetAttribute("nsecs", latest_message_->header.stamp.nanosec); - headerElement->InsertEndChild(stampElement); - - occupancyGridElement->InsertEndChild(headerElement); - - // Info element with attributes - tinyxml2::XMLElement* infoElement = element->GetDocument()->NewElement("info"); - infoElement->SetAttribute("resolution", latest_message_->info.resolution); - infoElement->SetAttribute("width", latest_message_->info.width); - infoElement->SetAttribute("height", latest_message_->info.height); - - // Origin element with position and orientation attributes - tinyxml2::XMLElement* originElement = element->GetDocument()->NewElement("origin"); - - tinyxml2::XMLElement* positionElement = element->GetDocument()->NewElement("position"); - positionElement->SetAttribute("x", latest_message_->info.origin.position.x); - positionElement->SetAttribute("y", latest_message_->info.origin.position.y); - positionElement->SetAttribute("z", latest_message_->info.origin.position.z); - originElement->InsertEndChild(positionElement); - - tinyxml2::XMLElement* orientationElement = element->GetDocument()->NewElement("orientation"); - orientationElement->SetAttribute("x", latest_message_->info.origin.orientation.x); - orientationElement->SetAttribute("y", latest_message_->info.origin.orientation.y); - orientationElement->SetAttribute("z", latest_message_->info.origin.orientation.z); - orientationElement->SetAttribute("w", latest_message_->info.origin.orientation.w); - originElement->InsertEndChild(orientationElement); - - infoElement->InsertEndChild(originElement); - - // Map load time with attributes - tinyxml2::XMLElement* mapLoadTimeElement = element->GetDocument()->NewElement("map_load_time"); - mapLoadTimeElement->SetAttribute("secs", latest_message_->info.map_load_time.sec); - mapLoadTimeElement->SetAttribute("nsecs", latest_message_->info.map_load_time.nanosec); - infoElement->InsertEndChild(mapLoadTimeElement); - - occupancyGridElement->InsertEndChild(infoElement); - - // Data element for occupancy data (converted to a string) - tinyxml2::XMLElement* dataElement = element->GetDocument()->NewElement("data"); - - std::string data_str; - for (size_t i = 0; i < latest_message_->data.size(); i++) - { - data_str += std::to_string(latest_message_->data[i]) + " "; - } - dataElement->SetText(data_str.c_str()); - - occupancyGridElement->InsertEndChild(dataElement); - - // Return the updated parameters element with OccupancyGrid added - std::string result = convert_to_string(element); - - // output_("on_success trigger parameter", result); - - return result; - }; -}; -} // namespace capabilities2_runner \ No newline at end of file diff --git a/capabilities2_runner_nav2/include/capabilities2_runner_nav2/robotpose_runner.hpp b/capabilities2_runner_nav2/include/capabilities2_runner_nav2/robotpose_runner.hpp deleted file mode 100644 index 4f7d8bd..0000000 --- a/capabilities2_runner_nav2/include/capabilities2_runner_nav2/robotpose_runner.hpp +++ /dev/null @@ -1,207 +0,0 @@ -#pragma once - -#include - -#include -#include "geometry_msgs/msg/transform_stamped.hpp" - -#include - -#include "tf2/exceptions.h" -#include "tf2_ros/transform_listener.h" -#include "tf2_ros/buffer.h" - -namespace capabilities2_runner -{ - -/** - * @brief odometry runner class - * - * Capability Class to grab odometry data - * - */ -class RobotPoseRunner : public RunnerBase -{ -public: - RobotPoseRunner() : RunnerBase() - { - } - - /** - * @brief Starter function for starting the subscription runner - * - * @param node shared pointer to the capabilities node. Allows to use ros node related functionalities - * @param run_config runner configuration loaded from the yaml file - */ - virtual void start(rclcpp::Node::SharedPtr node, const runner_opts& run_config) override - { - // initialize the runner base by storing node pointer and run config - init_base(node, run_config); - - tf_buffer_ = std::make_unique(node_->get_clock()); - tf_listener_ = std::make_shared(*tf_buffer_); - } - - /** - * @brief Trigger process to be executed. - * - * This method utilizes paramters set via the trigger() function - * - * @param parameters pointer to tinyxml2::XMLElement that contains parameters - */ - virtual void execution(int id) override - { - const char* map; - const char* odom; - const char* robot; - - // if parameters are not provided then cannot proceed - if (!parameters_[id]) - throw runner_exception("cannot grab data without parameters"); - - // trigger the events related to on_started state - if (events[id].on_started.interface != "") - { - event_(EventType::STARTED, id, events[id].on_started.interface, events[id].on_started.provider); - triggerFunction_(events[id].on_started.interface, update_on_started(events[id].on_started.parameters)); - } - - info_("Waiting for Transformation.", id); - - parameters_[id]->QueryStringAttribute("map", &map); - parameters_[id]->QueryStringAttribute("odom", &odom); - parameters_[id]->QueryStringAttribute("robot", &robot); - - // Store frame names in variables that will be used to - // compute transformations - std::string mapFrame(map); - std::string odomFrame(odom); - std::string robotFrame(robot); - - // Try to use map -> robot first - try - { - transform_ = tf_buffer_->lookupTransform(mapFrame, robotFrame, tf2::TimePointZero); - - // trigger the events related to on_success state - if (events[id].on_success.interface != "") - { - event_(EventType::SUCCEEDED, id, events[id].on_success.interface, events[id].on_success.provider); - triggerFunction_(events[id].on_success.interface, update_on_success(events[id].on_success.parameters)); - } - - info_("Transformation received. Thread closing.", id); - return; - } - catch (tf2::TransformException& ex) - { - info_("Could not transform from map to robot: " + std::string(ex.what()), id); - } - - // Fall back to odom -> robot - try - { - transform_ = tf_buffer_->lookupTransform(odomFrame, robotFrame, tf2::TimePointZero); - - // trigger the events related to on_success state - if (events[id].on_success.interface != "") - { - event_(EventType::SUCCEEDED, id, events[id].on_success.interface, events[id].on_success.provider); - triggerFunction_(events[id].on_success.interface, update_on_success(events[id].on_success.parameters)); - } - - info_("Transformation received. Thread closing.", id); - } - catch (tf2::TransformException& ex) - { - info_("Could not transform from odom to robot: " + std::string(ex.what()), id); - - // trigger the events related to on_failure state - if (events[id].on_failure.interface != "") - { - event_(EventType::FAILED, id, events[id].on_failure.interface, events[id].on_failure.provider); - triggerFunction_(events[id].on_failure.interface, update_on_failure(events[id].on_failure.parameters)); - } - - info_("Transformation not received. Thread closing.", id); - } - } - - /** - * @brief stop function to cease functionality and shutdown - * - */ - virtual void stop() override - { - // if the node pointer is empty then throw an error - // this means that the runner was not started and is being used out of order - - if (!node_) - throw runner_exception("cannot stop runner that was not started"); - - // throw an error if the service client is null - // this can happen if the runner is not able to find the action resource - - if (!tf_listener_) - throw runner_exception("cannot stop runner subscriber that was not started"); - - // Trigger on_stopped event if defined - if (events[runner_id].on_stopped.interface != "") - { - event_(EventType::STOPPED, -1, events[runner_id].on_stopped.interface, events[runner_id].on_stopped.provider); - triggerFunction_(events[runner_id].on_stopped.interface, - update_on_stopped(events[runner_id].on_stopped.parameters)); - } - } - -protected: - /** - * @brief Update on_success event parameters with new data if avaible. - * - * This function is used to inject new data into the XMLElement containing - * parameters related to the on_success trigger event - * - - - - - * - * @param parameters pointer to the XMLElement containing parameters - * @return pointer to the XMLElement containing updated parameters - */ - virtual std::string update_on_success(std::string& parameters) - { - tinyxml2::XMLElement* element = convert_to_xml(parameters); - - // Create the Pose element as a child of the existing parameters element - tinyxml2::XMLElement* poseElement = element->GetDocument()->NewElement("Pose"); - element->InsertEndChild(poseElement); - - // Position element with attributes - tinyxml2::XMLElement* positionElement = element->GetDocument()->NewElement("position"); - positionElement->SetAttribute("x", transform_.transform.translation.x); - positionElement->SetAttribute("y", transform_.transform.translation.y); - positionElement->SetAttribute("z", transform_.transform.translation.z); - poseElement->InsertEndChild(positionElement); - - // Orientation element with attributes - tinyxml2::XMLElement* orientationElement = element->GetDocument()->NewElement("orientation"); - orientationElement->SetAttribute("x", transform_.transform.rotation.x); - orientationElement->SetAttribute("y", transform_.transform.rotation.y); - orientationElement->SetAttribute("z", transform_.transform.rotation.z); - orientationElement->SetAttribute("w", transform_.transform.rotation.w); - poseElement->InsertEndChild(orientationElement); - - // Return the updated parameters element with Pose added as string - std::string result = convert_to_string(element); - - // output_("on_success trigger parameter", result); - - return result; - }; - - std::shared_ptr tf_listener_{ nullptr }; - std::unique_ptr tf_buffer_; - geometry_msgs::msg::TransformStamped transform_; -}; -} // namespace capabilities2_runner \ No newline at end of file diff --git a/capabilities2_runner_nav2/include/capabilities2_runner_nav2/waypoint_runner.hpp b/capabilities2_runner_nav2/include/capabilities2_runner_nav2/waypoint_runner.hpp deleted file mode 100644 index bf2ad5c..0000000 --- a/capabilities2_runner_nav2/include/capabilities2_runner_nav2/waypoint_runner.hpp +++ /dev/null @@ -1,97 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include -#include - -#include -#include - -#include - -using namespace std::chrono_literals; - -namespace capabilities2_runner -{ - -/** - * @brief waypoint runner class - * - * Class to run waypointfollower action based capability - * - */ -class WayPointRunner : public ActionRunner -{ -public: - WayPointRunner() : ActionRunner() - { - } - - /** - * @brief Starter function for starting the action runner - * - * @param node shared pointer to the capabilities node. Allows to use ros node related functionalities - * @param run_config runner configuration loaded from the yaml file - */ - virtual void start(rclcpp::Node::SharedPtr node, const runner_opts& run_config) override - { - init_action(node, run_config, "navigate_to_pose"); - } - -protected: - /** - * @brief This generate goal function overrides the generate_goal() function from ActionRunner() - * @param parameters XMLElement that contains parameters in the format - '' - * @return ActionT::Goal the generated goal - */ - virtual nav2_msgs::action::NavigateToPose::Goal generate_goal(tinyxml2::XMLElement* parameters, int id) override - { - parameters->QueryDoubleAttribute("x", &x); - parameters->QueryDoubleAttribute("y", &y); - - info_("goal consist of x: " + std::to_string(x) + " and y: " + std::to_string(y), id); - - nav2_msgs::action::NavigateToPose::Goal goal_msg; - geometry_msgs::msg::PoseStamped pose_msg; - - pose_msg.header.frame_id = "map"; - pose_msg.header.stamp.sec = 0; - pose_msg.header.stamp.nanosec = 0; - - pose_msg.pose.position.x = x; - pose_msg.pose.position.y = y; - pose_msg.pose.position.z = 0.0; - pose_msg.pose.orientation.w = 1.0; // Set default orientation (facing forward) - - goal_msg.pose = pose_msg; - - return goal_msg; - } - - /** - * @brief This generate feedback function overrides the generate_feedback() function from ActionRunner() - * - * @param msg feedback message from the action server - * @return std::string of feedback information - */ - virtual std::string - generate_feedback(const typename nav2_msgs::action::NavigateToPose::Feedback::ConstSharedPtr msg) override - { - // std::string feedback = "x: " + std::to_string(msg->current_pose.pose.position.x) + - // " y: " + std::to_string(msg->current_pose.pose.position.y); - // return feedback; - return ""; - } - -protected: - std::string global_frame_; /**The global frame of the robot*/ - std::string robot_base_frame_; /**The frame of the robot base*/ - - double x, y; /**Coordinate frame parameters*/ -}; - -} // namespace capabilities2_runner diff --git a/capabilities2_runner_nav2/package.xml b/capabilities2_runner_nav2/package.xml deleted file mode 100644 index 7222b62..0000000 --- a/capabilities2_runner_nav2/package.xml +++ /dev/null @@ -1,34 +0,0 @@ - - - capabilities2_runner_nav2 - 0.0.0 - TODO: Package description - - Kalana Ratnayake - Kalana Ratnayake - - Kalana Ratnayake - - MIT - - ament_cmake - - rclcpp - rclcpp_action - pluginlib - std_msgs - nav2_msgs - geometry_msgs - capabilities2_msgs - capabilities2_runner - event_logger - event_logger_msgs - tinyxml2_vendor - - ament_lint_auto - ament_lint_common - - - ament_cmake - - diff --git a/capabilities2_runner_nav2/plugins.xml b/capabilities2_runner_nav2/plugins.xml deleted file mode 100644 index 2c4d4ca..0000000 --- a/capabilities2_runner_nav2/plugins.xml +++ /dev/null @@ -1,17 +0,0 @@ - - - - A plugin that provide occupancy grid map extraction capability - - - - - A plugin that provide robot pose extraction capability - - - - - A plugin that provide nav2 waypoint navigation capability - - - diff --git a/capabilities2_runner_nav2/src/nav2_runners.cpp b/capabilities2_runner_nav2/src/nav2_runners.cpp deleted file mode 100644 index d0ea3f1..0000000 --- a/capabilities2_runner_nav2/src/nav2_runners.cpp +++ /dev/null @@ -1,10 +0,0 @@ -#include -#include -#include -#include -#include - -// register runner plugins -PLUGINLIB_EXPORT_CLASS(capabilities2_runner::WayPointRunner, capabilities2_runner::RunnerBase) -PLUGINLIB_EXPORT_CLASS(capabilities2_runner::RobotPoseRunner, capabilities2_runner::RunnerBase) -PLUGINLIB_EXPORT_CLASS(capabilities2_runner::OccupancyGridRunner, capabilities2_runner::RunnerBase) diff --git a/capabilities2_runner_prompt/.clang-format b/capabilities2_runner_prompt/.clang-format deleted file mode 100644 index d36804f..0000000 --- a/capabilities2_runner_prompt/.clang-format +++ /dev/null @@ -1,64 +0,0 @@ - -BasedOnStyle: Google -AccessModifierOffset: -2 -ConstructorInitializerIndentWidth: 2 -AlignEscapedNewlinesLeft: false -AlignTrailingComments: true -AllowAllParametersOfDeclarationOnNextLine: false -AllowShortIfStatementsOnASingleLine: false -AllowShortLoopsOnASingleLine: false -AllowShortFunctionsOnASingleLine: None -AlwaysBreakTemplateDeclarations: true -AlwaysBreakBeforeMultilineStrings: false -BreakBeforeBinaryOperators: false -BreakBeforeTernaryOperators: false -BreakConstructorInitializersBeforeComma: true -BinPackParameters: true -ColumnLimit: 120 -ConstructorInitializerAllOnOneLineOrOnePerLine: true -DerivePointerBinding: false -PointerBindsToType: true -ExperimentalAutoDetectBinPacking: false -IndentCaseLabels: true -MaxEmptyLinesToKeep: 1 -NamespaceIndentation: None -ObjCSpaceBeforeProtocolList: true -PenaltyBreakBeforeFirstCallParameter: 19 -PenaltyBreakComment: 60 -PenaltyBreakString: 1 -PenaltyBreakFirstLessLess: 1000 -PenaltyExcessCharacter: 1000 -PenaltyReturnTypeOnItsOwnLine: 90 -SpacesBeforeTrailingComments: 2 -Cpp11BracedListStyle: false -Standard: Auto -IndentWidth: 2 -TabWidth: 2 -UseTab: Never -IndentFunctionDeclarationAfterType: false -SpacesInParentheses: false -SpacesInAngles: false -SpaceInEmptyParentheses: false -SpacesInCStyleCastParentheses: false -SpaceAfterControlStatementKeyword: true -SpaceBeforeAssignmentOperators: true -ContinuationIndentWidth: 4 -SortIncludes: false -SpaceAfterCStyleCast: false - -# Configure each individual brace in BraceWrapping -BreakBeforeBraces: Custom - -# Control of individual brace wrapping cases -BraceWrapping: { - AfterClass: 'true' - AfterControlStatement: 'true' - AfterEnum : 'true' - AfterFunction : 'true' - AfterNamespace : 'true' - AfterStruct : 'true' - AfterUnion : 'true' - BeforeCatch : 'true' - BeforeElse : 'true' - IndentBraces : 'false' -} diff --git a/capabilities2_runner_prompt/CMakeLists.txt b/capabilities2_runner_prompt/CMakeLists.txt deleted file mode 100644 index 8df7df5..0000000 --- a/capabilities2_runner_prompt/CMakeLists.txt +++ /dev/null @@ -1,63 +0,0 @@ -cmake_minimum_required(VERSION 3.8) -project(capabilities2_runner_prompt) - -# Default to C++17 -if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 17) -endif() - -if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic) -endif() - -find_package(ament_cmake REQUIRED) -find_package(rclcpp REQUIRED) -find_package(rclcpp_action REQUIRED) -find_package(pluginlib REQUIRED) -find_package(prompt_msgs REQUIRED) -find_package(capabilities2_msgs REQUIRED) -find_package(capabilities2_runner REQUIRED) -find_package(capabilities2_utils REQUIRED) -find_package(event_logger REQUIRED) -find_package(event_logger_msgs REQUIRED) -find_package(tinyxml2_vendor REQUIRED) -find_package(TinyXML2 REQUIRED) # provided by tinyxml2 upstream, or tinyxml2_vendor - -include_directories( - include -) - -add_library(${PROJECT_NAME} SHARED - src/prompt_runners.cpp -) - -ament_target_dependencies(${PROJECT_NAME} - rclcpp - rclcpp_action - pluginlib - prompt_msgs - capabilities2_msgs - capabilities2_runner - capabilities2_utils - event_logger - event_logger_msgs - TinyXML2 -) - -pluginlib_export_plugin_description_file(capabilities2_runner plugins.xml) - -install(TARGETS ${PROJECT_NAME} - EXPORT ${PROJECT_NAME} - ARCHIVE DESTINATION lib - LIBRARY DESTINATION lib - RUNTIME DESTINATION bin -) - -install(DIRECTORY include/ - DESTINATION include -) - -ament_export_include_directories(include) -ament_export_libraries(${PROJECT_NAME}) - -ament_package() diff --git a/capabilities2_runner_prompt/include/capabilities2_runner_prompt/prompt_capability_runner.hpp b/capabilities2_runner_prompt/include/capabilities2_runner_prompt/prompt_capability_runner.hpp deleted file mode 100644 index 4bb4673..0000000 --- a/capabilities2_runner_prompt/include/capabilities2_runner_prompt/prompt_capability_runner.hpp +++ /dev/null @@ -1,44 +0,0 @@ -#pragma once -#include -#include -#include -#include - -namespace capabilities2_runner -{ - -/** - * @brief prompt capabilities runner - * - * This class is a wrapper around the capabilities2 service runner and is used to pass - * data to prompt_tools/prompt service, providing it as a capability that prompts - * robot capabilities. - */ -class PromptCapabilityRunner : public PromptServiceRunner -{ -public: - PromptCapabilityRunner() : PromptServiceRunner() - { - } - - /** - * @brief generate the prompt used for prompting the capabilities. - * - * @param parameters tinyXML2 parameters - * @return std::string - */ - virtual void generate_prompt(tinyxml2::XMLElement* parameters, int id, std::string& prompt, bool& flush) override - { - tinyxml2::XMLElement* capabilitySpecsElement = parameters->FirstChildElement("CapabilitySpecs"); - - tinyxml2::XMLPrinter printer; - capabilitySpecsElement->Accept(&printer); - - std::string data(printer.CStr()); - - prompt = "The capabilities of the robot are given as follows" + data; - flush = false; - } -}; - -} // namespace capabilities2_runner diff --git a/capabilities2_runner_prompt/include/capabilities2_runner_prompt/prompt_occupancy_runner.hpp b/capabilities2_runner_prompt/include/capabilities2_runner_prompt/prompt_occupancy_runner.hpp deleted file mode 100644 index 529773c..0000000 --- a/capabilities2_runner_prompt/include/capabilities2_runner_prompt/prompt_occupancy_runner.hpp +++ /dev/null @@ -1,47 +0,0 @@ -#pragma once -#include -#include -#include -#include - -namespace capabilities2_runner -{ -/** - * @brief prompt capability runner - * - * This class is a wrapper around the capabilities2 service runner and is used to - * call on the prompt_tools/prompt service, providing it as a capability that prompts - * occupancy grid map values - */ -class PromptOccupancyRunner : public PromptServiceRunner -{ -public: - PromptOccupancyRunner() : PromptServiceRunner() - { - } - - /** - * @brief generate the prompt used for prompting the occupancy grids. - * - * @param parameters tinyXML2 parameters - * @return std::string - */ - virtual void generate_prompt(tinyxml2::XMLElement* parameters, int id, std::string& prompt, bool& flush) override - { - tinyxml2::XMLElement* occupancyElement = parameters->FirstChildElement("OccupancyGrid"); - - tinyxml2::XMLPrinter printer; - occupancyElement->Accept(&printer); - - std::string data(printer.CStr()); - - prompt = "The OccupancyGrid of the robot shows the surrounding environment of the robot. The data " - "is given as a ros2 nav_msgs::msg::OccupancyGrid of which the content are " + - data; - flush = false; - - info_("prompting with : " + prompt, id); - } -}; - -} // namespace capabilities2_runner diff --git a/capabilities2_runner_prompt/include/capabilities2_runner_prompt/prompt_plan_runner.hpp b/capabilities2_runner_prompt/include/capabilities2_runner_prompt/prompt_plan_runner.hpp deleted file mode 100644 index e9b3460..0000000 --- a/capabilities2_runner_prompt/include/capabilities2_runner_prompt/prompt_plan_runner.hpp +++ /dev/null @@ -1,93 +0,0 @@ -#pragma once -#include -#include -#include -#include - -namespace capabilities2_runner -{ -/** - * @brief prompt capability runner - * - * This class is a wrapper around the capabilities2 service runner and is used to - * call on the prompt_tools/prompt service, providing it as a capability that prompts - * capabilitie plans values - */ -class PromptPlanRunner : public PromptServiceRunner -{ -public: - PromptPlanRunner() : PromptServiceRunner() - { - } - - /** - * @brief generate the prompt used for prompting the occupancy grids. - * - * @param parameters tinyXML2 parameters - * @return std::string - */ - virtual void generate_prompt(tinyxml2::XMLElement* parameters, int id, std::string& prompt, bool& flush) override - { - bool replan; - const char* task; - std::string taskString; - - parameters->QueryBoolAttribute("replan", &replan); - parameters->QueryStringAttribute("task", &task); - - if (task) - taskString = task; - else - taskString = ""; - - if (!replan) - { - prompt = "Build a xml plan based on the availbale capabilities to acheive mentioned task of " + taskString + - ". Return only the xml plan without explanations or comments."; - - flush = true; - } - else - { - tinyxml2::XMLElement* failedElements = parameters->FirstChildElement("FailedElements"); - - prompt = "Rebuild the xml plan based on the availbale capabilities to acheive mentioned task of " + taskString + - ". Just give the xml plan without explanations or comments. These XML " - "elements had incompatibilities. " + - std::string(failedElements->GetText()) + "Recorrect them as well"; - flush = true; - } - - info_("prompting with : " + prompt, id); - } - - /** - * @brief Update on_success event parameters with new data if avaible. - * - * This function is used to inject new data into the XMLElement containing - * parameters related to the on_success trigger event - * - * A pattern needs to be implemented in the derived class - * - * @param parameters pointer to the XMLElement containing parameters - * @return pointer to the XMLElement containing updated parameters - */ - virtual std::string update_on_success(std::string& parameters) - { - tinyxml2::XMLElement* element = convert_to_xml(parameters); - - std::string document_string = response_->response.response; - - // Create the plan element as a child of the existing parameters element - tinyxml2::XMLElement* textElement = element->GetDocument()->NewElement("ReceievdPlan"); - element->InsertEndChild(textElement); - textElement->SetText(document_string.c_str()); - - // Return the updated parameters element with Pose added - std::string result = convert_to_string(element); - - return result; - }; -}; - -} // namespace capabilities2_runner diff --git a/capabilities2_runner_prompt/include/capabilities2_runner_prompt/prompt_pose_runner.hpp b/capabilities2_runner_prompt/include/capabilities2_runner_prompt/prompt_pose_runner.hpp deleted file mode 100644 index 4c831d9..0000000 --- a/capabilities2_runner_prompt/include/capabilities2_runner_prompt/prompt_pose_runner.hpp +++ /dev/null @@ -1,46 +0,0 @@ -#pragma once -#include -#include -#include -#include - -namespace capabilities2_runner -{ -/** - * @brief prompt pose runner - * - * This class is a wrapper around the capabilities2 service runner and is used to pass - * data to prompt_tools/prompt service, providing it as a capability that prompts - * robot pose values - */ -class PromptPoseRunner : public PromptServiceRunner -{ -public: - PromptPoseRunner() : PromptServiceRunner() - { - } - - /** - * @brief generate the prompt used for prompting the capabilities. - * - * @param parameters tinyXML2 parameters - * @return std::string - */ - virtual void generate_prompt(tinyxml2::XMLElement* parameters, int id, std::string& prompt, bool& flush) override - { - tinyxml2::XMLElement* poseElement = parameters->FirstChildElement("Pose"); - - tinyxml2::XMLPrinter printer; - poseElement->Accept(&printer); - - std::string data(printer.CStr()); - - prompt = "The position of the robot is given as a standard ros2 geometry_msgs::msg::Pose of which the content " - "are " + data; - flush = false; - - info_("prompting with : " + prompt, id); - } -}; - -} // namespace capabilities2_runner diff --git a/capabilities2_runner_prompt/include/capabilities2_runner_prompt/prompt_service_runner.hpp b/capabilities2_runner_prompt/include/capabilities2_runner_prompt/prompt_service_runner.hpp deleted file mode 100644 index a60ba9f..0000000 --- a/capabilities2_runner_prompt/include/capabilities2_runner_prompt/prompt_service_runner.hpp +++ /dev/null @@ -1,91 +0,0 @@ -#pragma once -#include -#include -#include -#include -#include -#include - -namespace capabilities2_runner -{ -/** - * @brief prompt service runner - * - * This class is a base class and a wrapper around the capabilities2 service runner - * and is used to call on the prompt_tools/prompt service, providing it as a capability - * that prompts capabilitie plans values - */ -class PromptServiceRunner : public ServiceRunner -{ -public: - PromptServiceRunner() : ServiceRunner() - { - } - - /** - * @brief Starter function for starting the service runner - * - * @param node shared pointer to the capabilities node. Allows to use ros node related functionalities - * @param run_config runner configuration loaded from the yaml file - */ - virtual void start(rclcpp::Node::SharedPtr node, const runner_opts& run_config) override - { - init_service(node, run_config, "/prompt_bridge/prompt"); - } - -protected: - /** - * @brief Generate a request from parameters given. - * - * This function is used in conjunction with the trigger function to inject type erased parameters - * into the typed action - * - * A pattern needs to be implemented in the derived class - * - * @param parameters - * @return prompt_msgs::srv::Prompt::Request the generated request - */ - virtual typename prompt_msgs::srv::Prompt::Request generate_request(tinyxml2::XMLElement* parameters, int id) override - { - prompt_msgs::srv::Prompt::Request request; - - prompt_msgs::msg::ModelOption modelOption1; - modelOption1.key = "model"; - modelOption1.value = "llama3.2"; - - request.prompt.options.push_back(modelOption1); - - prompt_msgs::msg::ModelOption modelOption2; - modelOption2.key = "stream"; - modelOption2.value = false; - modelOption2.type = prompt_msgs::msg::ModelOption::BOOL_TYPE; - - request.prompt.options.push_back(modelOption2); - - generate_prompt(parameters, id, request.prompt.prompt, request.prompt.flush); - - return request; - } - - /** - * @brief generate the prompt used for prompting the data. - * - * @param parameters tinyXML2 parameters - * @return std::string - */ - virtual void generate_prompt(tinyxml2::XMLElement* parameters, int id, std::string& prompt, bool& flush) = 0; - - virtual void process_response(typename prompt_msgs::srv::Prompt::Response::SharedPtr response, int id) - { - if (response->response.buffered) - { - info_("information buffered", id); - } - else - { - info_("response received : " + response->response.response, id); - } - } -}; - -} // namespace capabilities2_runner diff --git a/capabilities2_runner_prompt/include/capabilities2_runner_prompt/prompt_text_runner.hpp b/capabilities2_runner_prompt/include/capabilities2_runner_prompt/prompt_text_runner.hpp deleted file mode 100644 index 026f70b..0000000 --- a/capabilities2_runner_prompt/include/capabilities2_runner_prompt/prompt_text_runner.hpp +++ /dev/null @@ -1,45 +0,0 @@ -#pragma once -#include -#include -#include -#include - -namespace capabilities2_runner -{ -/** - * @brief prompt capability runner - * - * This class is a wrapper around the capabilities2 service runner and is used to - * call on the prompt_tools/prompt service, providing it as a capability that prompts - * text values - */ -class PromptTextRunner : public PromptServiceRunner -{ -public: - PromptTextRunner() : PromptServiceRunner() - { - } - - /** - * @brief generate the prompt used for prompting the text. - * - * @param parameters tinyXML2 parameters - * @return std::string - */ - virtual void generate_prompt(tinyxml2::XMLElement* parameters, int id, std::string& prompt, bool& flush) override - { - tinyxml2::XMLElement* textElement = parameters->FirstChildElement("Text"); - - tinyxml2::XMLPrinter printer; - textElement->Accept(&printer); - - std::string data(printer.CStr()); - - prompt = "The response was " + data; - flush = true; - - info_("prompting with : " + prompt, id); - } -}; - -} // namespace capabilities2_runner diff --git a/capabilities2_runner_prompt/package.xml b/capabilities2_runner_prompt/package.xml deleted file mode 100644 index 54160c3..0000000 --- a/capabilities2_runner_prompt/package.xml +++ /dev/null @@ -1,33 +0,0 @@ - - - - capabilities2_runner_prompt - 0.0.0 - TODO: Package description - - Kalana Ratnayake - Kalana Ratnayake - - Kalana Ratnayake - - TODO: License declaration - - ament_cmake - - rclcpp - rclcpp_action - pluginlib - prompt_msgs - capabilities2_msgs - capabilities2_runner - event_logger - event_logger_msgs - tinyxml2_vendor - - ament_lint_auto - ament_lint_common - - - ament_cmake - - diff --git a/capabilities2_runner_prompt/plugins.xml b/capabilities2_runner_prompt/plugins.xml deleted file mode 100644 index 343617d..0000000 --- a/capabilities2_runner_prompt/plugins.xml +++ /dev/null @@ -1,27 +0,0 @@ - - - - A plugin that provide capability prompting capability - - - - - A plugin that provide occupancy grid map prompting capability - - - - - A plugin that requests a new pplan based on available capabilities and a defined task - - - - - A plugin that provide pose prompting capability - - - - - A plugin that provide text prompting capability - - - diff --git a/capabilities2_runner_prompt/src/prompt_runners.cpp b/capabilities2_runner_prompt/src/prompt_runners.cpp deleted file mode 100644 index 1ebcd4d..0000000 --- a/capabilities2_runner_prompt/src/prompt_runners.cpp +++ /dev/null @@ -1,14 +0,0 @@ -#include -#include -#include -#include -#include -#include -#include - -// register runner plugins -PLUGINLIB_EXPORT_CLASS(capabilities2_runner::PromptTextRunner, capabilities2_runner::RunnerBase) -PLUGINLIB_EXPORT_CLASS(capabilities2_runner::PromptPoseRunner, capabilities2_runner::RunnerBase) -PLUGINLIB_EXPORT_CLASS(capabilities2_runner::PromptOccupancyRunner, capabilities2_runner::RunnerBase) -PLUGINLIB_EXPORT_CLASS(capabilities2_runner::PromptPlanRunner, capabilities2_runner::RunnerBase) -PLUGINLIB_EXPORT_CLASS(capabilities2_runner::PromptCapabilityRunner, capabilities2_runner::RunnerBase) \ No newline at end of file diff --git a/capabilities2_runner_system/CMakeLists.txt b/capabilities2_runner_system/CMakeLists.txt index 9d56357..aaec417 100644 --- a/capabilities2_runner_system/CMakeLists.txt +++ b/capabilities2_runner_system/CMakeLists.txt @@ -57,6 +57,14 @@ install(DIRECTORY include/ DESTINATION include ) +install(DIRECTORY interfaces + DESTINATION share/${PROJECT_NAME} +) + +install(DIRECTORY providers + DESTINATION share/${PROJECT_NAME} +) + ament_export_include_directories(include) ament_export_libraries(${PROJECT_NAME}) diff --git a/system_capabilities/interfaces/CompletionRunner.yaml b/capabilities2_runner_system/interfaces/CompletionRunner.yaml similarity index 100% rename from system_capabilities/interfaces/CompletionRunner.yaml rename to capabilities2_runner_system/interfaces/CompletionRunner.yaml diff --git a/system_capabilities/interfaces/InputMultiplexAllRunner.yaml b/capabilities2_runner_system/interfaces/InputMultiplexAllRunner.yaml similarity index 100% rename from system_capabilities/interfaces/InputMultiplexAllRunner.yaml rename to capabilities2_runner_system/interfaces/InputMultiplexAllRunner.yaml diff --git a/system_capabilities/interfaces/InputMultiplexAnyRunner.yaml b/capabilities2_runner_system/interfaces/InputMultiplexAnyRunner.yaml similarity index 100% rename from system_capabilities/interfaces/InputMultiplexAnyRunner.yaml rename to capabilities2_runner_system/interfaces/InputMultiplexAnyRunner.yaml diff --git a/capabilities2_runner_system/package.xml b/capabilities2_runner_system/package.xml index dd79d51..f6449b3 100644 --- a/capabilities2_runner_system/package.xml +++ b/capabilities2_runner_system/package.xml @@ -32,5 +32,33 @@ ament_cmake + + + + interfaces/CompletionRunner.yaml + + + + providers/CompletionRunner.yaml + + + + + interfaces/InputMultiplexAllRunner.yaml + + + + providers/InputMultiplexAllRunner.yaml + + + + + interfaces/InputMultiplexAnyRunner.yaml + + + + providers/InputMultiplexAnyRunner.yaml + + diff --git a/system_capabilities/providers/CompletionRunner.yaml b/capabilities2_runner_system/providers/CompletionRunner.yaml similarity index 100% rename from system_capabilities/providers/CompletionRunner.yaml rename to capabilities2_runner_system/providers/CompletionRunner.yaml diff --git a/system_capabilities/providers/InputMultiplexAllRunner.yaml b/capabilities2_runner_system/providers/InputMultiplexAllRunner.yaml similarity index 100% rename from system_capabilities/providers/InputMultiplexAllRunner.yaml rename to capabilities2_runner_system/providers/InputMultiplexAllRunner.yaml diff --git a/system_capabilities/providers/InputMultiplexAnyRunner.yaml b/capabilities2_runner_system/providers/InputMultiplexAnyRunner.yaml similarity index 100% rename from system_capabilities/providers/InputMultiplexAnyRunner.yaml rename to capabilities2_runner_system/providers/InputMultiplexAnyRunner.yaml diff --git a/system_capabilities/CMakeLists.txt b/system_capabilities/CMakeLists.txt deleted file mode 100644 index 1d10d3b..0000000 --- a/system_capabilities/CMakeLists.txt +++ /dev/null @@ -1,16 +0,0 @@ -cmake_minimum_required(VERSION 3.8) -project(system_capabilities) - -find_package(ament_cmake REQUIRED) - -# install interface files -install(DIRECTORY interfaces - DESTINATION share/${PROJECT_NAME} -) - -# install semantic interface files -install(DIRECTORY providers - DESTINATION share/${PROJECT_NAME} -) - -ament_package() diff --git a/system_capabilities/LICENSE b/system_capabilities/LICENSE deleted file mode 100644 index 30e8e2e..0000000 --- a/system_capabilities/LICENSE +++ /dev/null @@ -1,17 +0,0 @@ -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in -all copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL -THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN -THE SOFTWARE. diff --git a/system_capabilities/package.xml b/system_capabilities/package.xml deleted file mode 100644 index 6bbf60c..0000000 --- a/system_capabilities/package.xml +++ /dev/null @@ -1,48 +0,0 @@ - - - - system_capabilities - 0.0.0 - TODO: Package description - kalana - MIT - - ament_cmake - - ament_lint_auto - ament_lint_common - - - ament_cmake - - - - interfaces/CompletionRunner.yaml - - - - providers/CompletionRunner.yaml - - - - - interfaces/InputMultiplexAllRunner.yaml - - - - providers/InputMultiplexAllRunner.yaml - - - - - - interfaces/InputMultiplexAnyRunner.yaml - - - - providers/InputMultiplexAnyRunner.yaml - - - - - From c554ebf5f9b9680c9243c7fef383403d2f9cb3ad Mon Sep 17 00:00:00 2001 From: Kalana Ratnayake Date: Fri, 22 Aug 2025 15:23:01 +1000 Subject: [PATCH 2/5] updated documentation --- docs/fabric_setup.md | 25 +++++++++++++++++++++++++ docs/nav2_setup.md | 17 +++++++++-------- docs/prompt_tools_setup.md | 9 ++++++++- readme.md | 1 + 4 files changed, 43 insertions(+), 9 deletions(-) create mode 100644 docs/fabric_setup.md diff --git a/docs/fabric_setup.md b/docs/fabric_setup.md new file mode 100644 index 0000000..7ce2a50 --- /dev/null +++ b/docs/fabric_setup.md @@ -0,0 +1,25 @@ +# Dependency installation for Prompt Tools Runners + +## Clone packages + +Clone the fabric package same workspace if its not already availabe in the workspace. Capabilities2 Fabric Runners are dependent on this package. + +```bash +cd src +git clone https://github.com/CollaborativeRoboticsLab/fabric.git +``` + +## Clone Capabilities2 plugin for Fabric stack + +```bash +cd src +git clone https://github.com/CollaborativeRoboticsLab/fabric.git +``` + +## Dependency Installation + +Move to workspace root and run the following command to install dependencies + +```bash +rosdep install --from-paths src --ignore-src -r -y +``` \ No newline at end of file diff --git a/docs/nav2_setup.md b/docs/nav2_setup.md index 2a44385..b8eaab5 100644 --- a/docs/nav2_setup.md +++ b/docs/nav2_setup.md @@ -1,26 +1,27 @@ # Dependency installation for Nav2 Runners -## Install nav2 stack +## Install nav2 stack and slam-toolbox Run the following commands to install nav2 stack ```bash -sudo apt install ros-humble-navigation2 ros-humble-nav2-bringup +sudo apt install ros-$ROS_DISTRO-navigation2 ros-$ROS_DISTRO-nav2-bringup ros-$ROS_DISTRO-slam-toolbox ``` -## Install slam-toolbox +## Clone Nav2 configuration + +Clone the nav_stack default configuration and launch files to the same workspace if its not already availabe in the workspace. Capabilities2 Nav2 Runners are dependent on this package. ```bash -sudo apt install ros-$ROS_DISTRO-slam-toolbox +cd src +git clone https://github.com/CollaborativeRoboticsLab/nav_stack.git ``` -## Clone configuration - -Clone the nav_stack default configuration and launch files to the same workspace if its not already availabe in the workspace. Capabilities2 Nav2 Runners are dependent on this package. +## Clone Capabilities2 plugin for Nav2 stack ```bash cd src -git clone https://github.com/CollaborativeRoboticsLab/nav_stack.git +git clone https://github.com/CollaborativeRoboticsLab/capabilities2_runner_nav2.git ``` ## Turtlebot3 Simulation (Optional) diff --git a/docs/prompt_tools_setup.md b/docs/prompt_tools_setup.md index 466c21e..dd71076 100644 --- a/docs/prompt_tools_setup.md +++ b/docs/prompt_tools_setup.md @@ -6,7 +6,14 @@ Clone the prompt tools package same workspace if its not already availabe in the ```bash cd src -git clone https://github.com/CollaborativeRoboticsLab/prompt_tools.git -b develop +git clone https://github.com/CollaborativeRoboticsLab/prompt_tools.git +``` + +## Clone Capabilities2 plugin for Prompt tools stack + +```bash +cd src +git clone https://github.com/CollaborativeRoboticsLab/capabilities2_runner_prompt.git ``` ## Dependency Installation diff --git a/readme.md b/readme.md index 99ac6dc..139ce28 100644 --- a/readme.md +++ b/readme.md @@ -37,6 +37,7 @@ Runners can be created using the runner API parent classes [here](./capabilities - [Setup Instructions without devcontainer](./docs/setup.md) - [Dependency installation for Nav2 Runners](./docs/nav2_setup.md) - [Dependency installation for Prompt Runners](./docs/prompt_tools_setup.md) +- [Dependency installation for Fabric Runners](./docs/fabric_setup.md) - [Dependency installation for Foxglove-studio](./docs/foxglove_studio.md) ## Quick Startup information From 92662a26e36783870776f64052a56cef1f719040 Mon Sep 17 00:00:00 2001 From: Kalana Ratnayake Date: Fri, 22 Aug 2025 23:12:12 +1000 Subject: [PATCH 3/5] minor fixes --- docs/setup.md | 24 +++++++++++------------- readme.md | 6 +++--- 2 files changed, 14 insertions(+), 16 deletions(-) diff --git a/docs/setup.md b/docs/setup.md index 74bce4a..05ac7d6 100644 --- a/docs/setup.md +++ b/docs/setup.md @@ -11,26 +11,18 @@ mkdir -p /home/$USER/capabilities_ws/src cd /home/$USER/capabilities_ws/src ``` -### Tinyxml2 Installation - -Clone and install the tinyXML2 package - -```bash -git clone https://github.com/leethomason/tinyxml2.git -cd tinyxml2 -make install -``` - ### Cloning the Packages Clone the package using Git ```bash -git clone -b capabilities2-server-fabric https://github.com/CollaborativeRoboticsLab/capabilities2.git -git clone -b develop https://github.com/CollaborativeRoboticsLab/std_capabilities.git -git clone https://github.com/AIResearchLab/nav_stack.git +git clone https://github.com/CollaborativeRoboticsLab/capabilities2.git ``` +Optionally you can clone +```bash +git https://github.com/CollaborativeRoboticsLab/std_capabilities.git +``` ### Dependency installation Move the terminal to workspace root and install dependencies. @@ -49,3 +41,9 @@ Use colcon to build the packages: ```bash colcon build ``` + +### Additional installtions + +[Fabric](fabric_setup.md) \ +[Prompt Tools](./prompt_tools_setup.md) \ +[Nav2 stack](./nav2_setup.md) \ No newline at end of file diff --git a/readme.md b/readme.md index 139ce28..e7bacbd 100644 --- a/readme.md +++ b/readme.md @@ -1,4 +1,4 @@ -# capabilities2 +# Capabilities2 [![ROS2 Jazzy](https://img.shields.io/badge/ROS2-Jazzy-blue)](https://index.ros.org/doc/ros2/Releases/) [![License: MIT](https://img.shields.io/badge/License-MIT-yellow.svg)](https://opensource.org/licenses/MIT) @@ -33,11 +33,11 @@ Runners can be created using the runner API parent classes [here](./capabilities ## Setup Information +- [Installation](./docs/setup.md) - [Setup Instructions with devcontainer](./docs/setup_with_dev.md) -- [Setup Instructions without devcontainer](./docs/setup.md) +- [Dependency installation for Fabric Runners](./docs/fabric_setup.md) - [Dependency installation for Nav2 Runners](./docs/nav2_setup.md) - [Dependency installation for Prompt Runners](./docs/prompt_tools_setup.md) -- [Dependency installation for Fabric Runners](./docs/fabric_setup.md) - [Dependency installation for Foxglove-studio](./docs/foxglove_studio.md) ## Quick Startup information From 27893bc493b82d710df8724b1d0d5167a1031448 Mon Sep 17 00:00:00 2001 From: Kalana Ratnayake Date: Sat, 23 Aug 2025 17:20:56 +1000 Subject: [PATCH 4/5] fixes to match code refactoring --- .../interfaces/CapabilityGetRunner.yaml | 10 ++-- .../providers/CapabilityGetRunner.yaml | 2 +- .../completion_runner.hpp | 52 ------------------- .../interfaces/CompletionRunner.yaml | 13 ----- capabilities2_runner_system/package.xml | 9 ---- capabilities2_runner_system/plugins.xml | 5 -- .../providers/CompletionRunner.yaml | 8 --- .../providers/InputMultiplexAllRunner.yaml | 4 +- .../providers/InputMultiplexAnyRunner.yaml | 4 +- .../src/capabilities2_runner.cpp | 4 +- 10 files changed, 11 insertions(+), 100 deletions(-) delete mode 100644 capabilities2_runner_system/include/capabilities2_runner_system/completion_runner.hpp delete mode 100644 capabilities2_runner_system/interfaces/CompletionRunner.yaml delete mode 100644 capabilities2_runner_system/providers/CompletionRunner.yaml diff --git a/capabilities2_runner_capabilities/interfaces/CapabilityGetRunner.yaml b/capabilities2_runner_capabilities/interfaces/CapabilityGetRunner.yaml index 79535fc..c50bbbb 100644 --- a/capabilities2_runner_capabilities/interfaces/CapabilityGetRunner.yaml +++ b/capabilities2_runner_capabilities/interfaces/CapabilityGetRunner.yaml @@ -3,11 +3,11 @@ name: CapabilityGetRunner spec_version: 1.1 spec_type: interface -description: "This capability depends on the capabilities2 server functionalities and allows an decision making authority such as an - LLM extract capabilities of the robot. The capability can be trigged with an command such as - ''. This is included in - the default starting plan and the decision making authority such as an LLM does not need to include this in any generated - plans. The details for the Capaiblities are stored in a format as follows, +description: "This capability depends on the capabilities2 server functionalities and allows an decision making authority such as an LLM extract + capabilities of the robot. The capability can be trigged with an command such as + ''. + This is included in the default starting plan and the decision making authority such as an LLM does not need to include this in any + generated plans. The details for the Capaiblities are stored in a format as follows, ' diff --git a/capabilities2_runner_capabilities/providers/CapabilityGetRunner.yaml b/capabilities2_runner_capabilities/providers/CapabilityGetRunner.yaml index 7202ee7..640e3fc 100644 --- a/capabilities2_runner_capabilities/providers/CapabilityGetRunner.yaml +++ b/capabilities2_runner_capabilities/providers/CapabilityGetRunner.yaml @@ -5,5 +5,5 @@ name: CapabilityGetRunner spec_type: provider spec_version: 1.1 description: "The capability provider for extracting capabilities from server. This is used to identify the capabilities of the robot" -implements: std_capabilities/CapabilityGetRunner +implements: capabilities2_runner_capabilities/CapabilityGetRunner runner: capabilities2_runner::CapabilityGetRunner \ No newline at end of file diff --git a/capabilities2_runner_system/include/capabilities2_runner_system/completion_runner.hpp b/capabilities2_runner_system/include/capabilities2_runner_system/completion_runner.hpp deleted file mode 100644 index 8e5dcdc..0000000 --- a/capabilities2_runner_system/include/capabilities2_runner_system/completion_runner.hpp +++ /dev/null @@ -1,52 +0,0 @@ -#pragma once -#include -#include -#include -#include -#include - -namespace capabilities2_runner -{ -/** - * @brief completion runner - * - * This class is a wrapper around the capabilities2 service runner and is used to - * call on the /fabric/set_completion service, providing it as a - * capability that notifys the completion of the fabric - */ -class CompletionRunner : public ServiceRunner -{ -public: - CompletionRunner() : ServiceRunner() - { - } - - /** - * @brief Starter function for starting the service runner - * - * @param node shared pointer to the capabilities node. Allows to use ros node related functionalities - * @param run_config runner configuration loaded from the yaml file - */ - virtual void start(rclcpp::Node::SharedPtr node, const runner_opts& run_config) override - { - init_service(node, run_config, "/fabric/set_completion"); - } - -protected: - /** - * @brief Generate a empty request. - * - * This function is used in conjunction with the trigger function to inject type erased parameters - * into the typed action - * - * @param parameters - * @return prompt_msgs::srv::Prompt::Request the generated request - */ - virtual typename fabric_msgs::srv::CompleteFabric::Request generate_request(tinyxml2::XMLElement* parameters, int id) override - { - fabric_msgs::srv::CompleteFabric::Request request; - return request; - } -}; - -} // namespace capabilities2_runner diff --git a/capabilities2_runner_system/interfaces/CompletionRunner.yaml b/capabilities2_runner_system/interfaces/CompletionRunner.yaml deleted file mode 100644 index d34d09f..0000000 --- a/capabilities2_runner_system/interfaces/CompletionRunner.yaml +++ /dev/null @@ -1,13 +0,0 @@ -%YAML 1.1 ---- -name: CompletionRunner -spec_version: 1.1 -spec_type: interface -description: "This capability notifies the completion of the capabilities fabric to the completion_server on the capabilities2 fabric - package. This is included on every fabric as the last capability to be triggered during connection idenification for the - fabric. A decision making authority such as an LLM does not need to include this in plans generated by it." -interface: - actions: - "/fabric/set_completion": - type: "capabilities2_msgs::srv::CompleteFabric" - description: "Fabric completion notifier interface of the Capabilities fabric" \ No newline at end of file diff --git a/capabilities2_runner_system/package.xml b/capabilities2_runner_system/package.xml index f6449b3..1af9a4e 100644 --- a/capabilities2_runner_system/package.xml +++ b/capabilities2_runner_system/package.xml @@ -33,15 +33,6 @@ ament_cmake - - - interfaces/CompletionRunner.yaml - - - - providers/CompletionRunner.yaml - - interfaces/InputMultiplexAllRunner.yaml diff --git a/capabilities2_runner_system/plugins.xml b/capabilities2_runner_system/plugins.xml index 41e8b96..bc05f3c 100644 --- a/capabilities2_runner_system/plugins.xml +++ b/capabilities2_runner_system/plugins.xml @@ -11,9 +11,4 @@ It can handle multiple input streams and route them to the appropriate output.
- - - A plugin that notifies about the completion of the fabric to the action server - - diff --git a/capabilities2_runner_system/providers/CompletionRunner.yaml b/capabilities2_runner_system/providers/CompletionRunner.yaml deleted file mode 100644 index 3fb38e6..0000000 --- a/capabilities2_runner_system/providers/CompletionRunner.yaml +++ /dev/null @@ -1,8 +0,0 @@ -%YAML 1.1 ---- -name: CompletionRunner -spec_type: provider -spec_version: 1.1 -description: "The capability provider for the /fabric/set_completion interface" -implements: system_capabilities/CompletionRunner -runner: capabilities2_runner::CompletionRunner diff --git a/capabilities2_runner_system/providers/InputMultiplexAllRunner.yaml b/capabilities2_runner_system/providers/InputMultiplexAllRunner.yaml index b3edbfd..1720a2b 100644 --- a/capabilities2_runner_system/providers/InputMultiplexAllRunner.yaml +++ b/capabilities2_runner_system/providers/InputMultiplexAllRunner.yaml @@ -3,6 +3,6 @@ name: InputMultiplexAllRunner spec_type: provider spec_version: 1.1 -description: "The capability provider for the system_capabilities/InputMultiplexAllRunner interface" -implements: system_capabilities/InputMultiplexAllRunner +description: "The capability provider for the capabilities2_runner_system/InputMultiplexAllRunner interface" +implements: capabilities2_runner_system/InputMultiplexAllRunner runner: capabilities2_runner::InputMultiplexAllRunner \ No newline at end of file diff --git a/capabilities2_runner_system/providers/InputMultiplexAnyRunner.yaml b/capabilities2_runner_system/providers/InputMultiplexAnyRunner.yaml index 789ee28..9e07449 100644 --- a/capabilities2_runner_system/providers/InputMultiplexAnyRunner.yaml +++ b/capabilities2_runner_system/providers/InputMultiplexAnyRunner.yaml @@ -3,6 +3,6 @@ name: InputMultiplexAnyRunner spec_type: provider spec_version: 1.1 -description: "The capability provider for the system_capabilities/InputMultiplexAnyRunner interface" -implements: system_capabilities/InputMultiplexAnyRunner +description: "The capability provider for the capabilities2_runner_system/InputMultiplexAnyRunner interface" +implements: capabilities2_runner_system/InputMultiplexAnyRunner runner: capabilities2_runner::InputMultiplexAnyRunner \ No newline at end of file diff --git a/capabilities2_runner_system/src/capabilities2_runner.cpp b/capabilities2_runner_system/src/capabilities2_runner.cpp index 9d828da..114133e 100644 --- a/capabilities2_runner_system/src/capabilities2_runner.cpp +++ b/capabilities2_runner_system/src/capabilities2_runner.cpp @@ -1,10 +1,8 @@ #include #include -#include #include #include // register runner plugins PLUGINLIB_EXPORT_CLASS(capabilities2_runner::InputMultiplexAllRunner, capabilities2_runner::RunnerBase); -PLUGINLIB_EXPORT_CLASS(capabilities2_runner::InputMultiplexAnyRunner, capabilities2_runner::RunnerBase); -PLUGINLIB_EXPORT_CLASS(capabilities2_runner::CompletionRunner, capabilities2_runner::RunnerBase) \ No newline at end of file +PLUGINLIB_EXPORT_CLASS(capabilities2_runner::InputMultiplexAnyRunner, capabilities2_runner::RunnerBase); \ No newline at end of file From 201b9058f08c8c76712f858eee377a02f1bc5f3f Mon Sep 17 00:00:00 2001 From: Kalana Ratnayake Date: Sun, 24 Aug 2025 00:47:30 +1000 Subject: [PATCH 5/5] minor fixes after refactoring --- .../include/capabilities2_runner/action_runner.hpp | 12 ++++++++++-- .../include/capabilities2_runner/runner_base.hpp | 2 +- .../include/capabilities2_runner/service_runner.hpp | 9 ++++++++- .../include/capabilities2_runner/topic_runner.hpp | 9 ++++++++- 4 files changed, 27 insertions(+), 5 deletions(-) diff --git a/capabilities2_runner/include/capabilities2_runner/action_runner.hpp b/capabilities2_runner/include/capabilities2_runner/action_runner.hpp index de2786a..7c768df 100644 --- a/capabilities2_runner/include/capabilities2_runner/action_runner.hpp +++ b/capabilities2_runner/include/capabilities2_runner/action_runner.hpp @@ -93,7 +93,8 @@ class ActionRunner : public RunnerBase // Trigger on_stopped event if defined if (events[runner_id].on_stopped.interface != "") { - event_(EventType::STOPPED, -1, events[runner_id].on_stopped.interface, events[runner_id].on_stopped.provider); + event_(EventType::STOPPED, -1, events[runner_id].on_stopped.interface, + events[runner_id].on_stopped.provider); triggerFunction_(events[runner_id].on_stopped.interface, update_on_stopped(events[runner_id].on_stopped.parameters)); } @@ -116,7 +117,14 @@ class ActionRunner : public RunnerBase } } - info_("stopping runner"); + info_("removing event options"); + + // remove all event options for this runner instance + const auto n = events.size(); + events.clear(); + info_("removed event options for " + std::to_string(n) + " runner ids"); + + info_("runner cleaned. stopping.."); } /** diff --git a/capabilities2_runner/include/capabilities2_runner/runner_base.hpp b/capabilities2_runner/include/capabilities2_runner/runner_base.hpp index 65d8659..b0e20ae 100644 --- a/capabilities2_runner/include/capabilities2_runner/runner_base.hpp +++ b/capabilities2_runner/include/capabilities2_runner/runner_base.hpp @@ -115,7 +115,7 @@ class RunnerBase parameters_[runner_id] = element; - info_("received new parameters with event id", runner_id); + info_("received new parameters with event id : " + std::to_string(runner_id), runner_id); executionThreadPool[runner_id] = std::thread(&RunnerBase::execution, this, runner_id); diff --git a/capabilities2_runner/include/capabilities2_runner/service_runner.hpp b/capabilities2_runner/include/capabilities2_runner/service_runner.hpp index 5238c0b..d28f6be 100644 --- a/capabilities2_runner/include/capabilities2_runner/service_runner.hpp +++ b/capabilities2_runner/include/capabilities2_runner/service_runner.hpp @@ -143,7 +143,14 @@ class ServiceRunner : public RunnerBase update_on_stopped(events[runner_id].on_stopped.parameters)); } - info_("stopping runner"); + info_("removing event options"); + + // remove all event options for this runner instance + const auto n = events.size(); + events.clear(); + info_("removed event options for " + std::to_string(n) + " runner ids"); + + info_("runner cleaned. stopping.."); } protected: diff --git a/capabilities2_runner/include/capabilities2_runner/topic_runner.hpp b/capabilities2_runner/include/capabilities2_runner/topic_runner.hpp index 0fb84ce..5cf2138 100644 --- a/capabilities2_runner/include/capabilities2_runner/topic_runner.hpp +++ b/capabilities2_runner/include/capabilities2_runner/topic_runner.hpp @@ -121,7 +121,14 @@ class TopicRunner : public RunnerBase update_on_stopped(events[runner_id].on_stopped.parameters)); } - info_("stopping runner"); + info_("removing event options"); + + // remove all event options for this runner instance + const auto n = events.size(); + events.clear(); + info_("removed event options for " + std::to_string(n) + " runner ids"); + + info_("runner cleaned. stopping.."); } protected: