Skip to content

Commit

Permalink
Address review feedback
Browse files Browse the repository at this point in the history
Signed-off-by: Luca Della Vedova <[email protected]>
  • Loading branch information
luca-della-vedova committed Nov 21, 2024
1 parent 857b610 commit ac5d861
Show file tree
Hide file tree
Showing 6 changed files with 24 additions and 23 deletions.
12 changes: 12 additions & 0 deletions nav2_bringup/params/nav2_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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
Expand Down
12 changes: 0 additions & 12 deletions nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
1 change: 1 addition & 0 deletions nav2_costmap_2d/include/nav2_costmap_2d/costmap_layer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
*/
Expand Down
6 changes: 0 additions & 6 deletions nav2_costmap_2d/src/costmap_2d_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down
12 changes: 9 additions & 3 deletions nav2_dwb_controller/dwb_critics/test/obstacle_footprint_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<nav2_costmap_2d::Costmap2DROS>("test_global_costmap", ns);
std::string costmap_name = "test_global_costmap";
auto costmap_ros =
std::make_shared<nav2_costmap_2d::Costmap2DROS>(costmap_name, ns, costmap_name, false);
costmap_ros->configure();

std::string name = "name";
Expand Down Expand Up @@ -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<nav2_costmap_2d::Costmap2DROS>("test_global_costmap", ns);
std::string costmap_name = "test_global_costmap";
auto costmap_ros =
std::make_shared<nav2_costmap_2d::Costmap2DROS>(costmap_name, ns, costmap_name, false);
costmap_ros->configure();

std::string name = "name";
Expand All @@ -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<nav2_costmap_2d::Costmap2DROS>("test_global_costmap", ns);
std::string costmap_name = "test_global_costmap";
auto costmap_ros =
std::make_shared<nav2_costmap_2d::Costmap2DROS>(costmap_name, ns, costmap_name, false);
costmap_ros->configure();

std::string name = "name";
Expand Down
4 changes: 2 additions & 2 deletions nav2_system_tests/src/system/test_multi_robot_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down

0 comments on commit ac5d861

Please sign in to comment.