diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp index 360e8f24d6..bc67a84f13 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp @@ -80,7 +80,7 @@ bool BtActionServer::on_configure() auto options = rclcpp::NodeOptions().arguments( {"--ros-args", "-r", - std::string("__node:=") + std::string(node->get_name()) + client_node_name + "_rclcpp_node", + std::string("__node:=") + std::string(node->get_name()) + "_" + client_node_name + "_rclcpp_node", "--"}); // Support for handling the topic-based goal pose from rviz diff --git a/nav2_bringup/params/nav2_multirobot_params_1.yaml b/nav2_bringup/params/nav2_multirobot_params_1.yaml index dc6317f587..88bebc3590 100644 --- a/nav2_bringup/params/nav2_multirobot_params_1.yaml +++ b/nav2_bringup/params/nav2_multirobot_params_1.yaml @@ -39,14 +39,6 @@ amcl: z_short: 0.05 scan_topic: scan -amcl_map_client: - ros__parameters: - use_sim_time: True - -amcl_rclcpp_node: - ros__parameters: - use_sim_time: True - bt_navigator: ros__parameters: use_sim_time: True @@ -104,7 +96,11 @@ bt_navigator: - nav2_back_up_cancel_bt_node - nav2_drive_on_heading_cancel_bt_node -bt_navigator_rclcpp_node: +bt_navigator_navigate_through_poses_rclcpp_node: + ros__parameters: + use_sim_time: True + +bt_navigator_navigate_to_pose_rclcpp_node: ros__parameters: use_sim_time: True @@ -170,10 +166,6 @@ controller_server: RotateToGoal.slowing_factor: 5.0 RotateToGoal.lookahead_time: -1.0 -controller_server_rclcpp_node: - ros__parameters: - use_sim_time: True - local_costmap: local_costmap: ros__parameters: @@ -205,12 +197,6 @@ local_costmap: map_subscribe_transient_local: True always_send_full_costmap: True observation_sources: scan - local_costmap_client: - ros__parameters: - use_sim_time: True - local_costmap_rclcpp_node: - ros__parameters: - use_sim_time: True global_costmap: global_costmap: @@ -232,12 +218,6 @@ global_costmap: map_subscribe_transient_local: True always_send_full_costmap: True observation_sources: scan - global_costmap_client: - ros__parameters: - use_sim_time: True - global_costmap_rclcpp_node: - ros__parameters: - use_sim_time: True map_server: ros__parameters: @@ -255,10 +235,6 @@ planner_server: use_astar: false allow_unknown: true -planner_server_rclcpp_node: - ros__parameters: - use_sim_time: True - smoother_server: ros__parameters: use_sim_time: True diff --git a/nav2_bringup/params/nav2_multirobot_params_2.yaml b/nav2_bringup/params/nav2_multirobot_params_2.yaml index f48886c906..7ec0f1edda 100644 --- a/nav2_bringup/params/nav2_multirobot_params_2.yaml +++ b/nav2_bringup/params/nav2_multirobot_params_2.yaml @@ -39,14 +39,6 @@ amcl: z_short: 0.05 scan_topic: scan -amcl_map_client: - ros__parameters: - use_sim_time: True - -amcl_rclcpp_node: - ros__parameters: - use_sim_time: True - bt_navigator: ros__parameters: use_sim_time: True @@ -104,7 +96,11 @@ bt_navigator: - nav2_back_up_cancel_bt_node - nav2_drive_on_heading_cancel_bt_node -bt_navigator_rclcpp_node: +bt_navigator_navigate_through_poses_rclcpp_node: + ros__parameters: + use_sim_time: True + +bt_navigator_navigate_to_pose_rclcpp_node: ros__parameters: use_sim_time: True @@ -170,10 +166,6 @@ controller_server: RotateToGoal.slowing_factor: 5.0 RotateToGoal.lookahead_time: -1.0 -controller_server_rclcpp_node: - ros__parameters: - use_sim_time: True - local_costmap: local_costmap: ros__parameters: @@ -205,12 +197,6 @@ local_costmap: map_subscribe_transient_local: True always_send_full_costmap: True observation_sources: scan - local_costmap_client: - ros__parameters: - use_sim_time: True - local_costmap_rclcpp_node: - ros__parameters: - use_sim_time: True global_costmap: global_costmap: @@ -232,12 +218,6 @@ global_costmap: map_subscribe_transient_local: True always_send_full_costmap: True observation_sources: scan - global_costmap_client: - ros__parameters: - use_sim_time: True - global_costmap_rclcpp_node: - ros__parameters: - use_sim_time: True map_server: ros__parameters: @@ -255,10 +235,6 @@ planner_server: use_astar: false allow_unknown: true -planner_server_rclcpp_node: - ros__parameters: - use_sim_time: True - smoother_server: ros__parameters: use_sim_time: True diff --git a/nav2_bringup/params/nav2_params.yaml b/nav2_bringup/params/nav2_params.yaml index 3705004f1b..4b573c778c 100644 --- a/nav2_bringup/params/nav2_params.yaml +++ b/nav2_bringup/params/nav2_params.yaml @@ -39,14 +39,6 @@ amcl: z_short: 0.05 scan_topic: scan -amcl_map_client: - ros__parameters: - use_sim_time: True - -amcl_rclcpp_node: - ros__parameters: - use_sim_time: True - bt_navigator: ros__parameters: use_sim_time: True @@ -104,7 +96,11 @@ bt_navigator: - nav2_back_up_cancel_bt_node - nav2_drive_on_heading_cancel_bt_node -bt_navigator_rclcpp_node: +bt_navigator_navigate_through_poses_rclcpp_node: + ros__parameters: + use_sim_time: True + +bt_navigator_navigate_to_pose_rclcpp_node: ros__parameters: use_sim_time: True @@ -179,10 +175,6 @@ controller_server: RotateToGoal.slowing_factor: 5.0 RotateToGoal.lookahead_time: -1.0 -controller_server_rclcpp_node: - ros__parameters: - use_sim_time: True - local_costmap: local_costmap: ros__parameters: @@ -224,12 +216,6 @@ local_costmap: static_layer: map_subscribe_transient_local: True always_send_full_costmap: True - local_costmap_client: - ros__parameters: - use_sim_time: True - local_costmap_rclcpp_node: - ros__parameters: - use_sim_time: True global_costmap: global_costmap: @@ -265,12 +251,6 @@ global_costmap: cost_scaling_factor: 3.0 inflation_radius: 0.55 always_send_full_costmap: True - global_costmap_client: - ros__parameters: - use_sim_time: True - global_costmap_rclcpp_node: - ros__parameters: - use_sim_time: True map_server: ros__parameters: @@ -296,10 +276,6 @@ planner_server: use_astar: false allow_unknown: true -planner_server_rclcpp_node: - ros__parameters: - use_sim_time: True - smoother_server: ros__parameters: use_sim_time: True diff --git a/nav2_system_tests/src/costmap_filters/keepout_params.yaml b/nav2_system_tests/src/costmap_filters/keepout_params.yaml index de3722edfe..c068d67ff9 100644 --- a/nav2_system_tests/src/costmap_filters/keepout_params.yaml +++ b/nav2_system_tests/src/costmap_filters/keepout_params.yaml @@ -39,14 +39,6 @@ amcl: z_short: 0.05 scan_topic: scan -amcl_map_client: - ros__parameters: - use_sim_time: True - -amcl_rclcpp_node: - ros__parameters: - use_sim_time: True - bt_navigator: ros__parameters: use_sim_time: True @@ -97,7 +89,11 @@ bt_navigator: - nav2_back_up_cancel_bt_node - nav2_drive_on_heading_cancel_bt_node -bt_navigator_rclcpp_node: +bt_navigator_navigate_through_poses_rclcpp_node: + ros__parameters: + use_sim_time: True + +bt_navigator_navigate_to_pose_rclcpp_node: ros__parameters: use_sim_time: True @@ -167,11 +163,6 @@ controller_server: RotateToGoal.lookahead_time: -1.0 publish_cost_grid_pc: True - -controller_server_rclcpp_node: - ros__parameters: - use_sim_time: True - local_costmap: local_costmap: ros__parameters: @@ -218,12 +209,6 @@ local_costmap: enabled: True filter_info_topic: "/costmap_filter_info" always_send_full_costmap: True - local_costmap_client: - ros__parameters: - use_sim_time: True - local_costmap_rclcpp_node: - ros__parameters: - use_sim_time: True global_costmap: global_costmap: @@ -260,12 +245,6 @@ global_costmap: enabled: True filter_info_topic: "/costmap_filter_info" always_send_full_costmap: True - global_costmap_client: - ros__parameters: - use_sim_time: True - global_costmap_rclcpp_node: - ros__parameters: - use_sim_time: True map_server: ros__parameters: @@ -291,10 +270,6 @@ planner_server: use_astar: False allow_unknown: True -planner_server_rclcpp_node: - ros__parameters: - use_sim_time: True - smoother_server: ros__parameters: use_sim_time: True diff --git a/nav2_system_tests/src/costmap_filters/speed_global_params.yaml b/nav2_system_tests/src/costmap_filters/speed_global_params.yaml index 11a8f80551..f4fa961a3d 100644 --- a/nav2_system_tests/src/costmap_filters/speed_global_params.yaml +++ b/nav2_system_tests/src/costmap_filters/speed_global_params.yaml @@ -39,14 +39,6 @@ amcl: z_short: 0.05 scan_topic: scan -amcl_map_client: - ros__parameters: - use_sim_time: True - -amcl_rclcpp_node: - ros__parameters: - use_sim_time: True - bt_navigator: ros__parameters: use_sim_time: True @@ -98,7 +90,11 @@ bt_navigator: - nav2_back_up_cancel_bt_node - nav2_drive_on_heading_cancel_bt_node -bt_navigator_rclcpp_node: +bt_navigator_navigate_through_poses_rclcpp_node: + ros__parameters: + use_sim_time: True + +bt_navigator_navigate_to_pose_rclcpp_node: ros__parameters: use_sim_time: True @@ -168,10 +164,6 @@ controller_server: RotateToGoal.slowing_factor: 5.0 RotateToGoal.lookahead_time: -1.0 -controller_server_rclcpp_node: - ros__parameters: - use_sim_time: True - local_costmap: local_costmap: ros__parameters: @@ -209,12 +201,6 @@ local_costmap: static_layer: map_subscribe_transient_local: True always_send_full_costmap: True - local_costmap_client: - ros__parameters: - use_sim_time: True - local_costmap_rclcpp_node: - ros__parameters: - use_sim_time: True global_costmap: global_costmap: @@ -252,12 +238,6 @@ global_costmap: filter_info_topic: "/costmap_filter_info" speed_limit_topic: "/speed_limit" always_send_full_costmap: True - global_costmap_client: - ros__parameters: - use_sim_time: True - global_costmap_rclcpp_node: - ros__parameters: - use_sim_time: True map_server: ros__parameters: @@ -283,10 +263,6 @@ planner_server: use_astar: False allow_unknown: True -planner_server_rclcpp_node: - ros__parameters: - use_sim_time: True - smoother_server: ros__parameters: use_sim_time: True diff --git a/nav2_system_tests/src/costmap_filters/speed_local_params.yaml b/nav2_system_tests/src/costmap_filters/speed_local_params.yaml index 413cff5ce1..df05269447 100644 --- a/nav2_system_tests/src/costmap_filters/speed_local_params.yaml +++ b/nav2_system_tests/src/costmap_filters/speed_local_params.yaml @@ -39,14 +39,6 @@ amcl: z_short: 0.05 scan_topic: scan -amcl_map_client: - ros__parameters: - use_sim_time: True - -amcl_rclcpp_node: - ros__parameters: - use_sim_time: True - bt_navigator: ros__parameters: use_sim_time: True @@ -98,7 +90,11 @@ bt_navigator: - nav2_back_up_cancel_bt_node - nav2_drive_on_heading_cancel_bt_node -bt_navigator_rclcpp_node: +bt_navigator_navigate_through_poses_rclcpp_node: + ros__parameters: + use_sim_time: True + +bt_navigator_navigate_to_pose_rclcpp_node: ros__parameters: use_sim_time: True @@ -168,10 +164,6 @@ controller_server: RotateToGoal.slowing_factor: 5.0 RotateToGoal.lookahead_time: -1.0 -controller_server_rclcpp_node: - ros__parameters: - use_sim_time: True - local_costmap: local_costmap: ros__parameters: @@ -215,12 +207,6 @@ local_costmap: filter_info_topic: "/costmap_filter_info" speed_limit_topic: "/speed_limit" always_send_full_costmap: True - local_costmap_client: - ros__parameters: - use_sim_time: True - local_costmap_rclcpp_node: - ros__parameters: - use_sim_time: True global_costmap: global_costmap: @@ -252,12 +238,6 @@ global_costmap: cost_scaling_factor: 3.0 inflation_radius: 0.55 always_send_full_costmap: True - global_costmap_client: - ros__parameters: - use_sim_time: True - global_costmap_rclcpp_node: - ros__parameters: - use_sim_time: True map_server: ros__parameters: @@ -283,10 +263,6 @@ planner_server: use_astar: False allow_unknown: True -planner_server_rclcpp_node: - ros__parameters: - use_sim_time: True - smoother_server: ros__parameters: use_sim_time: True