diff --git a/nav2_bringup/params/nav2_params.yaml b/nav2_bringup/params/nav2_params.yaml index b0e2fbf2f6f..6bd51ac11bf 100644 --- a/nav2_bringup/params/nav2_params.yaml +++ b/nav2_bringup/params/nav2_params.yaml @@ -211,6 +211,12 @@ local_costmap: mark_threshold: 0 observation_sources: scan scan: + # A relative topic will be appended to the parent of the local_costmap namespace. + # For example: + # * User chosen namespace is `tb4`. + # * User chosen topic is `scan`. + # * Topic will be remapped to `/tb4/scan` without `local_costmap`. + # * Use global topic `/scan` if you do not wish the node namespace to apply topic: scan max_obstacle_height: 2.0 clearing: True @@ -241,6 +247,12 @@ global_costmap: enabled: True observation_sources: scan scan: + # A relative topic will be appended to the parent of the global_costmap namespace. + # For example: + # * User chosen namespace is `tb4`. + # * User chosen topic is `scan`. + # * Topic will be remapped to `/tb4/scan` without `global_costmap`. + # * Use global topic `/scan` if you do not wish the node namespace to apply topic: scan max_obstacle_height: 2.0 clearing: True diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp index 3a4b00cc3c8..33feaa700df 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp @@ -89,18 +89,6 @@ class Costmap2DROS : public nav2_util::LifecycleNode */ explicit Costmap2DROS(const std::string & name, const bool & use_sim_time = false); - /** - * @brief Constructor for the wrapper, the node will - * be placed in a namespace equal to the parent_namespace and the node's name - * @param name Name of the costmap ROS node - * @param name Absolute namespace of the node hosting the costmap node - * @param use_sim_time Whether to use simulation or real time - */ - explicit Costmap2DROS( - const std::string & name, - const std::string & parent_namespace, - const bool & use_sim_time = false); - /** * @brief Constructor for the wrapper * @param name Name of the costmap ROS node diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_layer.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_layer.hpp index 8cd4fac4d5d..34f0314b76d 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_layer.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_layer.hpp @@ -206,6 +206,7 @@ class CostmapLayer : public Layer, public Costmap2D * * Costmap node namespace will be `/tb4/global_costmap`. * * Without this function, the topic would be `/tb4/global_costmap/scan`. * * With this function, topic will be remapped to `/tb4/scan`. + * Use global topic `/scan` if you do not wish the node namespace to apply * * @param topic the topic to parse */ diff --git a/nav2_costmap_2d/src/costmap_2d_ros.cpp b/nav2_costmap_2d/src/costmap_2d_ros.cpp index 2e48c25d57d..fa11b60ebfe 100644 --- a/nav2_costmap_2d/src/costmap_2d_ros.cpp +++ b/nav2_costmap_2d/src/costmap_2d_ros.cpp @@ -75,12 +75,6 @@ Costmap2DROS::Costmap2DROS(const rclcpp::NodeOptions & options) init(); } -Costmap2DROS::Costmap2DROS( - const std::string & name, - const std::string & parent_namespace, - const bool & use_sim_time) -: Costmap2DROS(name, parent_namespace, name, use_sim_time) {} - Costmap2DROS::Costmap2DROS( const std::string & name, const std::string & parent_namespace, diff --git a/nav2_dwb_controller/dwb_critics/test/obstacle_footprint_test.cpp b/nav2_dwb_controller/dwb_critics/test/obstacle_footprint_test.cpp index 6013dd4ea90..77a1d56e17d 100644 --- a/nav2_dwb_controller/dwb_critics/test/obstacle_footprint_test.cpp +++ b/nav2_dwb_controller/dwb_critics/test/obstacle_footprint_test.cpp @@ -126,7 +126,9 @@ TEST(ObstacleFootprint, Prepare) auto node = nav2_util::LifecycleNode::make_shared("costmap_tester"); std::string ns = "/ns"; - auto costmap_ros = std::make_shared("test_global_costmap", ns); + std::string costmap_name = "test_global_costmap"; + auto costmap_ros = + std::make_shared(costmap_name, ns, costmap_name, false); costmap_ros->configure(); std::string name = "name"; @@ -186,7 +188,9 @@ TEST(ObstacleFootprint, PointCost) auto node = nav2_util::LifecycleNode::make_shared("costmap_tester"); std::string ns = "/ns"; - auto costmap_ros = std::make_shared("test_global_costmap", ns); + std::string costmap_name = "test_global_costmap"; + auto costmap_ros = + std::make_shared(costmap_name, ns, costmap_name, false); costmap_ros->configure(); std::string name = "name"; @@ -209,7 +213,9 @@ TEST(ObstacleFootprint, LineCost) auto node = nav2_util::LifecycleNode::make_shared("costmap_tester"); std::string ns = "/ns"; - auto costmap_ros = std::make_shared("test_global_costmap", ns); + std::string costmap_name = "test_global_costmap"; + auto costmap_ros = + std::make_shared(costmap_name, ns, costmap_name, false); costmap_ros->configure(); std::string name = "name"; diff --git a/nav2_system_tests/src/system/test_multi_robot_launch.py b/nav2_system_tests/src/system/test_multi_robot_launch.py index 92f9a912dfd..87c7bb671e0 100755 --- a/nav2_system_tests/src/system/test_multi_robot_launch.py +++ b/nav2_system_tests/src/system/test_multi_robot_launch.py @@ -47,10 +47,10 @@ def generate_launch_description(): bringup_dir = get_package_share_directory('nav2_bringup') robot1_params_file = os.path.join( # noqa: F841 - bringup_dir, 'params/nav2_multirobot_params_1.yaml' + bringup_dir, 'params/nav2_params.yaml' ) robot2_params_file = os.path.join( # noqa: F841 - bringup_dir, 'params/nav2_multirobot_params_2.yaml' + bringup_dir, 'params/nav2_params.yaml' ) # Names and poses of the robots