Skip to content

Commit 6736448

Browse files
nav2_bt_navigator: log current location on navigate_to_pose action initialization (#3720)
It is very useful to know the current location considered by the bt_navigator for debug purposes.
1 parent fb1e12c commit 6736448

File tree

1 file changed

+8
-1
lines changed

1 file changed

+8
-1
lines changed

nav2_bt_navigator/src/navigators/navigate_to_pose.cpp

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -203,8 +203,15 @@ NavigateToPoseNavigator::onPreempt(ActionT::Goal::ConstSharedPtr goal)
203203
void
204204
NavigateToPoseNavigator::initializeGoalPose(ActionT::Goal::ConstSharedPtr goal)
205205
{
206+
geometry_msgs::msg::PoseStamped current_pose;
207+
nav2_util::getCurrentPose(
208+
current_pose, *feedback_utils_.tf,
209+
feedback_utils_.global_frame, feedback_utils_.robot_frame,
210+
feedback_utils_.transform_tolerance);
211+
206212
RCLCPP_INFO(
207-
logger_, "Begin navigating from current location to (%.2f, %.2f)",
213+
logger_, "Begin navigating from current location (%.2f, %.2f) to (%.2f, %.2f)",
214+
current_pose.pose.position.x, current_pose.pose.position.y,
208215
goal->pose.pose.position.x, goal->pose.pose.position.y);
209216

210217
// Reset state for new action feedback

0 commit comments

Comments
 (0)