16 #ifndef NAV2_MPPI_CONTROLLER__TOOLS__UTILS_HPP_
17 #define NAV2_MPPI_CONTROLLER__TOOLS__UTILS_HPP_
19 #include <Eigen/Dense>
28 #include "angles/angles.h"
30 #include "tf2/utils.hpp"
31 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
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"
38 #include "rclcpp/rclcpp.hpp"
39 #include "rclcpp_lifecycle/lifecycle_node.hpp"
41 #include "nav2_ros_common/node_utils.hpp"
42 #include "nav2_core/goal_checker.hpp"
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"
50 #define M_PIF 3.141592653589793238462643383279502884e+00F
51 #define M_PIF_2 1.5707963267948966e+00F
62 inline geometry_msgs::msg::Pose createPose(
double x,
double y,
double z)
64 geometry_msgs::msg::Pose pose;
68 pose.orientation.w = 1;
69 pose.orientation.x = 0;
70 pose.orientation.y = 0;
71 pose.orientation.z = 0;
82 inline geometry_msgs::msg::Vector3 createScale(
double x,
double y,
double z)
84 geometry_msgs::msg::Vector3 scale;
99 inline std_msgs::msg::ColorRGBA createColor(
float r,
float g,
float b,
float a)
101 std_msgs::msg::ColorRGBA color;
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)
122 using visualization_msgs::msg::Marker;
124 marker.header.frame_id = frame_id;
125 marker.header.stamp = rclcpp::Time(0, 0);
128 marker.type = Marker::SPHERE;
129 marker.action = Marker::ADD;
132 marker.scale = scale;
133 marker.color = color;
144 inline geometry_msgs::msg::TwistStamped toTwistStamped(
145 float vx,
float wz,
const builtin_interfaces::msg::Time & stamp,
const std::string & frame)
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;
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)
168 auto twist = toTwistStamped(vx, wz, stamp, frame);
169 twist.twist.linear.y = vy;
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)
180 auto trajectory_msg = std::make_unique<nav2_msgs::msg::Trajectory>();
181 trajectory_msg->header = header;
182 trajectory_msg->points.resize(trajectory.rows());
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);
199 return trajectory_msg;
207 inline models::Path toTensor(
const nav_msgs::msg::Path & path)
209 auto result = models::Path{};
210 result.
reset(path.poses.size());
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);
226 inline geometry_msgs::msg::Pose getLastPathPose(
const models::Path & path)
228 const unsigned int path_last_idx = path.x.size() - 1;
230 auto last_orientation = path.yaws(path_last_idx);
232 tf2::Quaternion pose_orientation;
233 pose_orientation.setRPY(0.0, 0.0, last_orientation);
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();
254 auto normalize_angles(
const T & angles)
256 return (angles + M_PIF).unaryExpr([&](
const float x) {
257 float remainder = std::fmod(x, 2.0f * M_PIF);
258 return remainder < 0.0f ? remainder + M_PIF : remainder - M_PIF;
275 template<
typename F,
typename T>
276 auto shortest_angular_distance(
280 return normalize_angles(to - from);
289 inline size_t findPathFurthestReachedPoint(
const CriticData & data)
291 int traj_cols = data.trajectories.x.cols();
292 const auto traj_x = data.trajectories.x.col(traj_cols - 1);
293 const auto traj_y = data.trajectories.y.col(traj_cols - 1);
295 const auto dx = (data.path.x.transpose()).replicate(traj_x.rows(), 1).colwise() - traj_x;
296 const auto dy = (data.path.y.transpose()).replicate(traj_y.rows(), 1).colwise() - traj_y;
298 const auto dists = dx * dx + dy * dy;
300 int max_id_by_trajectories = 0, min_id_by_path = 0;
301 float min_distance_by_path = std::numeric_limits<float>::max();
302 size_t n_rows = dists.rows();
303 size_t n_cols = dists.cols();
304 for (
size_t i = 0; i != n_rows; i++) {
306 min_distance_by_path = std::numeric_limits<float>::max();
307 for (
size_t j = max_id_by_trajectories; j != n_cols; j++) {
308 const float cur_dist = dists(i, j);
309 if (cur_dist < min_distance_by_path) {
310 min_distance_by_path = cur_dist;
314 max_id_by_trajectories = std::max(max_id_by_trajectories, min_id_by_path);
316 return max_id_by_trajectories;
323 inline void setPathFurthestPointIfNotSet(CriticData & data)
325 if (!data.furthest_reached_path_point) {
326 data.furthest_reached_path_point = findPathFurthestReachedPoint(data);
334 inline void findPathCosts(
336 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
338 auto * costmap = costmap_ros->getCostmap();
339 unsigned int map_x, map_y;
340 const size_t path_segments_count = data.path.x.size() - 1;
341 data.path_pts_valid = std::vector<bool>(path_segments_count,
false);
342 const bool tracking_unknown = costmap_ros->getLayeredCostmap()->isTrackingUnknown();
343 for (
unsigned int idx = 0; idx < path_segments_count; idx++) {
344 if (!costmap->worldToMap(data.path.x(idx), data.path.y(idx), map_x, map_y)) {
345 (*data.path_pts_valid)[idx] =
false;
349 switch (costmap->getCost(map_x, map_y)) {
350 case (nav2_costmap_2d::LETHAL_OBSTACLE):
351 (*data.path_pts_valid)[idx] =
false;
353 case (nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE):
354 (*data.path_pts_valid)[idx] =
false;
356 case (nav2_costmap_2d::NO_INFORMATION):
357 (*data.path_pts_valid)[idx] = tracking_unknown ?
true :
false;
361 (*data.path_pts_valid)[idx] =
true;
369 inline void setPathCostsIfNotSet(
371 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
373 if (!data.path_pts_valid) {
374 findPathCosts(data, costmap_ros);
386 inline float posePointAngle(
387 const geometry_msgs::msg::Pose & pose,
double point_x,
double point_y,
bool forward_preference)
389 float pose_x = pose.position.x;
390 float pose_y = pose.position.y;
391 float pose_yaw = tf2::getYaw(pose.orientation);
393 float yaw = atan2f(point_y - pose_y, point_x - pose_x);
396 if (!forward_preference) {
398 fabs(angles::shortest_angular_distance(yaw, pose_yaw)),
399 fabs(angles::shortest_angular_distance(yaw, angles::normalize_angle(pose_yaw + M_PIF))));
402 return fabs(angles::shortest_angular_distance(yaw, pose_yaw));
413 inline float posePointAngle(
414 const geometry_msgs::msg::Pose & pose,
415 double point_x,
double point_y,
double point_yaw)
417 float pose_x =
static_cast<float>(pose.position.x);
418 float pose_y =
static_cast<float>(pose.position.y);
419 float pose_yaw =
static_cast<float>(tf2::getYaw(pose.orientation));
421 float yaw = atan2f(
static_cast<float>(point_y) - pose_y,
static_cast<float>(point_x) - pose_x);
423 if (fabs(angles::shortest_angular_distance(yaw,
static_cast<float>(point_yaw))) > M_PIF_2) {
424 yaw = angles::normalize_angle(yaw + M_PIF);
427 return fabs(angles::shortest_angular_distance(yaw, pose_yaw));
436 inline void savitskyGolayFilter(
437 models::ControlSequence & control_sequence,
438 std::array<mppi::models::Control, 4> & control_history,
439 const models::OptimizerSettings & settings)
442 Eigen::Array<float, 9, 1> filter = {-21.0f, 14.0f, 39.0f, 54.0f, 59.0f, 54.0f, 39.0f, 14.0f,
447 const unsigned int num_sequences = control_sequence.vx.size() - 1;
448 if (num_sequences < 20) {
452 auto applyFilter = [&](
const Eigen::Array<float, 9, 1> & data) ->
float {
453 return (data * filter).eval().sum();
456 auto applyFilterOverAxis =
457 [&](Eigen::ArrayXf & sequence,
const Eigen::ArrayXf & initial_sequence,
458 const float hist_0,
const float hist_1,
const float hist_2,
const float hist_3) ->
void
460 float pt_m4 = hist_0;
461 float pt_m3 = hist_1;
462 float pt_m2 = hist_2;
463 float pt_m1 = hist_3;
464 float pt = initial_sequence(0);
465 float pt_p1 = initial_sequence(1);
466 float pt_p2 = initial_sequence(2);
467 float pt_p3 = initial_sequence(3);
468 float pt_p4 = initial_sequence(4);
470 for (
unsigned int idx = 0; idx != num_sequences; idx++) {
471 sequence(idx) = applyFilter({pt_m4, pt_m3, pt_m2, pt_m1, pt, pt_p1, pt_p2, pt_p3, pt_p4});
481 if (idx + 5 < num_sequences) {
482 pt_p4 = initial_sequence(idx + 5);
485 pt_p4 = initial_sequence(num_sequences);
491 const models::ControlSequence initial_control_sequence = control_sequence;
493 control_sequence.vx, initial_control_sequence.vx, control_history[0].vx,
494 control_history[1].vx, control_history[2].vx, control_history[3].vx);
496 control_sequence.vy, initial_control_sequence.vy, control_history[0].vy,
497 control_history[1].vy, control_history[2].vy, control_history[3].vy);
499 control_sequence.wz, initial_control_sequence.wz, control_history[0].wz,
500 control_history[1].wz, control_history[2].wz, control_history[3].wz);
503 unsigned int offset = settings.shift_control_sequence ? 1 : 0;
504 control_history[0] = control_history[1];
505 control_history[1] = control_history[2];
506 control_history[2] = control_history[3];
507 control_history[3] = {
508 control_sequence.vx(offset),
509 control_sequence.vy(offset),
510 control_sequence.wz(offset)};
518 inline unsigned int findFirstPathInversion(nav_msgs::msg::Path & path)
521 if (path.poses.size() < 3) {
522 return path.poses.size();
526 for (
unsigned int idx = 1; idx < path.poses.size() - 1; ++idx) {
528 float oa_x = path.poses[idx].pose.position.x -
529 path.poses[idx - 1].pose.position.x;
530 float oa_y = path.poses[idx].pose.position.y -
531 path.poses[idx - 1].pose.position.y;
532 float ab_x = path.poses[idx + 1].pose.position.x -
533 path.poses[idx].pose.position.x;
534 float ab_y = path.poses[idx + 1].pose.position.y -
535 path.poses[idx].pose.position.y;
538 float dot_product = (oa_x * ab_x) + (oa_y * ab_y);
539 if (dot_product < 0.0f) {
544 return path.poses.size();
552 inline unsigned int removePosesAfterFirstInversion(nav_msgs::msg::Path & path)
554 nav_msgs::msg::Path cropped_path = path;
555 const unsigned int first_after_inversion = findFirstPathInversion(cropped_path);
556 if (first_after_inversion == path.poses.size()) {
560 cropped_path.poses.erase(
561 cropped_path.poses.begin() + first_after_inversion, cropped_path.poses.end());
563 return first_after_inversion;
572 inline unsigned int findClosestPathPt(
573 const std::vector<float> & vec,
const float dist,
const unsigned int init = 0u)
575 float distim1 = init != 0u ? vec[init] : 0.0f;
577 const unsigned int size = vec.size();
578 for (
unsigned int i = init + 1; i != size; i++) {
581 if (i > 0 && dist - distim1 < disti - dist) {
604 inline void shiftColumnsByOnePlace(Eigen::Ref<Eigen::ArrayXXf> e,
int direction)
607 if(size == 1) {
return;}
608 if(abs(direction) != 1) {
609 throw std::logic_error(
"Invalid direction, only 1 and -1 are valid values.");
612 if((e.cols() == 1 || e.rows() == 1) && size > 1) {
613 auto start_ptr = direction == 1 ? e.data() + size - 2 : e.data() + 1;
614 auto end_ptr = direction == 1 ? e.data() : e.data() + size - 1;
615 while(start_ptr != end_ptr) {
616 *(start_ptr + direction) = *start_ptr;
617 start_ptr -= direction;
619 *(start_ptr + direction) = *start_ptr;
621 auto start_ptr = direction == 1 ? e.data() + size - 2 * e.rows() : e.data() + e.rows();
622 auto end_ptr = direction == 1 ? e.data() : e.data() + size - e.rows();
623 auto span = e.rows();
624 while(start_ptr != end_ptr) {
625 std::copy(start_ptr, start_ptr + span, start_ptr + direction * span);
626 start_ptr -= (direction * span);
628 std::copy(start_ptr, start_ptr + span, start_ptr + direction * span);
639 inline auto normalize_yaws_between_points(
640 const Eigen::Ref<const Eigen::ArrayXf> & last_yaws,
641 const Eigen::Ref<const Eigen::ArrayXf> & yaw_between_points)
643 Eigen::ArrayXf yaws = utils::shortest_angular_distance(
644 last_yaws, yaw_between_points).abs();
645 int size = yaws.size();
646 Eigen::ArrayXf yaws_between_points_corrected(size);
647 for(
int i = 0; i != size; i++) {
648 const float & yaw_between_point = yaw_between_points[i];
649 yaws_between_points_corrected[i] = yaws[i] < M_PIF_2 ?
650 yaw_between_point : angles::normalize_angle(yaw_between_point + M_PIF);
652 return yaws_between_points_corrected;
661 inline auto normalize_yaws_between_points(
662 const float goal_yaw,
const Eigen::Ref<const Eigen::ArrayXf> & yaw_between_points)
664 int size = yaw_between_points.size();
665 Eigen::ArrayXf yaws_between_points_corrected(size);
666 for(
int i = 0; i != size; i++) {
667 const float & yaw_between_point = yaw_between_points[i];
668 yaws_between_points_corrected[i] = fabs(
669 angles::normalize_angle(yaw_between_point - goal_yaw)) < M_PIF_2 ?
670 yaw_between_point : angles::normalize_angle(yaw_between_point + M_PIF);
672 return yaws_between_points_corrected;
682 const float lower_bound,
const float upper_bound,
const float input)
684 return std::min(upper_bound, std::max(input, lower_bound));
void reset(unsigned int size)
Reset path data.