43 double poseDistance(
const geometry_msgs::Pose2D& pose0,
const geometry_msgs::Pose2D& pose1)
45 return hypot(pose0.x - pose1.x, pose0.y - pose1.y);
48 double getPlanLength(
const nav_2d_msgs::Path2D& plan,
const unsigned int start_index)
51 for (
unsigned int i = start_index + 1; i < plan.poses.size(); i++)
58 double getPlanLength(
const nav_2d_msgs::Path2D& plan,
const geometry_msgs::Pose2D& query_pose)
60 if (plan.poses.size() == 0)
return 0.0;
62 unsigned int closest_index = 0;
63 double closest_distance =
poseDistance(plan.poses[0], query_pose);
64 for (
unsigned int i = 1; i < plan.poses.size(); i++)
66 double distance =
poseDistance(plan.poses[i], query_pose);
67 if (closest_distance > distance)
70 closest_distance = distance;
78 nav_2d_msgs::Path2D global_plan_out;
79 global_plan_out.header = global_plan_in.header;
80 if (global_plan_in.poses.size() == 0)
82 return global_plan_out;
85 geometry_msgs::Pose2D last = global_plan_in.poses[0];
86 global_plan_out.poses.push_back(last);
88 double sq_resolution = resolution * resolution;
90 for (
unsigned int i = 1; i < global_plan_in.poses.size(); ++i)
92 geometry_msgs::Pose2D loop = global_plan_in.poses[i];
93 double sq_dist = (loop.x - last.x) * (loop.x - last.x) + (loop.y - last.y) * (loop.y - last.y);
94 if (sq_dist > sq_resolution)
97 double diff = sqrt(sq_dist) - resolution;
98 double steps_double = ceil(diff / resolution) + 1.0;
99 int steps =
static_cast<int>(steps_double);
101 double delta_x = (loop.x - last.x) / steps_double;
102 double delta_y = (loop.y - last.y) / steps_double;
103 double delta_t = (loop.theta - last.theta) / steps_double;
105 for (
int j = 1; j < steps; ++j)
107 geometry_msgs::Pose2D pose;
108 pose.x = last.x + j * delta_x;
109 pose.y = last.y + j * delta_y;
110 pose.theta = last.theta + j * delta_t;
111 global_plan_out.poses.push_back(pose);
114 global_plan_out.poses.push_back(global_plan_in.poses[i]);
118 return global_plan_out;
121 using PoseList = std::vector<geometry_msgs::Pose2D>;
137 if (end_index - start_index <= 1)
139 PoseList::const_iterator first = input.begin() + start_index;
140 PoseList::const_iterator last = input.begin() + end_index + 1;
145 const geometry_msgs::Pose2D&
start = input[start_index],
146 end = input[end_index];
147 double max_distance = 0.0;
148 unsigned int max_index = 0;
149 for (
unsigned int i = start_index + 1; i < end_index; i++)
151 const geometry_msgs::Pose2D& pose = input[i];
153 if (
d > max_distance)
164 outer.push_back(
start);
165 outer.push_back(end);
172 first_part.insert(first_part.end(), second_part.begin() + 1, second_part.end());
176 nav_2d_msgs::Path2D
compressPlan(
const nav_2d_msgs::Path2D& input_path,
double epsilon)
178 nav_2d_msgs::Path2D results;
179 results.header = input_path.header;
184 void addPose(nav_2d_msgs::Path2D& path,
double x,
double y,
double theta)
186 geometry_msgs::Pose2D pose;
190 path.poses.push_back(pose);