update
This commit is contained in:
parent
b22ac17c71
commit
1de5a35cc7
|
|
@ -83,7 +83,7 @@ namespace robot_nav_2d_utils
|
|||
* @param frame_id Frame to transform the pose into
|
||||
* @return The resulting transformed pose
|
||||
*/
|
||||
::geometry_msgs::Pose2D transformStampedPose(const TFListenerPtr tf, const ::robot_nav_2d_msgs::Pose2DStamped &pose,
|
||||
geometry_msgs::Pose2D transformStampedPose(const TFListenerPtr tf, const ::robot_nav_2d_msgs::Pose2DStamped &pose,
|
||||
const ::std::string &frame_id);
|
||||
|
||||
} // namespace robot_nav_2d_utils
|
||||
|
|
|
|||
|
|
@ -1275,10 +1275,7 @@ geometry_msgs::PoseStamped move_base::MoveBase::goalToGlobalFrame(const geometry
|
|||
geometry_msgs::PoseStamped goal_pose, global_pose;
|
||||
goal_pose = goal_pose_msg;
|
||||
|
||||
// just get the latest available transform... for accuracy they should send
|
||||
// goals in the frame of the planner
|
||||
goal_pose.header.stamp = robot::Time(); // latest available
|
||||
|
||||
try
|
||||
{
|
||||
tf3::TransformStampedMsg transform = tf_->lookupTransform(global_frame, goal_pose.header.frame_id, data_convert::convertTime(goal_pose.header.stamp));
|
||||
|
|
@ -1299,7 +1296,6 @@ geometry_msgs::PoseStamped move_base::MoveBase::goalToGlobalFrame(const geometry
|
|||
std::cerr << "Extrapolation Error looking up robot pose: " << ex.what() << std::endl;
|
||||
return goal_pose_msg;
|
||||
}
|
||||
|
||||
return global_pose;
|
||||
}
|
||||
|
||||
|
|
|
|||
Loading…
Reference in New Issue
Block a user