Skip to content

Commit

Permalink
nav2_bt_navigator: log current location on navigate_to_pose action in…
Browse files Browse the repository at this point in the history
…itialization (#3720)

It is very useful to know the current location considered by the
bt_navigator for debug purposes.
  • Loading branch information
DylanDeCoeyer-Quimesis authored and SteveMacenski committed Aug 4, 2023
1 parent fb1e12c commit 6736448
Showing 1 changed file with 8 additions and 1 deletion.
9 changes: 8 additions & 1 deletion nav2_bt_navigator/src/navigators/navigate_to_pose.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -203,8 +203,15 @@ NavigateToPoseNavigator::onPreempt(ActionT::Goal::ConstSharedPtr goal)
void
NavigateToPoseNavigator::initializeGoalPose(ActionT::Goal::ConstSharedPtr goal)
{
geometry_msgs::msg::PoseStamped current_pose;
nav2_util::getCurrentPose(
current_pose, *feedback_utils_.tf,
feedback_utils_.global_frame, feedback_utils_.robot_frame,
feedback_utils_.transform_tolerance);

RCLCPP_INFO(
logger_, "Begin navigating from current location to (%.2f, %.2f)",
logger_, "Begin navigating from current location (%.2f, %.2f) to (%.2f, %.2f)",
current_pose.pose.position.x, current_pose.pose.position.y,
goal->pose.pose.position.x, goal->pose.pose.position.y);

// Reset state for new action feedback
Expand Down

0 comments on commit 6736448

Please sign in to comment.