File tree Expand file tree Collapse file tree 2 files changed +7
-7
lines changed
nav2_bt_navigator/src/navigators Expand file tree Collapse file tree 2 files changed +7
-7
lines changed Original file line number Diff line number Diff line change @@ -31,11 +31,11 @@ NavigateThroughPosesNavigator::configure(
31
31
auto node = parent_node.lock ();
32
32
33
33
goals_blackboard_id_ =
34
- node->declare_or_get_parameter (" goals_blackboard_id" , std::string (" goals" ));
34
+ node->declare_or_get_parameter (getName () + " . goals_blackboard_id" , std::string (" goals" ));
35
35
path_blackboard_id_ =
36
- node->declare_or_get_parameter (" path_blackboard_id" , std::string (" path" ));
36
+ node->declare_or_get_parameter (getName () + " . path_blackboard_id" , std::string (" path" ));
37
37
waypoint_statuses_blackboard_id_ =
38
- node->declare_or_get_parameter (" waypoint_statuses_blackboard_id" ,
38
+ node->declare_or_get_parameter (getName () + " . waypoint_statuses_blackboard_id" ,
39
39
std::string (" waypoint_statuses" ));
40
40
41
41
// Odometry smoother object for getting current speed
Original file line number Diff line number Diff line change @@ -29,10 +29,10 @@ NavigateToPoseNavigator::configure(
29
29
start_time_ = rclcpp::Time (0 );
30
30
auto node = parent_node.lock ();
31
31
32
- goal_blackboard_id_ =
33
- node-> declare_or_get_parameter ( " goal_blackboard_id " , std::string (" goal" ));
34
- path_blackboard_id_ =
35
- node-> declare_or_get_parameter ( " path_blackboard_id " , std::string (" path" ));
32
+ goal_blackboard_id_ = node-> declare_or_get_parameter ( getName () + " .goal_blackboard_id " ,
33
+ std::string (" goal" ));
34
+ path_blackboard_id_ = node-> declare_or_get_parameter ( getName () + " .path_blackboard_id " ,
35
+ std::string (" path" ));
36
36
37
37
// Odometry smoother object for getting current speed
38
38
odom_smoother_ = odom_smoother;
You can’t perform that action at this time.
0 commit comments