From d2df0ce916c7680c6967d0cbe449bf00bf56e42c Mon Sep 17 00:00:00 2001 From: JafarAbdi Date: Wed, 25 May 2022 13:49:31 +0000 Subject: [PATCH 1/5] Use moveit_configs_utils for launch files --- core/package.xml | 1 + core/test/move_to.launch.py | 77 +++--------- demo/launch/alternative_path_costs.launch.py | 68 ++--------- demo/launch/cartesian.launch.py | 52 ++------ demo/launch/demo.launch.py | 119 ++++--------------- demo/launch/ik_clearance_cost.launch.py | 52 ++------ demo/launch/modular.launch.py | 52 ++------ demo/launch/pickplace.launch.py | 70 +++-------- demo/package.xml | 1 + 9 files changed, 99 insertions(+), 393 deletions(-) diff --git a/core/package.xml b/core/package.xml index b7c6261eb..2db661cdf 100644 --- a/core/package.xml +++ b/core/package.xml @@ -21,6 +21,7 @@ ament_cmake_gmock ament_cmake_gtest + moveit_configs_utils diff --git a/core/test/move_to.launch.py b/core/test/move_to.launch.py index 103a20cff..d563e7847 100644 --- a/core/test/move_to.launch.py +++ b/core/test/move_to.launch.py @@ -1,73 +1,26 @@ -import unittest import os -import yaml +import unittest +import launch_testing +import pytest +from ament_index_python.packages import get_package_share_directory from launch import LaunchDescription from launch.actions import DeclareLaunchArgument from launch.substitutions import LaunchConfiguration -import launch_testing +from launch_ros.actions import Node +from launch_testing.actions import ReadyToTest from launch_testing.asserts import assertExitCodes from launch_testing.util import KeepAliveProc -from launch_testing.actions import ReadyToTest -from ament_index_python.packages import get_package_share_directory -from launch_ros.actions import Node - -import pytest - -import xacro - - -def load_file(package_name, file_path): - package_path = get_package_share_directory(package_name) - absolute_file_path = os.path.join(package_path, file_path) - - try: - with open(absolute_file_path, "r") as file: - return file.read() - except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available - return None - - -def load_yaml(package_name, file_path): - package_path = get_package_share_directory(package_name) - absolute_file_path = os.path.join(package_path, file_path) - - try: - with open(absolute_file_path, "r") as file: - return yaml.safe_load(file) - except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available - return None +from moveit_configs_utils import MoveItConfigsBuilder @pytest.mark.launch_test def generate_test_description(): - # planning_context - robot_description_config = xacro.process_file( - os.path.join( - get_package_share_directory("moveit_resources_panda_moveit_config"), - "config", - "panda.urdf.xacro", - ) - ) - robot_description = {"robot_description": robot_description_config.toxml()} - - robot_description_semantic_config = load_file( - "moveit_resources_panda_moveit_config", "config/panda.srdf" + moveit_config = ( + MoveItConfigsBuilder("moveit_resources_panda") + .robot_description(file_path="config/panda.urdf.xacro") + .to_moveit_configs() ) - robot_description_semantic = { - "robot_description_semantic": robot_description_semantic_config - } - - kinematics_yaml = load_yaml( - "moveit_resources_panda_moveit_config", "config/kinematics.yaml" - ) - robot_description_kinematics = {"robot_description_kinematics": kinematics_yaml} - - robot_description_planning = { - "robot_description_planning": load_yaml( - "moveit_resources_panda_moveit_config", "config/joint_limits.yaml" - ) - } test_exec = Node( executable=[ @@ -75,10 +28,10 @@ def generate_test_description(): ], output="screen", parameters=[ - robot_description, - robot_description_semantic, - robot_description_kinematics, - robot_description_planning, + moveit_config.robot_description, + moveit_config.robot_description_semantic, + moveit_config.robot_description_kinematics, + moveit_config.joint_limits, ], ) diff --git a/demo/launch/alternative_path_costs.launch.py b/demo/launch/alternative_path_costs.launch.py index e72e8ceb9..3edd2343a 100644 --- a/demo/launch/alternative_path_costs.launch.py +++ b/demo/launch/alternative_path_costs.launch.py @@ -1,72 +1,28 @@ import os -import yaml + +from ament_index_python.packages import get_package_share_directory from launch import LaunchDescription from launch_ros.actions import Node -from ament_index_python.packages import get_package_share_directory - - -def load_file(package_name, file_path): - package_path = get_package_share_directory(package_name) - absolute_file_path = os.path.join(package_path, file_path) - - try: - with open(absolute_file_path, "r") as file: - return file.read() - except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available - return None - - -def load_yaml(package_name, file_path): - package_path = get_package_share_directory(package_name) - absolute_file_path = os.path.join(package_path, file_path) - - try: - with open(absolute_file_path, "r") as file: - return yaml.safe_load(file) - except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available - return None +from moveit_configs_utils import MoveItConfigsBuilder def generate_launch_description(): - # Get URDF and SRDF - robot_description_config = load_file( - "moveit_resources_panda_description", "urdf/panda.urdf" - ) - robot_description = {"robot_description": robot_description_config} - - robot_description_semantic_config = load_file( - "moveit_resources_panda_moveit_config", "config/panda.srdf" - ) - robot_description_semantic = { - "robot_description_semantic": robot_description_semantic_config - } - - kinematics_yaml = load_yaml( - "moveit_resources_panda_moveit_config", "config/kinematics.yaml" - ) - - # Planning Functionality - ompl_planning_pipeline_config = { - "move_group": { - "planning_plugin": "ompl_interface/OMPLPlanner", - "request_adapters": """default_planner_request_adapters/AddTimeOptimalParameterization default_planner_request_adapters/FixWorkspaceBounds default_planner_request_adapters/FixStartStateBounds default_planner_request_adapters/FixStartStateCollision default_planner_request_adapters/FixStartStatePathConstraints""", - "start_state_max_bounds_error": 0.1, - } - } - ompl_planning_yaml = load_yaml( - "moveit_resources_panda_moveit_config", "config/ompl_planning.yaml" + moveit_config = ( + MoveItConfigsBuilder("moveit_resources_panda") + .robot_description(file_path="config/panda.urdf.xacro") + .planning_pipelines(pipelines=["ompl"]) + .to_moveit_configs() ) - ompl_planning_pipeline_config["move_group"].update(ompl_planning_yaml) cartesian_task = Node( package="moveit_task_constructor_demo", executable="alternative_path_costs", output="screen", parameters=[ - robot_description, - robot_description_semantic, - kinematics_yaml, - ompl_planning_pipeline_config, + moveit_config.robot_description, + moveit_config.robot_description_semantic, + moveit_config.robot_description_kinematics, + moveit_config.planning_pipelines, ], ) diff --git a/demo/launch/cartesian.launch.py b/demo/launch/cartesian.launch.py index 8773ece61..b3b6e9d48 100644 --- a/demo/launch/cartesian.launch.py +++ b/demo/launch/cartesian.launch.py @@ -1,55 +1,27 @@ import os -import yaml + +from ament_index_python.packages import get_package_share_directory from launch import LaunchDescription from launch_ros.actions import Node -from ament_index_python.packages import get_package_share_directory - - -def load_file(package_name, file_path): - package_path = get_package_share_directory(package_name) - absolute_file_path = os.path.join(package_path, file_path) - - try: - with open(absolute_file_path, "r") as file: - return file.read() - except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available - return None - - -def load_yaml(package_name, file_path): - package_path = get_package_share_directory(package_name) - absolute_file_path = os.path.join(package_path, file_path) - - try: - with open(absolute_file_path, "r") as file: - return yaml.safe_load(file) - except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available - return None +from moveit_configs_utils import MoveItConfigsBuilder def generate_launch_description(): - # Get URDF and SRDF - robot_description_config = load_file( - "moveit_resources_panda_description", "urdf/panda.urdf" - ) - robot_description = {"robot_description": robot_description_config} - - robot_description_semantic_config = load_file( - "moveit_resources_panda_moveit_config", "config/panda.srdf" - ) - robot_description_semantic = { - "robot_description_semantic": robot_description_semantic_config - } - - kinematics_yaml = load_yaml( - "moveit_resources_panda_moveit_config", "config/kinematics.yaml" + moveit_config = ( + MoveItConfigsBuilder("moveit_resources_panda") + .robot_description(file_path="config/panda.urdf.xacro") + .to_moveit_configs() ) cartesian_task = Node( package="moveit_task_constructor_demo", executable="cartesian", output="screen", - parameters=[robot_description, robot_description_semantic, kinematics_yaml], + parameters=[ + moveit_config.robot_description, + moveit_config.robot_description_semantic, + moveit_config.robot_description_kinematics, + ], ) return LaunchDescription([cartesian_task]) diff --git a/demo/launch/demo.launch.py b/demo/launch/demo.launch.py index 2756703a9..6785ea9a4 100644 --- a/demo/launch/demo.launch.py +++ b/demo/launch/demo.launch.py @@ -1,91 +1,21 @@ import os -import yaml + +import xacro +from ament_index_python.packages import get_package_share_directory from launch import LaunchDescription from launch.actions import ExecuteProcess from launch_ros.actions import Node -from ament_index_python.packages import get_package_share_directory -import xacro - - -def load_file(package_name, file_path): - package_path = get_package_share_directory(package_name) - absolute_file_path = os.path.join(package_path, file_path) - - try: - with open(absolute_file_path, "r") as file: - return file.read() - except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available - return None - - -def load_yaml(package_name, file_path): - package_path = get_package_share_directory(package_name) - absolute_file_path = os.path.join(package_path, file_path) - - try: - with open(absolute_file_path, "r") as file: - return yaml.safe_load(file) - except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available - return None +from moveit_configs_utils import MoveItConfigsBuilder def generate_launch_description(): - # planning_context - robot_description_config = xacro.process_file( - os.path.join( - get_package_share_directory("moveit_resources_panda_moveit_config"), - "config", - "panda.urdf.xacro", - ) + moveit_config = ( + MoveItConfigsBuilder("moveit_resources_panda") + .planning_pipelines(pipelines=["ompl"]) + .robot_description(file_path="config/panda.urdf.xacro") + .trajectory_execution(file_path="config/gripper_moveit_controllers.yaml") + .to_moveit_configs() ) - robot_description = {"robot_description": robot_description_config.toxml()} - - robot_description_semantic_config = load_file( - "moveit_resources_panda_moveit_config", "config/panda.srdf" - ) - robot_description_semantic = { - "robot_description_semantic": robot_description_semantic_config - } - - kinematics_yaml = load_yaml( - "moveit_resources_panda_moveit_config", "config/kinematics.yaml" - ) - - # Planning Functionality - ompl_planning_pipeline_config = { - "move_group": { - "planning_plugin": "ompl_interface/OMPLPlanner", - "request_adapters": """default_planner_request_adapters/AddTimeOptimalParameterization default_planner_request_adapters/FixWorkspaceBounds default_planner_request_adapters/FixStartStateBounds default_planner_request_adapters/FixStartStateCollision default_planner_request_adapters/FixStartStatePathConstraints""", - "start_state_max_bounds_error": 0.1, - } - } - ompl_planning_yaml = load_yaml( - "moveit_resources_panda_moveit_config", "config/ompl_planning.yaml" - ) - ompl_planning_pipeline_config["move_group"].update(ompl_planning_yaml) - - # Trajectory Execution Functionality - moveit_simple_controllers_yaml = load_yaml( - "moveit_resources_panda_moveit_config", "config/panda_controllers.yaml" - ) - moveit_controllers = { - "moveit_simple_controller_manager": moveit_simple_controllers_yaml, - "moveit_controller_manager": "moveit_simple_controller_manager/MoveItSimpleControllerManager", - } - - trajectory_execution = { - "moveit_manage_controllers": True, - "trajectory_execution.allowed_execution_duration_scaling": 1.2, - "trajectory_execution.allowed_goal_duration_margin": 0.5, - "trajectory_execution.allowed_start_tolerance": 0.01, - } - - planning_scene_monitor_parameters = { - "publish_planning_scene": True, - "publish_geometry_updates": True, - "publish_state_updates": True, - "publish_transforms_updates": True, - } # Load ExecuteTaskSolutionCapability so we can execute found solutions in simulation move_group_capabilities = { @@ -98,13 +28,7 @@ def generate_launch_description(): executable="move_group", output="screen", parameters=[ - robot_description, - robot_description_semantic, - kinematics_yaml, - ompl_planning_pipeline_config, - trajectory_execution, - moveit_controllers, - planning_scene_monitor_parameters, + moveit_config.to_dict(), move_group_capabilities, ], ) @@ -120,10 +44,10 @@ def generate_launch_description(): output="log", arguments=["-d", rviz_config_file], parameters=[ - robot_description, - robot_description_semantic, - ompl_planning_pipeline_config, - kinematics_yaml, + moveit_config.robot_description, + moveit_config.robot_description_semantic, + moveit_config.robot_description_kinematics, + moveit_config.planning_pipelines, ], ) @@ -142,23 +66,20 @@ def generate_launch_description(): executable="robot_state_publisher", name="robot_state_publisher", output="both", - parameters=[robot_description], + parameters=[moveit_config.robot_description], ) # ros2_control using FakeSystem as hardware ros2_controllers_path = os.path.join( get_package_share_directory("moveit_resources_panda_moveit_config"), "config", - "panda_ros_controllers.yaml", + "ros2_controllers.yaml", ) ros2_control_node = Node( package="controller_manager", executable="ros2_control_node", - parameters=[robot_description, ros2_controllers_path], - output={ - "stdout": "screen", - "stderr": "screen", - }, + parameters=[moveit_config.robot_description, ros2_controllers_path], + output="both", ) # Load controllers @@ -170,7 +91,7 @@ def generate_launch_description(): ]: load_controllers += [ ExecuteProcess( - cmd=["ros2 run controller_manager spawner.py {}".format(controller)], + cmd=["ros2 run controller_manager spawner {}".format(controller)], shell=True, output="screen", ) diff --git a/demo/launch/ik_clearance_cost.launch.py b/demo/launch/ik_clearance_cost.launch.py index e97f2a8ba..a2f2d7003 100644 --- a/demo/launch/ik_clearance_cost.launch.py +++ b/demo/launch/ik_clearance_cost.launch.py @@ -1,55 +1,27 @@ import os -import yaml + +from ament_index_python.packages import get_package_share_directory from launch import LaunchDescription from launch_ros.actions import Node -from ament_index_python.packages import get_package_share_directory - - -def load_file(package_name, file_path): - package_path = get_package_share_directory(package_name) - absolute_file_path = os.path.join(package_path, file_path) - - try: - with open(absolute_file_path, "r") as file: - return file.read() - except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available - return None - - -def load_yaml(package_name, file_path): - package_path = get_package_share_directory(package_name) - absolute_file_path = os.path.join(package_path, file_path) - - try: - with open(absolute_file_path, "r") as file: - return yaml.safe_load(file) - except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available - return None +from moveit_configs_utils import MoveItConfigsBuilder def generate_launch_description(): - # Get URDF and SRDF - robot_description_config = load_file( - "moveit_resources_panda_description", "urdf/panda.urdf" - ) - robot_description = {"robot_description": robot_description_config} - - robot_description_semantic_config = load_file( - "moveit_resources_panda_moveit_config", "config/panda.srdf" - ) - robot_description_semantic = { - "robot_description_semantic": robot_description_semantic_config - } - - kinematics_yaml = load_yaml( - "moveit_resources_panda_moveit_config", "config/kinematics.yaml" + moveit_config = ( + MoveItConfigsBuilder("moveit_resources_panda") + .robot_description(file_path="config/panda.urdf.xacro") + .to_moveit_configs() ) cartesian_task = Node( package="moveit_task_constructor_demo", executable="ik_clearance_cost", output="screen", - parameters=[robot_description, robot_description_semantic, kinematics_yaml], + parameters=[ + moveit_config.robot_description, + moveit_config.robot_description_semantic, + moveit_config.robot_description_kinematics, + ], ) return LaunchDescription([cartesian_task]) diff --git a/demo/launch/modular.launch.py b/demo/launch/modular.launch.py index 673dfe97e..a2372e800 100644 --- a/demo/launch/modular.launch.py +++ b/demo/launch/modular.launch.py @@ -1,55 +1,27 @@ import os -import yaml + +from ament_index_python.packages import get_package_share_directory from launch import LaunchDescription from launch_ros.actions import Node -from ament_index_python.packages import get_package_share_directory - - -def load_file(package_name, file_path): - package_path = get_package_share_directory(package_name) - absolute_file_path = os.path.join(package_path, file_path) - - try: - with open(absolute_file_path, "r") as file: - return file.read() - except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available - return None - - -def load_yaml(package_name, file_path): - package_path = get_package_share_directory(package_name) - absolute_file_path = os.path.join(package_path, file_path) - - try: - with open(absolute_file_path, "r") as file: - return yaml.safe_load(file) - except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available - return None +from moveit_configs_utils import MoveItConfigsBuilder def generate_launch_description(): - # Get URDF and SRDF - robot_description_config = load_file( - "moveit_resources_panda_description", "urdf/panda.urdf" - ) - robot_description = {"robot_description": robot_description_config} - - robot_description_semantic_config = load_file( - "moveit_resources_panda_moveit_config", "config/panda.srdf" - ) - robot_description_semantic = { - "robot_description_semantic": robot_description_semantic_config - } - - kinematics_yaml = load_yaml( - "moveit_resources_panda_moveit_config", "config/kinematics.yaml" + moveit_config = ( + MoveItConfigsBuilder("moveit_resources_panda") + .robot_description(file_path="config/panda.urdf.xacro") + .to_moveit_configs() ) modular_task = Node( package="moveit_task_constructor_demo", executable="modular", output="screen", - parameters=[robot_description, robot_description_semantic, kinematics_yaml], + parameters=[ + moveit_config.robot_description, + moveit_config.robot_description_semantic, + moveit_config.robot_description_kinematics, + ], ) return LaunchDescription([modular_task]) diff --git a/demo/launch/pickplace.launch.py b/demo/launch/pickplace.launch.py index ebf16e91a..d332dbdb4 100644 --- a/demo/launch/pickplace.launch.py +++ b/demo/launch/pickplace.launch.py @@ -1,62 +1,19 @@ import os -import yaml + +from ament_index_python.packages import get_package_share_directory from launch import LaunchDescription from launch_ros.actions import Node -from ament_index_python.packages import get_package_share_directory - - -def load_file(package_name, file_path): - package_path = get_package_share_directory(package_name) - absolute_file_path = os.path.join(package_path, file_path) - - try: - with open(absolute_file_path, "r") as file: - return file.read() - except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available - return None - - -def load_yaml(package_name, file_path): - package_path = get_package_share_directory(package_name) - absolute_file_path = os.path.join(package_path, file_path) - - try: - with open(absolute_file_path, "r") as file: - return yaml.safe_load(file) - except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available - return None +from moveit_configs_utils import MoveItConfigsBuilder def generate_launch_description(): - # Get URDF and SRDF - robot_description_config = load_file( - "moveit_resources_panda_description", "urdf/panda.urdf" - ) - robot_description = {"robot_description": robot_description_config} - - robot_description_semantic_config = load_file( - "moveit_resources_panda_moveit_config", "config/panda.srdf" - ) - robot_description_semantic = { - "robot_description_semantic": robot_description_semantic_config - } - - kinematics_yaml = load_yaml( - "moveit_resources_panda_moveit_config", "config/kinematics.yaml" - ) - - # Planning Functionality - ompl_planning_pipeline_config = { - "move_group": { - "planning_plugin": "ompl_interface/OMPLPlanner", - "request_adapters": """default_planner_request_adapters/AddTimeOptimalParameterization default_planner_request_adapters/FixWorkspaceBounds default_planner_request_adapters/FixStartStateBounds default_planner_request_adapters/FixStartStateCollision default_planner_request_adapters/FixStartStatePathConstraints""", - "start_state_max_bounds_error": 0.1, - } - } - ompl_planning_yaml = load_yaml( - "moveit_resources_panda_moveit_config", "config/ompl_planning.yaml" + moveit_config = ( + MoveItConfigsBuilder("moveit_resources_panda") + .planning_pipelines(pipelines=["ompl"]) + .robot_description(file_path="config/panda.urdf.xacro") + .trajectory_execution(file_path="config/gripper_moveit_controllers.yaml") + .to_moveit_configs() ) - ompl_planning_pipeline_config["move_group"].update(ompl_planning_yaml) pick_place_demo = Node( package="moveit_task_constructor_demo", @@ -68,10 +25,11 @@ def generate_launch_description(): "config", "panda_config.yaml", ), - robot_description, - robot_description_semantic, - kinematics_yaml, - ompl_planning_pipeline_config, + moveit_config.robot_description, + moveit_config.robot_description_semantic, + moveit_config.robot_description_kinematics, + moveit_config.planning_pipelines, + moveit_config.joint_limits, ], ) diff --git a/demo/package.xml b/demo/package.xml index b6530c093..6bc46923d 100644 --- a/demo/package.xml +++ b/demo/package.xml @@ -15,6 +15,7 @@ moveit_ros_planning_interface moveit_task_constructor_core rosparam_shortcuts + moveit_configs_utils moveit_resources_panda_moveit_config moveit_task_constructor_capabilities From 7ec00235e1474cbf1e9eabcde62e827662da5e91 Mon Sep 17 00:00:00 2001 From: JafarAbdi Date: Wed, 25 May 2022 14:20:57 +0000 Subject: [PATCH 2/5] Suppress unrelated asan errors --- .github/workflows/ci.yaml | 1 + .github/workflows/lsan.suppressions | 1 + 2 files changed, 2 insertions(+) diff --git a/.github/workflows/ci.yaml b/.github/workflows/ci.yaml index 49b3e4f0e..930f5ccc1 100644 --- a/.github/workflows/ci.yaml +++ b/.github/workflows/ci.yaml @@ -34,6 +34,7 @@ jobs: DOCKER_RUN_OPTS: >- -e PRELOAD=libasan.so.5 -e LSAN_OPTIONS="suppressions=$PWD/.github/workflows/lsan.suppressions,fast_unwind_on_malloc=0" + -e ASAN_OPTIONS="new_delete_type_mismatch=0,alloc_dealloc_mismatch=0" TARGET_CMAKE_ARGS: -DCMAKE_CXX_FLAGS="-fsanitize=address -fno-omit-frame-pointer -O1" env: diff --git a/.github/workflows/lsan.suppressions b/.github/workflows/lsan.suppressions index 79bf7e06c..27c07e6f4 100644 --- a/.github/workflows/lsan.suppressions +++ b/.github/workflows/lsan.suppressions @@ -1 +1,2 @@ leak:class_loader +leak:rviz_default_plugins From 95cdb77d28c251010f7190fe5acb56a1d16fb9e1 Mon Sep 17 00:00:00 2001 From: JafarAbdi Date: Wed, 25 May 2022 14:48:24 +0000 Subject: [PATCH 3/5] Suppress unrelated asan errors --- .github/workflows/lsan.suppressions | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/workflows/lsan.suppressions b/.github/workflows/lsan.suppressions index 27c07e6f4..3164a5a4e 100644 --- a/.github/workflows/lsan.suppressions +++ b/.github/workflows/lsan.suppressions @@ -1,2 +1,3 @@ leak:class_loader leak:rviz_default_plugins +leak:static_transform_broadcaster_node From b843f05ce6730499d23770cb9569a251a082acde Mon Sep 17 00:00:00 2001 From: JafarAbdi Date: Wed, 25 May 2022 14:54:48 +0000 Subject: [PATCH 4/5] Remove unused imports --- core/test/move_to.launch.py | 3 --- demo/launch/alternative_path_costs.launch.py | 3 --- demo/launch/cartesian.launch.py | 3 --- demo/launch/demo.launch.py | 1 - demo/launch/ik_clearance_cost.launch.py | 3 --- demo/launch/modular.launch.py | 3 --- 6 files changed, 16 deletions(-) diff --git a/core/test/move_to.launch.py b/core/test/move_to.launch.py index d563e7847..023283bea 100644 --- a/core/test/move_to.launch.py +++ b/core/test/move_to.launch.py @@ -1,15 +1,12 @@ -import os import unittest import launch_testing import pytest -from ament_index_python.packages import get_package_share_directory from launch import LaunchDescription from launch.actions import DeclareLaunchArgument from launch.substitutions import LaunchConfiguration from launch_ros.actions import Node from launch_testing.actions import ReadyToTest -from launch_testing.asserts import assertExitCodes from launch_testing.util import KeepAliveProc from moveit_configs_utils import MoveItConfigsBuilder diff --git a/demo/launch/alternative_path_costs.launch.py b/demo/launch/alternative_path_costs.launch.py index 3edd2343a..4e465dd49 100644 --- a/demo/launch/alternative_path_costs.launch.py +++ b/demo/launch/alternative_path_costs.launch.py @@ -1,6 +1,3 @@ -import os - -from ament_index_python.packages import get_package_share_directory from launch import LaunchDescription from launch_ros.actions import Node from moveit_configs_utils import MoveItConfigsBuilder diff --git a/demo/launch/cartesian.launch.py b/demo/launch/cartesian.launch.py index b3b6e9d48..fe2db9ac0 100644 --- a/demo/launch/cartesian.launch.py +++ b/demo/launch/cartesian.launch.py @@ -1,6 +1,3 @@ -import os - -from ament_index_python.packages import get_package_share_directory from launch import LaunchDescription from launch_ros.actions import Node from moveit_configs_utils import MoveItConfigsBuilder diff --git a/demo/launch/demo.launch.py b/demo/launch/demo.launch.py index 6785ea9a4..a757a7d65 100644 --- a/demo/launch/demo.launch.py +++ b/demo/launch/demo.launch.py @@ -1,6 +1,5 @@ import os -import xacro from ament_index_python.packages import get_package_share_directory from launch import LaunchDescription from launch.actions import ExecuteProcess diff --git a/demo/launch/ik_clearance_cost.launch.py b/demo/launch/ik_clearance_cost.launch.py index a2f2d7003..9d2b826db 100644 --- a/demo/launch/ik_clearance_cost.launch.py +++ b/demo/launch/ik_clearance_cost.launch.py @@ -1,6 +1,3 @@ -import os - -from ament_index_python.packages import get_package_share_directory from launch import LaunchDescription from launch_ros.actions import Node from moveit_configs_utils import MoveItConfigsBuilder diff --git a/demo/launch/modular.launch.py b/demo/launch/modular.launch.py index a2372e800..a4bd7bb2e 100644 --- a/demo/launch/modular.launch.py +++ b/demo/launch/modular.launch.py @@ -1,6 +1,3 @@ -import os - -from ament_index_python.packages import get_package_share_directory from launch import LaunchDescription from launch_ros.actions import Node from moveit_configs_utils import MoveItConfigsBuilder From b7fc895be06f8043191a62a911bba6c02a1ce770 Mon Sep 17 00:00:00 2001 From: JafarAbdi Date: Wed, 25 May 2022 15:02:35 +0000 Subject: [PATCH 5/5] Add humble CI --- .github/workflows/ci.yaml | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/.github/workflows/ci.yaml b/.github/workflows/ci.yaml index 930f5ccc1..c37d6caf2 100644 --- a/.github/workflows/ci.yaml +++ b/.github/workflows/ci.yaml @@ -15,6 +15,10 @@ jobs: matrix: env: # TODO: We have to use -Wno-redundant-decls since rosidl_generator_c is generating broken headers + - IMAGE: humble-source + CXXFLAGS: >- + -Werror -Wall -Wextra -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wno-redundant-decls + -Wno-unused-parameter -Wno-unused-function -Wno-deprecated-copy -Wno-unused-but-set-parameter - IMAGE: rolling-source NAME: ccov TARGET_CMAKE_ARGS: -DCMAKE_BUILD_TYPE=Debug -DCMAKE_CXX_FLAGS="--coverage"