Skip to content

Commit 89bceb7

Browse files
authored
add getRobotRadius() in costmap_2d_ros (#2896)
1 parent 4234a6e commit 89bceb7

File tree

1 file changed

+8
-0
lines changed

1 file changed

+8
-0
lines changed

‎nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp‎

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -294,6 +294,14 @@ class Costmap2DROS : public nav2_util::LifecycleNode
294294
*/
295295
bool getUseRadius() {return use_radius_;}
296296

297+
/**
298+
* @brief Get the costmap's robot_radius_ parameter, corresponding to
299+
* raidus of the robot footprint when it is defined as as circle
300+
* (i.e. when use_radius_ == true).
301+
* @return robot_radius_
302+
*/
303+
double getRobotRadius() {return robot_radius_;}
304+
297305
protected:
298306
rclcpp::Node::SharedPtr client_node_;
299307

0 commit comments

Comments
 (0)