Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include <dwb_local_planner/trajectory_utils.h>
00036 #include <nav_core2/exceptions.h>
00037
00038 namespace dwb_local_planner
00039 {
00040 const geometry_msgs::Pose2D& getClosestPose(const dwb_msgs::Trajectory2D& trajectory, const double time_offset)
00041 {
00042 ros::Duration goal_time(time_offset);
00043 const unsigned int num_poses = trajectory.poses.size();
00044 if (num_poses == 0)
00045 {
00046 throw nav_core2::PlannerException("Cannot call getClosestPose on empty trajectory.");
00047 }
00048 unsigned int closest_index = num_poses;
00049 double closest_diff = 0.0;
00050 for (unsigned int i=0; i < num_poses; ++i)
00051 {
00052 double diff = fabs((trajectory.time_offsets[i] - goal_time).toSec());
00053 if (closest_index == num_poses || diff < closest_diff)
00054 {
00055 closest_index = i;
00056 closest_diff = diff;
00057 }
00058 if (goal_time < trajectory.time_offsets[i])
00059 {
00060 break;
00061 }
00062 }
00063 return trajectory.poses[closest_index];
00064 }
00065
00066 geometry_msgs::Pose2D projectPose(const dwb_msgs::Trajectory2D& trajectory, const double time_offset)
00067 {
00068 ros::Duration goal_time(time_offset);
00069 const unsigned int num_poses = trajectory.poses.size();
00070 if (num_poses == 0)
00071 {
00072 throw nav_core2::PlannerException("Cannot call projectPose on empty trajectory.");
00073 }
00074 if (goal_time <= trajectory.time_offsets[0])
00075 {
00076 return trajectory.poses[0];
00077 }
00078 else if (goal_time >= trajectory.time_offsets[num_poses - 1])
00079 {
00080 return trajectory.poses[num_poses - 1];
00081 }
00082
00083 for (unsigned int i=0; i < num_poses - 1; ++i)
00084 {
00085 if (goal_time >= trajectory.time_offsets[i] && goal_time < trajectory.time_offsets[i+1])
00086 {
00087 double time_diff = (trajectory.time_offsets[i+1] - trajectory.time_offsets[i]).toSec();
00088 double ratio = (goal_time - trajectory.time_offsets[i]).toSec() / time_diff;
00089 double inv_ratio = 1.0 - ratio;
00090 const geometry_msgs::Pose2D& pose_a = trajectory.poses[i];
00091 const geometry_msgs::Pose2D& pose_b = trajectory.poses[i + 1];
00092 geometry_msgs::Pose2D projected;
00093 projected.x = pose_a.x * inv_ratio + pose_b.x * ratio;
00094 projected.y = pose_a.y * inv_ratio + pose_b.y * ratio;
00095 projected.theta = pose_a.theta * inv_ratio + pose_b.theta * ratio;
00096 return projected;
00097 }
00098 }
00099
00100
00101 return trajectory.poses[num_poses - 1];
00102 }
00103
00104
00105 }