Skip to content

Commit

Permalink
Use private parameter for parent namespace
Browse files Browse the repository at this point in the history
Signed-off-by: Luca Della Vedova <lucadv@intrinsic.ai>
  • Loading branch information
luca-della-vedova committed Nov 25, 2024
1 parent 745af36 commit f66d9a9
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 7 deletions.
7 changes: 3 additions & 4 deletions nav2_costmap_2d/src/costmap_2d_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,8 +70,8 @@ Costmap2DROS::Costmap2DROS(const rclcpp::NodeOptions & options)
"nav2_costmap_2d::ObstacleLayer",
"nav2_costmap_2d::InflationLayer"}
{
declare_parameter("map_topic", rclcpp::ParameterValue(std::string("map")));
is_lifecycle_follower_ = false;
declare_parameter("__parent_namespace", std::string(get_namespace()));
init();
}

Expand Down Expand Up @@ -99,9 +99,7 @@ Costmap2DROS::Costmap2DROS(
"nav2_costmap_2d::ObstacleLayer",
"nav2_costmap_2d::InflationLayer"}
{
declare_parameter(
"map_topic", rclcpp::ParameterValue(
(parent_namespace_ == "/" ? "/" : parent_namespace_ + "/") + std::string("map")));
declare_parameter("__parent_namespace", parent_namespace);
init();
}

Expand All @@ -114,6 +112,7 @@ void Costmap2DROS::init()
declare_parameter("footprint_padding", rclcpp::ParameterValue(0.01f));
declare_parameter("footprint", rclcpp::ParameterValue(std::string("[]")));
declare_parameter("global_frame", rclcpp::ParameterValue(std::string("map")));
declare_parameter("map_topic", rclcpp::ParameterValue(std::string("map")));
declare_parameter("height", rclcpp::ParameterValue(5));
declare_parameter("width", rclcpp::ParameterValue(5));
declare_parameter("lethal_cost_threshold", rclcpp::ParameterValue(100));
Expand Down
10 changes: 7 additions & 3 deletions nav2_costmap_2d/src/costmap_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -273,9 +273,13 @@ std::string CostmapLayer::joinWithParentNamespace(const std::string & topic)
}

if (topic[0] != '/') {
std::string node_namespace = node->get_namespace();
std::string parent_namespace = node_namespace.substr(0, node_namespace.rfind("/"));
return parent_namespace + "/" + topic;
auto parent_param = node->get_parameter("__parent_namespace");
if (parent_param.get_type() != rclcpp::ParameterType::PARAMETER_STRING)
{
throw std::runtime_error{"__parent_namespace parameter not found or wrong type"};
}
auto parent_ns = parent_param.as_string();
return (parent_ns == "/" ? "/" : parent_ns + "/") + topic;
}

return topic;
Expand Down

0 comments on commit f66d9a9

Please sign in to comment.