Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
utils.hpp
1 // Copyright (c) 2022 Samsung Research America, @artofnothingness Alexey Budyakov
2 // Copyright (c) 2023 Open Navigation LLC
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License.
15 
16 #ifndef NAV2_MPPI_CONTROLLER__TOOLS__UTILS_HPP_
17 #define NAV2_MPPI_CONTROLLER__TOOLS__UTILS_HPP_
18 
19 #include <Eigen/Dense>
20 
21 #include <algorithm>
22 #include <chrono>
23 #include <string>
24 #include <limits>
25 #include <memory>
26 #include <vector>
27 
28 #include "angles/angles.h"
29 
30 #include "tf2/utils.hpp"
31 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
32 
33 #include "geometry_msgs/msg/twist_stamped.hpp"
34 #include "nav_msgs/msg/path.hpp"
35 #include "nav2_msgs/msg/trajectory.hpp"
36 #include "visualization_msgs/msg/marker_array.hpp"
37 
38 #include "rclcpp/rclcpp.hpp"
39 #include "rclcpp_lifecycle/lifecycle_node.hpp"
40 
41 #include "nav2_ros_common/node_utils.hpp"
42 #include "nav2_core/goal_checker.hpp"
43 
44 #include "nav2_mppi_controller/models/optimizer_settings.hpp"
45 #include "nav2_mppi_controller/models/control_sequence.hpp"
46 #include "nav2_mppi_controller/models/path.hpp"
47 #include "builtin_interfaces/msg/time.hpp"
48 #include "nav2_mppi_controller/critic_data.hpp"
49 
50 #define M_PIF 3.141592653589793238462643383279502884e+00F
51 #define M_PIF_2 1.5707963267948966e+00F
52 
53 namespace mppi::utils
54 {
62 inline geometry_msgs::msg::Pose createPose(double x, double y, double z)
63 {
64  geometry_msgs::msg::Pose pose;
65  pose.position.x = x;
66  pose.position.y = y;
67  pose.position.z = z;
68  pose.orientation.w = 1;
69  pose.orientation.x = 0;
70  pose.orientation.y = 0;
71  pose.orientation.z = 0;
72  return pose;
73 }
74 
82 inline geometry_msgs::msg::Vector3 createScale(double x, double y, double z)
83 {
84  geometry_msgs::msg::Vector3 scale;
85  scale.x = x;
86  scale.y = y;
87  scale.z = z;
88  return scale;
89 }
90 
99 inline std_msgs::msg::ColorRGBA createColor(float r, float g, float b, float a)
100 {
101  std_msgs::msg::ColorRGBA color;
102  color.r = r;
103  color.g = g;
104  color.b = b;
105  color.a = a;
106  return color;
107 }
108 
118 inline visualization_msgs::msg::Marker createMarker(
119  int id, const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::Vector3 & scale,
120  const std_msgs::msg::ColorRGBA & color, const std::string & frame_id, const std::string & ns)
121 {
122  using visualization_msgs::msg::Marker;
123  Marker marker;
124  marker.header.frame_id = frame_id;
125  marker.header.stamp = rclcpp::Time(0, 0);
126  marker.ns = ns;
127  marker.id = id;
128  marker.type = Marker::SPHERE;
129  marker.action = Marker::ADD;
130 
131  marker.pose = pose;
132  marker.scale = scale;
133  marker.color = color;
134  return marker;
135 }
136 
144 inline geometry_msgs::msg::TwistStamped toTwistStamped(
145  float vx, float wz, const builtin_interfaces::msg::Time & stamp, const std::string & frame)
146 {
147  geometry_msgs::msg::TwistStamped twist;
148  twist.header.frame_id = frame;
149  twist.header.stamp = stamp;
150  twist.twist.linear.x = vx;
151  twist.twist.angular.z = wz;
152 
153  return twist;
154 }
155 
164 inline geometry_msgs::msg::TwistStamped toTwistStamped(
165  float vx, float vy, float wz, const builtin_interfaces::msg::Time & stamp,
166  const std::string & frame)
167 {
168  auto twist = toTwistStamped(vx, wz, stamp, frame);
169  twist.twist.linear.y = vy;
170 
171  return twist;
172 }
173 
174 inline std::unique_ptr<nav2_msgs::msg::Trajectory> toTrajectoryMsg(
175  const Eigen::ArrayXXf & trajectory,
176  const models::ControlSequence & control_sequence,
177  const double & model_dt,
178  const std_msgs::msg::Header & header)
179 {
180  auto trajectory_msg = std::make_unique<nav2_msgs::msg::Trajectory>();
181  trajectory_msg->header = header;
182  trajectory_msg->points.resize(trajectory.rows());
183 
184  for (int i = 0; i < trajectory.rows(); ++i) {
185  auto & curr_pt = trajectory_msg->points[i];
186  curr_pt.time_from_start = rclcpp::Duration::from_seconds(i * model_dt);
187  curr_pt.pose.position.x = trajectory(i, 0);
188  curr_pt.pose.position.y = trajectory(i, 1);
189  tf2::Quaternion quat;
190  quat.setRPY(0.0, 0.0, trajectory(i, 2));
191  curr_pt.pose.orientation = tf2::toMsg(quat);
192  curr_pt.velocity.linear.x = control_sequence.vx(i);
193  curr_pt.velocity.angular.z = control_sequence.wz(i);
194  if (control_sequence.vy.size() > 0) {
195  curr_pt.velocity.linear.y = control_sequence.vy(i);
196  }
197  }
198 
199  return trajectory_msg;
200 }
201 
207 inline models::Path toTensor(const nav_msgs::msg::Path & path)
208 {
209  auto result = models::Path{};
210  result.reset(path.poses.size());
211 
212  for (size_t i = 0; i < path.poses.size(); ++i) {
213  result.x(i) = path.poses[i].pose.position.x;
214  result.y(i) = path.poses[i].pose.position.y;
215  result.yaws(i) = tf2::getYaw(path.poses[i].pose.orientation);
216  }
217 
218  return result;
219 }
220 
226 inline geometry_msgs::msg::Pose getLastPathPose(const models::Path & path)
227 {
228  const unsigned int path_last_idx = path.x.size() - 1;
229 
230  auto last_orientation = path.yaws(path_last_idx);
231 
232  tf2::Quaternion pose_orientation;
233  pose_orientation.setRPY(0.0, 0.0, last_orientation);
234 
235  geometry_msgs::msg::Pose pathPose;
236  pathPose.position.x = path.x(path_last_idx);
237  pathPose.position.y = path.y(path_last_idx);
238  pathPose.orientation.x = pose_orientation.x();
239  pathPose.orientation.y = pose_orientation.y();
240  pathPose.orientation.z = pose_orientation.z();
241  pathPose.orientation.w = pose_orientation.w();
242 
243  return pathPose;
244 }
245 
253 inline geometry_msgs::msg::Pose getCriticGoal(
254  const CriticData & data,
255  bool enforce_path_inversion)
256 {
257  if (enforce_path_inversion) {
258  return getLastPathPose(data.path);
259  } else {
260  return data.goal;
261  }
262 }
263 
271 inline bool withinPositionGoalTolerance(
272  nav2_core::GoalChecker * goal_checker,
273  const geometry_msgs::msg::Pose & robot,
274  const geometry_msgs::msg::Pose & goal)
275 {
276  if (goal_checker) {
277  geometry_msgs::msg::Pose pose_tolerance;
278  geometry_msgs::msg::Twist velocity_tolerance;
279  goal_checker->getTolerances(pose_tolerance, velocity_tolerance);
280 
281  const auto pose_tolerance_sq = pose_tolerance.position.x * pose_tolerance.position.x;
282 
283  auto dx = robot.position.x - goal.position.x;
284  auto dy = robot.position.y - goal.position.y;
285 
286  auto dist_sq = dx * dx + dy * dy;
287 
288  if (dist_sq < pose_tolerance_sq) {
289  return true;
290  }
291  }
292 
293  return false;
294 }
295 
303 inline bool withinPositionGoalTolerance(
304  float pose_tolerance,
305  const geometry_msgs::msg::Pose & robot,
306  const geometry_msgs::msg::Pose & goal)
307 {
308  const double & dist_sq =
309  std::pow(goal.position.x - robot.position.x, 2) +
310  std::pow(goal.position.y - robot.position.y, 2);
311 
312  const float pose_tolerance_sq = pose_tolerance * pose_tolerance;
313 
314  if (dist_sq < pose_tolerance_sq) {
315  return true;
316  }
317 
318  return false;
319 }
320 
328 template<typename T>
329 auto normalize_angles(const T & angles)
330 {
331  return (angles + M_PIF).unaryExpr([&](const float x) {
332  float remainder = std::fmod(x, 2.0f * M_PIF);
333  return remainder < 0.0f ? remainder + M_PIF : remainder - M_PIF;
334  });
335 }
336 
350 template<typename F, typename T>
351 auto shortest_angular_distance(
352  const F & from,
353  const T & to)
354 {
355  return normalize_angles(to - from);
356 }
357 
364 inline size_t findPathFurthestReachedPoint(const CriticData & data)
365 {
366  int traj_cols = data.trajectories.x.cols();
367  const auto traj_x = data.trajectories.x.col(traj_cols - 1);
368  const auto traj_y = data.trajectories.y.col(traj_cols - 1);
369 
370  const auto dx = (data.path.x.transpose()).replicate(traj_x.rows(), 1).colwise() - traj_x;
371  const auto dy = (data.path.y.transpose()).replicate(traj_y.rows(), 1).colwise() - traj_y;
372 
373  const auto dists = dx * dx + dy * dy;
374 
375  int max_id_by_trajectories = 0, min_id_by_path = 0;
376  float min_distance_by_path = std::numeric_limits<float>::max();
377  size_t n_rows = dists.rows();
378  size_t n_cols = dists.cols();
379  for (size_t i = 0; i != n_rows; i++) {
380  min_id_by_path = 0;
381  min_distance_by_path = std::numeric_limits<float>::max();
382  for (size_t j = max_id_by_trajectories; j != n_cols; j++) {
383  const float cur_dist = dists(i, j);
384  if (cur_dist < min_distance_by_path) {
385  min_distance_by_path = cur_dist;
386  min_id_by_path = j;
387  }
388  }
389  max_id_by_trajectories = std::max(max_id_by_trajectories, min_id_by_path);
390  }
391  return max_id_by_trajectories;
392 }
393 
398 inline void setPathFurthestPointIfNotSet(CriticData & data)
399 {
400  if (!data.furthest_reached_path_point) {
401  data.furthest_reached_path_point = findPathFurthestReachedPoint(data);
402  }
403 }
404 
409 inline void findPathCosts(
410  CriticData & data,
411  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
412 {
413  auto * costmap = costmap_ros->getCostmap();
414  unsigned int map_x, map_y;
415  const size_t path_segments_count = data.path.x.size() - 1;
416  data.path_pts_valid = std::vector<bool>(path_segments_count, false);
417  const bool tracking_unknown = costmap_ros->getLayeredCostmap()->isTrackingUnknown();
418  for (unsigned int idx = 0; idx < path_segments_count; idx++) {
419  if (!costmap->worldToMap(data.path.x(idx), data.path.y(idx), map_x, map_y)) {
420  (*data.path_pts_valid)[idx] = false;
421  continue;
422  }
423 
424  switch (costmap->getCost(map_x, map_y)) {
425  case (nav2_costmap_2d::LETHAL_OBSTACLE):
426  (*data.path_pts_valid)[idx] = false;
427  continue;
428  case (nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE):
429  (*data.path_pts_valid)[idx] = false;
430  continue;
431  case (nav2_costmap_2d::NO_INFORMATION):
432  (*data.path_pts_valid)[idx] = tracking_unknown ? true : false;
433  continue;
434  }
435 
436  (*data.path_pts_valid)[idx] = true;
437  }
438 }
439 
444 inline void setPathCostsIfNotSet(
445  CriticData & data,
446  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
447 {
448  if (!data.path_pts_valid) {
449  findPathCosts(data, costmap_ros);
450  }
451 }
452 
461 inline float posePointAngle(
462  const geometry_msgs::msg::Pose & pose, double point_x, double point_y, bool forward_preference)
463 {
464  float pose_x = pose.position.x;
465  float pose_y = pose.position.y;
466  float pose_yaw = tf2::getYaw(pose.orientation);
467 
468  float yaw = atan2f(point_y - pose_y, point_x - pose_x);
469 
470  // If no preference for forward, return smallest angle either in heading or 180 of heading
471  if (!forward_preference) {
472  return std::min(
473  fabs(angles::shortest_angular_distance(yaw, pose_yaw)),
474  fabs(angles::shortest_angular_distance(yaw, angles::normalize_angle(pose_yaw + M_PIF))));
475  }
476 
477  return fabs(angles::shortest_angular_distance(yaw, pose_yaw));
478 }
479 
488 inline float posePointAngle(
489  const geometry_msgs::msg::Pose & pose,
490  double point_x, double point_y, double point_yaw)
491 {
492  float pose_x = static_cast<float>(pose.position.x);
493  float pose_y = static_cast<float>(pose.position.y);
494  float pose_yaw = static_cast<float>(tf2::getYaw(pose.orientation));
495 
496  float yaw = atan2f(static_cast<float>(point_y) - pose_y, static_cast<float>(point_x) - pose_x);
497 
498  if (fabs(angles::shortest_angular_distance(yaw, static_cast<float>(point_yaw))) > M_PIF_2) {
499  yaw = angles::normalize_angle(yaw + M_PIF);
500  }
501 
502  return fabs(angles::shortest_angular_distance(yaw, pose_yaw));
503 }
504 
511 inline void savitskyGolayFilter(
512  models::ControlSequence & control_sequence,
513  std::array<mppi::models::Control, 4> & control_history,
514  const models::OptimizerSettings & settings)
515 {
516  // Savitzky-Golay Quadratic, 9-point Coefficients
517  Eigen::Array<float, 9, 1> filter = {-21.0f, 14.0f, 39.0f, 54.0f, 59.0f, 54.0f, 39.0f, 14.0f,
518  -21.0f};
519  filter /= 231.0f;
520 
521  // Too short to smooth meaningfully
522  const unsigned int num_sequences = control_sequence.vx.size() - 1;
523  if (num_sequences < 20) {
524  return;
525  }
526 
527  auto applyFilter = [&](const Eigen::Array<float, 9, 1> & data) -> float {
528  return (data * filter).eval().sum();
529  };
530 
531  auto applyFilterOverAxis =
532  [&](Eigen::ArrayXf & sequence, const Eigen::ArrayXf & initial_sequence,
533  const float hist_0, const float hist_1, const float hist_2, const float hist_3) -> void
534  {
535  float pt_m4 = hist_0;
536  float pt_m3 = hist_1;
537  float pt_m2 = hist_2;
538  float pt_m1 = hist_3;
539  float pt = initial_sequence(0);
540  float pt_p1 = initial_sequence(1);
541  float pt_p2 = initial_sequence(2);
542  float pt_p3 = initial_sequence(3);
543  float pt_p4 = initial_sequence(4);
544 
545  for (unsigned int idx = 0; idx != num_sequences; idx++) {
546  sequence(idx) = applyFilter({pt_m4, pt_m3, pt_m2, pt_m1, pt, pt_p1, pt_p2, pt_p3, pt_p4});
547  pt_m4 = pt_m3;
548  pt_m3 = pt_m2;
549  pt_m2 = pt_m1;
550  pt_m1 = pt;
551  pt = pt_p1;
552  pt_p1 = pt_p2;
553  pt_p2 = pt_p3;
554  pt_p3 = pt_p4;
555 
556  if (idx + 5 < num_sequences) {
557  pt_p4 = initial_sequence(idx + 5);
558  } else {
559  // Return the last point
560  pt_p4 = initial_sequence(num_sequences);
561  }
562  }
563  };
564 
565  // Filter trajectories
566  const models::ControlSequence initial_control_sequence = control_sequence;
567  applyFilterOverAxis(
568  control_sequence.vx, initial_control_sequence.vx, control_history[0].vx,
569  control_history[1].vx, control_history[2].vx, control_history[3].vx);
570  applyFilterOverAxis(
571  control_sequence.vy, initial_control_sequence.vy, control_history[0].vy,
572  control_history[1].vy, control_history[2].vy, control_history[3].vy);
573  applyFilterOverAxis(
574  control_sequence.wz, initial_control_sequence.wz, control_history[0].wz,
575  control_history[1].wz, control_history[2].wz, control_history[3].wz);
576 
577  // Update control history
578  unsigned int offset = settings.shift_control_sequence ? 1 : 0;
579  control_history[0] = control_history[1];
580  control_history[1] = control_history[2];
581  control_history[2] = control_history[3];
582  control_history[3] = {
583  control_sequence.vx(offset),
584  control_sequence.vy(offset),
585  control_sequence.wz(offset)};
586 }
587 
593 inline unsigned int findFirstPathInversion(nav_msgs::msg::Path & path)
594 {
595  // At least 3 poses for a possible inversion
596  if (path.poses.size() < 3) {
597  return path.poses.size();
598  }
599 
600  // Iterating through the path to determine the position of the path inversion
601  for (unsigned int idx = 1; idx < path.poses.size() - 1; ++idx) {
602  // We have two vectors for the dot product OA and AB. Determining the vectors.
603  float oa_x = path.poses[idx].pose.position.x -
604  path.poses[idx - 1].pose.position.x;
605  float oa_y = path.poses[idx].pose.position.y -
606  path.poses[idx - 1].pose.position.y;
607  float ab_x = path.poses[idx + 1].pose.position.x -
608  path.poses[idx].pose.position.x;
609  float ab_y = path.poses[idx + 1].pose.position.y -
610  path.poses[idx].pose.position.y;
611 
612  // Checking for the existence of cusp, in the path, using the dot product.
613  float dot_product = (oa_x * ab_x) + (oa_y * ab_y);
614  if (dot_product < 0.0f) {
615  return idx + 1;
616  }
617  }
618 
619  return path.poses.size();
620 }
621 
627 inline unsigned int removePosesAfterFirstInversion(nav_msgs::msg::Path & path)
628 {
629  nav_msgs::msg::Path cropped_path = path;
630  const unsigned int first_after_inversion = findFirstPathInversion(cropped_path);
631  if (first_after_inversion == path.poses.size()) {
632  return 0u;
633  }
634 
635  cropped_path.poses.erase(
636  cropped_path.poses.begin() + first_after_inversion, cropped_path.poses.end());
637  path = cropped_path;
638  return first_after_inversion;
639 }
640 
647 inline unsigned int findClosestPathPt(
648  const std::vector<float> & vec, const float dist, const unsigned int init = 0u)
649 {
650  float distim1 = init != 0u ? vec[init] : 0.0f; // First is 0, no accumulated distance yet
651  float disti = 0.0f;
652  const unsigned int size = vec.size();
653  for (unsigned int i = init + 1; i != size; i++) {
654  disti = vec[i];
655  if (disti > dist) {
656  if (i > 0 && dist - distim1 < disti - dist) {
657  return i - 1;
658  }
659  return i;
660  }
661  distim1 = disti;
662  }
663  return size - 1;
664 }
665 
666 // A struct to hold pose data in floating point resolution
667 struct Pose2D
668 {
669  float x, y, theta;
670 };
671 
679 inline void shiftColumnsByOnePlace(Eigen::Ref<Eigen::ArrayXXf> e, int direction)
680 {
681  int size = e.size();
682  if(size == 1) {return;}
683  if(abs(direction) != 1) {
684  throw std::logic_error("Invalid direction, only 1 and -1 are valid values.");
685  }
686 
687  if((e.cols() == 1 || e.rows() == 1) && size > 1) {
688  auto start_ptr = direction == 1 ? e.data() + size - 2 : e.data() + 1;
689  auto end_ptr = direction == 1 ? e.data() : e.data() + size - 1;
690  while(start_ptr != end_ptr) {
691  *(start_ptr + direction) = *start_ptr;
692  start_ptr -= direction;
693  }
694  *(start_ptr + direction) = *start_ptr;
695  } else {
696  auto start_ptr = direction == 1 ? e.data() + size - 2 * e.rows() : e.data() + e.rows();
697  auto end_ptr = direction == 1 ? e.data() : e.data() + size - e.rows();
698  auto span = e.rows();
699  while(start_ptr != end_ptr) {
700  std::copy(start_ptr, start_ptr + span, start_ptr + direction * span);
701  start_ptr -= (direction * span);
702  }
703  std::copy(start_ptr, start_ptr + span, start_ptr + direction * span);
704  }
705 }
706 
714 inline auto normalize_yaws_between_points(
715  const Eigen::Ref<const Eigen::ArrayXf> & last_yaws,
716  const Eigen::Ref<const Eigen::ArrayXf> & yaw_between_points)
717 {
718  Eigen::ArrayXf yaws = utils::shortest_angular_distance(
719  last_yaws, yaw_between_points).abs();
720  int size = yaws.size();
721  Eigen::ArrayXf yaws_between_points_corrected(size);
722  for(int i = 0; i != size; i++) {
723  const float & yaw_between_point = yaw_between_points[i];
724  yaws_between_points_corrected[i] = yaws[i] < M_PIF_2 ?
725  yaw_between_point : angles::normalize_angle(yaw_between_point + M_PIF);
726  }
727  return yaws_between_points_corrected;
728 }
729 
736 inline auto normalize_yaws_between_points(
737  const float goal_yaw, const Eigen::Ref<const Eigen::ArrayXf> & yaw_between_points)
738 {
739  int size = yaw_between_points.size();
740  Eigen::ArrayXf yaws_between_points_corrected(size);
741  for(int i = 0; i != size; i++) {
742  const float & yaw_between_point = yaw_between_points[i];
743  yaws_between_points_corrected[i] = fabs(
744  angles::normalize_angle(yaw_between_point - goal_yaw)) < M_PIF_2 ?
745  yaw_between_point : angles::normalize_angle(yaw_between_point + M_PIF);
746  }
747  return yaws_between_points_corrected;
748 }
749 
756 inline float clamp(
757  const float lower_bound, const float upper_bound, const float input)
758 {
759  return std::min(upper_bound, std::max(input, lower_bound));
760 }
761 
762 } // namespace mppi::utils
763 
764 #endif // NAV2_MPPI_CONTROLLER__TOOLS__UTILS_HPP_
Function-object for checking whether a goal has been reached.
virtual bool getTolerances(geometry_msgs::msg::Pose &pose_tolerance, geometry_msgs::msg::Twist &vel_tolerance)=0
Get the maximum possible tolerances used for goal checking in the major types. Any field without a va...
void reset(unsigned int size)
Reset path data.
Definition: path.hpp:36