Skip to content

Commit

Permalink
Add alternative API for costmap construction
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 20, 2024
1 parent e0b4089 commit 857b610
Show file tree
Hide file tree
Showing 3 changed files with 23 additions and 7 deletions.
12 changes: 12 additions & 0 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,6 +89,18 @@ 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
6 changes: 6 additions & 0 deletions nav2_costmap_2d/src/costmap_2d_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,6 +75,12 @@ 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: 5 additions & 7 deletions nav2_dwb_controller/dwb_critics/test/obstacle_footprint_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -125,10 +125,8 @@ TEST(ObstacleFootprint, Prepare)

auto node = nav2_util::LifecycleNode::make_shared("costmap_tester");

std::string costmap_name = "test_global_costmap";
std::string ns = "/ns";
auto costmap_ros =
std::make_shared<nav2_costmap_2d::Costmap2DROS>(costmap_name, ns, costmap_name, false);
auto costmap_ros = std::make_shared<nav2_costmap_2d::Costmap2DROS>("test_global_costmap", ns);
costmap_ros->configure();

std::string name = "name";
Expand Down Expand Up @@ -187,11 +185,11 @@ TEST(ObstacleFootprint, PointCost)

auto node = nav2_util::LifecycleNode::make_shared("costmap_tester");

auto costmap_ros = std::make_shared<nav2_costmap_2d::Costmap2DROS>("test_global_costmap");
std::string ns = "/ns";
auto costmap_ros = std::make_shared<nav2_costmap_2d::Costmap2DROS>("test_global_costmap", ns);
costmap_ros->configure();

std::string name = "name";
std::string ns = "ns";
critic->initialize(node, name, ns, costmap_ros);

costmap_ros->getCostmap()->setCost(0, 0, nav2_costmap_2d::LETHAL_OBSTACLE);
Expand All @@ -210,11 +208,11 @@ TEST(ObstacleFootprint, LineCost)

auto node = nav2_util::LifecycleNode::make_shared("costmap_tester");

auto costmap_ros = std::make_shared<nav2_costmap_2d::Costmap2DROS>("test_global_costmap");
std::string ns = "/ns";
auto costmap_ros = std::make_shared<nav2_costmap_2d::Costmap2DROS>("test_global_costmap", ns);
costmap_ros->configure();

std::string name = "name";
std::string ns = "ns";
critic->initialize(node, name, ns, costmap_ros);

costmap_ros->getCostmap()->setCost(3, 3, nav2_costmap_2d::LETHAL_OBSTACLE);
Expand Down

0 comments on commit 857b610

Please sign in to comment.