Skip to content

Commit

Permalink
change parameter names to be inside the plugin instance's namespace
Browse files Browse the repository at this point in the history
  • Loading branch information
Cakem1x committed Jan 24, 2024
1 parent f7e40de commit c0c0927
Showing 1 changed file with 4 additions and 4 deletions.
8 changes: 4 additions & 4 deletions dijkstra_mesh_planner/src/dijkstra_mesh_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -132,17 +132,17 @@ bool DijkstraMeshPlanner::initialize(const std::string& plugin_name, const std::
map_frame_ = mesh_map_->mapFrame();
node_ = node;

config_.publish_vector_field = node_->declare_parameter("publish_vector_field", config_.publish_vector_field);
config_.publish_face_vectors = node_->declare_parameter("publish_face_vectors", config_.publish_face_vectors);
config_.goal_dist_offset = node->declare_parameter("goal_dist_offset", config_.goal_dist_offset);
config_.publish_vector_field = node_->declare_parameter(name_ + ".publish_vector_field", config_.publish_vector_field);
config_.publish_face_vectors = node_->declare_parameter(name_ + ".publish_face_vectors", config_.publish_face_vectors);
config_.goal_dist_offset = node->declare_parameter(name_ + ".goal_dist_offset", config_.goal_dist_offset);
{ // cost limit param
rcl_interfaces::msg::ParameterDescriptor descriptor;
descriptor.description = "Defines the vertex cost limit with which it can be accessed.";
rcl_interfaces::msg::FloatingPointRange range;
range.from_value = 0.0;
range.to_value = 10.0;
descriptor.floating_point_range.push_back(range);
config_.cost_limit = node->declare_parameter("cost_limit", config_.cost_limit);
config_.cost_limit = node->declare_parameter(name_ + ".cost_limit", config_.cost_limit);
}

path_pub_ = node_->create_publisher<nav_msgs::msg::Path>("~/path", rclcpp::QoS(1).transient_local());
Expand Down

0 comments on commit c0c0927

Please sign in to comment.