36 namespace mnm = marti_nav_msgs;
43 const std::string &target_frame)
45 for (
auto &point : route.
points) {
46 point.setPosition(transform*point.position());
47 point.setOrientation(transform*point.orientation());
49 route.
header.frame_id = target_frame;
54 for (
auto &point : route.
points) {
55 point.position().setZ(0.0);
64 if (route.
points.size() < 2) {
68 std::vector<size_t> degenerate_orientations;
70 for (
size_t i = 0; i < route.
points.size(); ++i) {
78 v_forward = route.
points[i+1].position() - route.
points[i+0].position();
79 }
else if (i+1 == route.
points.size()) {
81 v_forward = route.
points[i+0].position() - route.
points[i-1].position();
83 v_forward = route.
points[i+1].position() - route.
points[i-1].position();
96 if (std::isnan(v_left.
x()))
100 degenerate_orientations.push_back(i);
116 v_forward.
x(), v_left.
x(), v_up.
x(),
117 v_forward.
y(), v_left.
y(), v_up.
y(),
118 v_forward.
z(), v_left.
z(), v_up.
z());
123 rotation.getRotation(orientation);
124 route.
points[i].setOrientation(orientation);
131 for (
size_t i = 0; i < degenerate_orientations.size(); ++i)
133 size_t d_idx = degenerate_orientations[i];
134 bool repaired_orientation =
false;
135 for (
size_t j = 1; j < route.
points.size(); ++j)
137 size_t up_idx = d_idx + j;
138 int64_t down_idx = (int64_t)d_idx - (int64_t)j;
139 if (up_idx < route.
points.size())
141 if (std::find(degenerate_orientations.begin(), degenerate_orientations.end(), up_idx) == degenerate_orientations.end())
144 route.
points[d_idx].setOrientation(route.
points[up_idx].orientation());
145 repaired_orientation =
true;
152 if (std::find(degenerate_orientations.begin(), degenerate_orientations.end(), down_idx) == degenerate_orientations.end())
155 route.
points[d_idx].setOrientation(route.
points[down_idx].orientation());
156 repaired_orientation =
true;
162 if (!repaired_orientation)
165 "orientation. The route may be malformed.");
170 "orientation. Note that the source route may contain " 184 double &min_distance_from_line,
185 double &min_distance_on_line,
189 bool extrapolate_start,
190 bool extrapolate_end)
193 const double v_len_sq = v.
dot(v);
198 if (v_len_sq > 1e-6) {
199 s = v.
dot(p - p0) / v_len_sq;
208 if (!extrapolate_start && s < 0.0) {
210 }
else if (!extrapolate_end && s > 1.0) {
216 min_distance_from_line = x_nearest.
distance(p);
217 min_distance_on_line = s*std::sqrt(v_len_sq);
223 bool extrapolate_before_start,
224 bool extrapolate_past_end)
226 if (route.
points.size() == 0) {
231 if (route.
points.size() == 1) {
233 position.route_id = route.
guid();
234 position.id = route.
points[0].id();
235 position.distance = 0.0;
241 double min_distance_from_line = std::numeric_limits<double>::infinity();
242 double min_distance_on_line = std::numeric_limits<double>::infinity();
243 size_t min_segment_index = 0;
245 for (
size_t i = 0; i+1 < route.
points.size(); ++i) {
246 double distance_from_line;
247 double distance_on_line;
251 route.
points[i+0].position(),
252 route.
points[i+1].position(),
256 if (distance_from_line <= min_distance_from_line) {
257 min_segment_index = i;
258 min_distance_on_line = distance_on_line;
259 min_distance_from_line = distance_from_line;
268 if (extrapolate_before_start && min_segment_index == 0) {
271 min_distance_on_line,
272 route.
points[i+0].position(),
273 route.
points[i+1].position(),
276 }
else if (min_segment_index + 2 == route.
points.size()) {
282 size_t i = min_segment_index;
284 min_distance_on_line,
285 route.
points[i+0].position(),
286 route.
points[i+1].position(),
290 double last_length = (route.
points[i+1].position() - route.
points[i+0].position()).
length();
291 if (min_distance_on_line > last_length) {
293 min_distance_on_line -= last_length;
296 if (!extrapolate_past_end) {
297 min_distance_on_line = 0.0;
301 position.route_id = route.
guid();
302 position.id = route.
points[min_segment_index].id();
303 position.distance = min_distance_on_line;
308 mnm::RoutePosition &position,
311 const mnm::RoutePosition &window_start,
312 const mnm::RoutePosition &window_end)
314 if (route.
points.size() < 2) {
320 mnm::RoutePosition start;
324 mnm::RoutePosition end;
331 if (start.id == end.id && start.distance == end.distance) {
332 position.route_id = route.
guid();
345 if ((end_index < start_index) ||
346 (start_index == end_index && end.distance < start.distance)) {
347 std::swap(end, start);
348 std::swap(start_index, end_index);
354 if (start_index+1 == route.
points.size()) {
356 start.id = route.
points[start_index].id();
357 start.distance += (route.
points[start_index+1].position() -
360 if (end_index+1 == route.
points.size()) {
362 end.id = route.
points[end_index].id();
363 end.distance += (route.
points[end_index+1].position() -
370 if (start_index == end_index) {
371 double distance_from_line;
372 double distance_on_line;
376 route.
points[start_index+0].position(),
377 route.
points[start_index+1].position(),
381 if (distance_on_line < start.distance) {
382 distance_on_line = start.distance;
383 }
else if (distance_on_line > end.distance) {
384 distance_on_line = end.distance;
387 mnm::RoutePosition denormal_position;
388 denormal_position.id = start.id;
389 denormal_position.distance = distance_on_line;
394 position.route_id = route.
guid();
400 double min_distance_from_line = std::numeric_limits<double>::infinity();
401 double min_distance_on_line = std::numeric_limits<double>::infinity();
402 size_t min_segment_index = 0;
404 for (
size_t i = start_index; i <= end_index; ++i) {
405 double distance_from_line;
406 double distance_on_line;
410 route.
points[i+0].position(),
411 route.
points[i+1].position(),
415 if (distance_from_line <= min_distance_from_line) {
416 min_segment_index = i;
417 min_distance_on_line = distance_on_line;
418 min_distance_from_line = distance_from_line;
424 if (min_segment_index == start_index) {
426 min_distance_on_line,
427 route.
points[min_segment_index+0].position(),
428 route.
points[min_segment_index+1].position(),
431 if (min_distance_on_line < start.distance) {
432 min_distance_on_line = start.distance;
434 }
else if (min_segment_index == end_index) {
436 min_distance_on_line,
437 route.
points[min_segment_index+0].position(),
438 route.
points[min_segment_index+1].position(),
441 if (min_distance_on_line > end.distance) {
442 min_distance_on_line = end.distance;
446 mnm::RoutePosition denormal_position;
447 denormal_position.id = route.
points[min_segment_index].id();
448 denormal_position.distance = min_distance_on_line;
453 position.route_id = route.
guid();
476 }
else if (distance > 1) {
494 const mnm::RoutePosition &position)
501 double distance = position.distance;
502 while (distance < 0.0) {
510 distance += (route.
points[index-0].position() -
515 while (distance > 0.0) {
517 if (index+1 == route.
points.size()) {
521 double segment_length = (route.
points[index+0].position() -
523 if (distance > segment_length) {
526 distance -= segment_length;
535 normalized_position.route_id = position.route_id;
536 normalized_position.distance = distance;
537 normalized_position.id = route.
points[index].id();
544 const mnm::RoutePosition &position,
545 bool allow_extrapolation)
547 mnm::RoutePosition norm_position;
557 if (index == 0 && norm_position.distance < 0.0) {
558 if (!allow_extrapolation) {
562 if (route.
points.size() < 2) {
571 norm_position.distance);
576 if (index+1 == route.
points.size() && norm_position.distance > 0.0) {
577 if (!allow_extrapolation) {
580 if (route.
points.size() < 2) {
593 norm_position.distance + extra_dist);
600 norm_position.distance);
606 const mnm::RoutePosition &start,
607 const mnm::RoutePosition &end,
620 size_t min_index = std::min(start_index, end_index);
621 size_t max_index = std::max(start_index, end_index);
624 if (route.
header.frame_id == stu::_wgs84_frame) {
625 for (
size_t i = min_index; i < max_index; i++) {
626 d += stu::GreatCircleDistance(route.
points[i+1].position(), route.
points[i].position());
629 for (
size_t i = min_index; i < max_index; i++) {
634 if (end_index < start_index) {
638 distance = d + end.distance - start.distance;
643 std::vector<double> &distances,
644 const mnm::RoutePosition &start,
645 const std::vector<mnm::RoutePosition> &ends,
656 size_t min_index = start_index;
657 size_t max_index = start_index;
658 std::vector<int> indices;
659 indices.resize(ends.size());
660 for (
size_t i = 0; i < ends.size(); ++i) {
663 indices[i] = pt_index;
664 min_index = std::min(min_index, pt_index);
665 max_index = std::max(max_index, pt_index);
672 const size_t roi_start_index = start_index - min_index;
677 std::vector<double> arc_lengths;
678 arc_lengths.resize(max_index-min_index+1);
680 arc_lengths[roi_start_index] = 0.0;
681 if (route.
header.frame_id == stu::_wgs84_frame) {
683 for (
size_t rev_i = 1; rev_i <= roi_start_index; ++rev_i) {
684 const size_t i = roi_start_index - rev_i;
687 arc_lengths[i] = arc_lengths[i+1] - stu::GreatCircleDistance(pt1, pt2);
690 for (
size_t i = roi_start_index+1; i < arc_lengths.size(); ++i) {
693 arc_lengths[i] = arc_lengths[i-1] + stu::GreatCircleDistance(pt1, pt2);
698 for (
size_t rev_i = 1; rev_i <= roi_start_index; ++rev_i) {
699 const size_t i = roi_start_index - rev_i;
702 arc_lengths[i] = arc_lengths[i+1] - (pt2-pt1).
length();
705 for (
size_t i = roi_start_index+1; i < arc_lengths.size(); ++i) {
708 arc_lengths[i] = arc_lengths[i-1] + (pt2-pt1).
length();
713 distances.resize(ends.size());
714 for (
size_t i = 0; i < distances.size(); ++i) {
715 if (indices[i] < 0) {
716 distances[i] = std::numeric_limits<double>::quiet_NaN();
720 const size_t cache_index = indices[i]-min_index;
721 distances[i] = arc_lengths[cache_index] + ends[i].distance - start.distance;
730 const marti_nav_msgs::RoutePosition &start,
731 const marti_nav_msgs::RoutePosition &end)
738 mnm::RoutePosition norm_start;
743 mnm::RoutePosition norm_end;
757 if (norm_end.distance > 0.0) {
764 end_index = std::min(end_index, route.
points.size());
766 if (end_index <= start_index)
773 sub_route.
points.reserve(end_index - start_index);
774 for (
size_t i = start_index; i < end_index; i++) {
void rebuildPointIndex() const
bool normalizeRoutePosition(marti_nav_msgs::RoutePosition &normalized_position, const Route &route, const marti_nav_msgs::RoutePosition &position)
std::map< std::string, std::string > properties_
void transform(Route &route, const swri_transform_util::Transform &transform, const std::string &target_frame)
bool routeDistances(std::vector< double > &distances, const marti_nav_msgs::RoutePosition &start, const std::vector< marti_nav_msgs::RoutePosition > &ends, const Route &route)
bool interpolateRoutePosition(RoutePoint &point, const Route &route, const marti_nav_msgs::RoutePosition &position, bool allow_extrapolation)
bool projectOntoRoute(marti_nav_msgs::RoutePosition &position, const Route &route, const tf::Vector3 &point, bool extrapolate_before_start, bool extrapolate_past_end)
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
Quaternion slerp(const Quaternion &q, const tfScalar &t) const
TFSIMD_FORCE_INLINE Vector3 cross(const Vector3 &v) const
void setPosition(const tf::Vector3 &position)
void fillOrientations(Route &route, const tf::Vector3 &up=tf::Vector3(0.0, 0.0, 1.0))
TFSIMD_FORCE_INLINE const tfScalar & x() const
TFSIMD_FORCE_INLINE tfScalar dot(const Vector3 &v) const
TFSIMD_FORCE_INLINE const tfScalar & z() const
#define ROS_WARN_THROTTLE(period,...)
#define ROS_ERROR_THROTTLE(period,...)
bool projectOntoRouteWindow(marti_nav_msgs::RoutePosition &position, const Route &route, const tf::Vector3 &point, const marti_nav_msgs::RoutePosition &window_start, const marti_nav_msgs::RoutePosition &window_end)
TFSIMD_FORCE_INLINE const tfScalar & y() const
bool findPointId(size_t &index, const std::string &id) const
std::vector< RoutePoint > points
TFSIMD_FORCE_INLINE Vector3 & normalize()
static void nearestDistanceToLineSegment(double &min_distance_from_line, double &min_distance_on_line, const tf::Vector3 &p0, const tf::Vector3 &p1, const tf::Vector3 &p, bool extrapolate_start, bool extrapolate_end)
bool routeDistance(double &distance, const marti_nav_msgs::RoutePosition &start, const marti_nav_msgs::RoutePosition &end, const Route &route)
static void interpolateRouteSegment(RoutePoint &dst, const RoutePoint &p0, const RoutePoint &p1, double distance)
void setOrientation(const tf::Quaternion &orientation)
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
const tf::Vector3 & position() const
void projectToXY(Route &route)
bool extractSubroute(Route &sub_route, const Route &route, const marti_nav_msgs::RoutePosition &start, const marti_nav_msgs::RoutePosition &end)
const tf::Quaternion & orientation() const