Skip to content

Commit

Permalink
Fix digits
Browse files Browse the repository at this point in the history
  • Loading branch information
nhatao committed Jul 31, 2023
1 parent d509fe3 commit 01caafe
Showing 1 changed file with 3 additions and 3 deletions.
6 changes: 3 additions & 3 deletions planner_cspace/src/planner_3d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -514,7 +514,7 @@ class Planner3dNode
e.cycleUnsigned(map_info_.angle);
if (goal_changed)
{
ROS_INFO("New goal received. Metric: (%f, %f, %f), Grid: (%d, %d, %d)",
ROS_INFO("New goal received. Metric: (%.3f, %.3f, %.3f), Grid: (%d, %d, %d)",
goal_raw_.pose.position.x, goal_raw_.pose.position.y, tf2::getYaw(goal_raw_.pose.orientation),
e[0], e[1], e[2]);
clearHysteresis();
Expand Down Expand Up @@ -550,7 +550,7 @@ class Planner3dNode
goal_.pose.orientation = tf2::toMsg(tf2::Quaternion(tf2::Vector3(0.0, 0.0, 1.0), yaw));
goal_.pose.position.x = x;
goal_.pose.position.y = y;
ROS_INFO("Goal moved. Metric: (%f, %f, %f), Grid: (%d, %d, %d)", x, y, yaw, e[0], e[1], e[2]);
ROS_INFO("Goal moved. Metric: (%.3f, %.3f, %.3f), Grid: (%d, %d, %d)", x, y, yaw, e[0], e[1], e[2]);
break;
default:
Astar::Vec e_prev;
Expand All @@ -560,7 +560,7 @@ class Planner3dNode
tf2::getYaw(goal_.pose.orientation));
if (e[0] != e_prev[0] || e[1] != e_prev[1] || e[2] != e_prev[2])
{
ROS_INFO("Goal reverted. Metric: (%f, %f, %f), Grid: (%d, %d, %d)",
ROS_INFO("Goal reverted. Metric: (%.3f, %.3f, %.3f), Grid: (%d, %d, %d)",
goal_raw_.pose.position.x, goal_raw_.pose.position.y, tf2::getYaw(goal_raw_.pose.orientation),
e[0], e[1], e[2]);
}
Expand Down

0 comments on commit 01caafe

Please sign in to comment.