@@ -70,8 +70,8 @@ Costmap2DROS::Costmap2DROS(const rclcpp::NodeOptions & options)
7070 " nav2_costmap_2d::ObstacleLayer" ,
7171 " nav2_costmap_2d::InflationLayer" }
7272{
73- declare_parameter (" map_topic" , rclcpp::ParameterValue (std::string (" map" )));
7473 is_lifecycle_follower_ = false ;
74+ declare_parameter (" __parent_namespace" , std::string (get_namespace ()));
7575 init ();
7676}
7777
@@ -99,9 +99,7 @@ Costmap2DROS::Costmap2DROS(
9999 " nav2_costmap_2d::ObstacleLayer" ,
100100 " nav2_costmap_2d::InflationLayer" }
101101{
102- declare_parameter (
103- " map_topic" , rclcpp::ParameterValue (
104- (parent_namespace_ == " /" ? " /" : parent_namespace_ + " /" ) + std::string (" map" )));
102+ declare_parameter (" __parent_namespace" , parent_namespace);
105103 init ();
106104}
107105
@@ -114,6 +112,7 @@ void Costmap2DROS::init()
114112 declare_parameter (" footprint_padding" , rclcpp::ParameterValue (0 .01f ));
115113 declare_parameter (" footprint" , rclcpp::ParameterValue (std::string (" []" )));
116114 declare_parameter (" global_frame" , rclcpp::ParameterValue (std::string (" map" )));
115+ declare_parameter (" map_topic" , rclcpp::ParameterValue (std::string (" map" )));
117116 declare_parameter (" height" , rclcpp::ParameterValue (5 ));
118117 declare_parameter (" width" , rclcpp::ParameterValue (5 ));
119118 declare_parameter (" lethal_cost_threshold" , rclcpp::ParameterValue (100 ));
0 commit comments