Program Listing for File utils.hpp
↰ Return to documentation for file (include/nav2_mppi_controller/tools/utils.hpp
)
// Copyright (c) 2022 Samsung Research America, @artofnothingness Alexey Budyakov
// Copyright (c) 2023 Open Navigation LLC
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef NAV2_MPPI_CONTROLLER__TOOLS__UTILS_HPP_
#define NAV2_MPPI_CONTROLLER__TOOLS__UTILS_HPP_
#include <algorithm>
#include <chrono>
#include <string>
#include <limits>
#include <memory>
#include <vector>
#include <xtensor/xarray.hpp>
#include <xtensor/xnorm.hpp>
#include <xtensor/xmath.hpp>
#include <xtensor/xview.hpp>
#include "angles/angles.h"
#include "tf2/utils.h"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
#include "geometry_msgs/msg/twist_stamped.hpp"
#include "nav_msgs/msg/path.hpp"
#include "visualization_msgs/msg/marker_array.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"
#include "nav2_util/node_utils.hpp"
#include "nav2_core/goal_checker.hpp"
#include "nav2_mppi_controller/models/optimizer_settings.hpp"
#include "nav2_mppi_controller/models/control_sequence.hpp"
#include "nav2_mppi_controller/models/path.hpp"
#include "builtin_interfaces/msg/time.hpp"
#include "nav2_mppi_controller/critic_data.hpp"
namespace mppi::utils
{
using xt::evaluation_strategy::immediate;
inline geometry_msgs::msg::Pose createPose(double x, double y, double z)
{
geometry_msgs::msg::Pose pose;
pose.position.x = x;
pose.position.y = y;
pose.position.z = z;
pose.orientation.w = 1;
pose.orientation.x = 0;
pose.orientation.y = 0;
pose.orientation.z = 0;
return pose;
}
inline geometry_msgs::msg::Vector3 createScale(double x, double y, double z)
{
geometry_msgs::msg::Vector3 scale;
scale.x = x;
scale.y = y;
scale.z = z;
return scale;
}
inline std_msgs::msg::ColorRGBA createColor(float r, float g, float b, float a)
{
std_msgs::msg::ColorRGBA color;
color.r = r;
color.g = g;
color.b = b;
color.a = a;
return color;
}
inline visualization_msgs::msg::Marker createMarker(
int id, const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::Vector3 & scale,
const std_msgs::msg::ColorRGBA & color, const std::string & frame_id, const std::string & ns)
{
using visualization_msgs::msg::Marker;
Marker marker;
marker.header.frame_id = frame_id;
marker.header.stamp = rclcpp::Time(0, 0);
marker.ns = ns;
marker.id = id;
marker.type = Marker::SPHERE;
marker.action = Marker::ADD;
marker.pose = pose;
marker.scale = scale;
marker.color = color;
return marker;
}
inline geometry_msgs::msg::TwistStamped toTwistStamped(
float vx, float wz, const builtin_interfaces::msg::Time & stamp, const std::string & frame)
{
geometry_msgs::msg::TwistStamped twist;
twist.header.frame_id = frame;
twist.header.stamp = stamp;
twist.twist.linear.x = vx;
twist.twist.angular.z = wz;
return twist;
}
inline geometry_msgs::msg::TwistStamped toTwistStamped(
float vx, float vy, float wz, const builtin_interfaces::msg::Time & stamp,
const std::string & frame)
{
auto twist = toTwistStamped(vx, wz, stamp, frame);
twist.twist.linear.y = vy;
return twist;
}
inline models::Path toTensor(const nav_msgs::msg::Path & path)
{
auto result = models::Path{};
result.reset(path.poses.size());
for (size_t i = 0; i < path.poses.size(); ++i) {
result.x(i) = path.poses[i].pose.position.x;
result.y(i) = path.poses[i].pose.position.y;
result.yaws(i) = tf2::getYaw(path.poses[i].pose.orientation);
}
return result;
}
inline bool withinPositionGoalTolerance(
nav2_core::GoalChecker * goal_checker,
const geometry_msgs::msg::Pose & robot,
const models::Path & path)
{
const auto goal_idx = path.x.shape(0) - 1;
const auto goal_x = path.x(goal_idx);
const auto goal_y = path.y(goal_idx);
if (goal_checker) {
geometry_msgs::msg::Pose pose_tolerance;
geometry_msgs::msg::Twist velocity_tolerance;
goal_checker->getTolerances(pose_tolerance, velocity_tolerance);
const auto pose_tolerance_sq = pose_tolerance.position.x * pose_tolerance.position.x;
auto dx = robot.position.x - goal_x;
auto dy = robot.position.y - goal_y;
auto dist_sq = dx * dx + dy * dy;
if (dist_sq < pose_tolerance_sq) {
return true;
}
}
return false;
}
inline bool withinPositionGoalTolerance(
float pose_tolerance,
const geometry_msgs::msg::Pose & robot,
const models::Path & path)
{
const auto goal_idx = path.x.shape(0) - 1;
const auto goal_x = path.x(goal_idx);
const auto goal_y = path.y(goal_idx);
const auto pose_tolerance_sq = pose_tolerance * pose_tolerance;
auto dx = robot.position.x - goal_x;
auto dy = robot.position.y - goal_y;
auto dist_sq = dx * dx + dy * dy;
if (dist_sq < pose_tolerance_sq) {
return true;
}
return false;
}
template<typename T>
auto normalize_angles(const T & angles)
{
auto && theta = xt::eval(xt::fmod(angles + M_PI, 2.0 * M_PI));
return xt::eval(xt::where(theta <= 0.0, theta + M_PI, theta - M_PI));
}
template<typename F, typename T>
auto shortest_angular_distance(
const F & from,
const T & to)
{
return normalize_angles(to - from);
}
inline size_t findPathFurthestReachedPoint(const CriticData & data)
{
const auto traj_x = xt::view(data.trajectories.x, xt::all(), -1, xt::newaxis());
const auto traj_y = xt::view(data.trajectories.y, xt::all(), -1, xt::newaxis());
const auto dx = data.path.x - traj_x;
const auto dy = data.path.y - traj_y;
const auto dists = dx * dx + dy * dy;
size_t max_id_by_trajectories = 0, min_id_by_path = 0;
float min_distance_by_path = std::numeric_limits<float>::max();
float cur_dist = 0.0f;
for (size_t i = 0; i < dists.shape(0); i++) {
min_id_by_path = 0;
min_distance_by_path = std::numeric_limits<float>::max();
for (size_t j = 0; j < dists.shape(1); j++) {
cur_dist = dists(i, j);
if (cur_dist < min_distance_by_path) {
min_distance_by_path = cur_dist;
min_id_by_path = j;
}
}
max_id_by_trajectories = std::max(max_id_by_trajectories, min_id_by_path);
}
return max_id_by_trajectories;
}
inline size_t findPathTrajectoryInitialPoint(const CriticData & data)
{
// First point should be the same for all trajectories from initial conditions
const auto dx = data.path.x - data.trajectories.x(0, 0);
const auto dy = data.path.y - data.trajectories.y(0, 0);
const auto dists = dx * dx + dy * dy;
float min_distance_by_path = std::numeric_limits<float>::max();
size_t min_id = 0;
for (size_t j = 0; j < dists.shape(0); j++) {
if (dists(j) < min_distance_by_path) {
min_distance_by_path = dists(j);
min_id = j;
}
}
return min_id;
}
inline void setPathFurthestPointIfNotSet(CriticData & data)
{
if (!data.furthest_reached_path_point) {
data.furthest_reached_path_point = findPathFurthestReachedPoint(data);
}
}
inline void findPathCosts(
CriticData & data,
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
{
auto * costmap = costmap_ros->getCostmap();
unsigned int map_x, map_y;
const size_t path_segments_count = data.path.x.shape(0) - 1;
data.path_pts_valid = std::vector<bool>(path_segments_count, false);
for (unsigned int idx = 0; idx < path_segments_count; idx++) {
const auto path_x = data.path.x(idx);
const auto path_y = data.path.y(idx);
if (!costmap->worldToMap(path_x, path_y, map_x, map_y)) {
(*data.path_pts_valid)[idx] = false;
continue;
}
switch (costmap->getCost(map_x, map_y)) {
using namespace nav2_costmap_2d; // NOLINT
case (LETHAL_OBSTACLE):
(*data.path_pts_valid)[idx] = false;
continue;
case (INSCRIBED_INFLATED_OBSTACLE):
(*data.path_pts_valid)[idx] = false;
continue;
case (NO_INFORMATION):
const bool is_tracking_unknown =
costmap_ros->getLayeredCostmap()->isTrackingUnknown();
(*data.path_pts_valid)[idx] = is_tracking_unknown ? true : false;
continue;
}
(*data.path_pts_valid)[idx] = true;
}
}
inline void setPathCostsIfNotSet(
CriticData & data,
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
{
if (!data.path_pts_valid) {
findPathCosts(data, costmap_ros);
}
}
inline float posePointAngle(
const geometry_msgs::msg::Pose & pose, double point_x, double point_y, bool forward_preference)
{
float pose_x = pose.position.x;
float pose_y = pose.position.y;
float pose_yaw = tf2::getYaw(pose.orientation);
float yaw = atan2f(point_y - pose_y, point_x - pose_x);
// If no preference for forward, return smallest angle either in heading or 180 of heading
if (!forward_preference) {
return std::min(
fabs(angles::shortest_angular_distance(yaw, pose_yaw)),
fabs(angles::shortest_angular_distance(yaw, angles::normalize_angle(pose_yaw + M_PI))));
}
return fabs(angles::shortest_angular_distance(yaw, pose_yaw));
}
inline void savitskyGolayFilter(
models::ControlSequence & control_sequence,
std::array<mppi::models::Control, 4> & control_history,
const models::OptimizerSettings & settings)
{
// Savitzky-Golay Quadratic, 9-point Coefficients
xt::xarray<float> filter = {-21.0, 14.0, 39.0, 54.0, 59.0, 54.0, 39.0, 14.0, -21.0};
filter /= 231.0;
const unsigned int num_sequences = control_sequence.vx.shape(0) - 1;
// Too short to smooth meaningfully
if (num_sequences < 20) {
return;
}
auto applyFilter = [&](const xt::xarray<float> & data) -> float {
return xt::sum(data * filter, {0}, immediate)();
};
auto applyFilterOverAxis =
[&](xt::xtensor<float, 1> & sequence,
const float hist_0, const float hist_1, const float hist_2, const float hist_3) -> void
{
unsigned int idx = 0;
sequence(idx) = applyFilter(
{
hist_0,
hist_1,
hist_2,
hist_3,
sequence(idx),
sequence(idx + 1),
sequence(idx + 2),
sequence(idx + 3),
sequence(idx + 4)});
idx++;
sequence(idx) = applyFilter(
{
hist_1,
hist_2,
hist_3,
sequence(idx - 1),
sequence(idx),
sequence(idx + 1),
sequence(idx + 2),
sequence(idx + 3),
sequence(idx + 4)});
idx++;
sequence(idx) = applyFilter(
{
hist_2,
hist_3,
sequence(idx - 2),
sequence(idx - 1),
sequence(idx),
sequence(idx + 1),
sequence(idx + 2),
sequence(idx + 3),
sequence(idx + 4)});
idx++;
sequence(idx) = applyFilter(
{
hist_3,
sequence(idx - 3),
sequence(idx - 2),
sequence(idx - 1),
sequence(idx),
sequence(idx + 1),
sequence(idx + 2),
sequence(idx + 3),
sequence(idx + 4)});
for (idx = 4; idx != num_sequences - 4; idx++) {
sequence(idx) = applyFilter(
{
sequence(idx - 4),
sequence(idx - 3),
sequence(idx - 2),
sequence(idx - 1),
sequence(idx),
sequence(idx + 1),
sequence(idx + 2),
sequence(idx + 3),
sequence(idx + 4)});
}
idx++;
sequence(idx) = applyFilter(
{
sequence(idx - 4),
sequence(idx - 3),
sequence(idx - 2),
sequence(idx - 1),
sequence(idx),
sequence(idx + 1),
sequence(idx + 2),
sequence(idx + 3),
sequence(idx + 3)});
idx++;
sequence(idx) = applyFilter(
{
sequence(idx - 4),
sequence(idx - 3),
sequence(idx - 2),
sequence(idx - 1),
sequence(idx),
sequence(idx + 1),
sequence(idx + 2),
sequence(idx + 2),
sequence(idx + 2)});
idx++;
sequence(idx) = applyFilter(
{
sequence(idx - 4),
sequence(idx - 3),
sequence(idx - 2),
sequence(idx - 1),
sequence(idx),
sequence(idx + 1),
sequence(idx + 1),
sequence(idx + 1),
sequence(idx + 1)});
idx++;
sequence(idx) = applyFilter(
{
sequence(idx - 4),
sequence(idx - 3),
sequence(idx - 2),
sequence(idx - 1),
sequence(idx),
sequence(idx),
sequence(idx),
sequence(idx),
sequence(idx)});
};
// Filter trajectories
applyFilterOverAxis(
control_sequence.vx, control_history[0].vx,
control_history[1].vx, control_history[2].vx, control_history[3].vx);
applyFilterOverAxis(
control_sequence.vy, control_history[0].vy,
control_history[1].vy, control_history[2].vy, control_history[3].vy);
applyFilterOverAxis(
control_sequence.wz, control_history[0].wz,
control_history[1].wz, control_history[2].wz, control_history[3].wz);
// Update control history
unsigned int offset = settings.shift_control_sequence ? 1 : 0;
control_history[0] = control_history[1];
control_history[1] = control_history[2];
control_history[2] = control_history[3];
control_history[3] = {
control_sequence.vx(offset),
control_sequence.vy(offset),
control_sequence.wz(offset)};
}
inline unsigned int findFirstPathInversion(nav_msgs::msg::Path & path)
{
// At least 3 poses for a possible inversion
if (path.poses.size() < 3) {
return path.poses.size();
}
// Iterating through the path to determine the position of the path inversion
for (unsigned int idx = 1; idx < path.poses.size() - 1; ++idx) {
// We have two vectors for the dot product OA and AB. Determining the vectors.
float oa_x = path.poses[idx].pose.position.x -
path.poses[idx - 1].pose.position.x;
float oa_y = path.poses[idx].pose.position.y -
path.poses[idx - 1].pose.position.y;
float ab_x = path.poses[idx + 1].pose.position.x -
path.poses[idx].pose.position.x;
float ab_y = path.poses[idx + 1].pose.position.y -
path.poses[idx].pose.position.y;
// Checking for the existance of cusp, in the path, using the dot product.
float dot_product = (oa_x * ab_x) + (oa_y * ab_y);
if (dot_product < 0.0) {
return idx + 1;
}
}
return path.poses.size();
}
inline unsigned int removePosesAfterFirstInversion(nav_msgs::msg::Path & path)
{
nav_msgs::msg::Path cropped_path = path;
const unsigned int first_after_inversion = findFirstPathInversion(cropped_path);
if (first_after_inversion == path.poses.size()) {
return 0u;
}
cropped_path.poses.erase(
cropped_path.poses.begin() + first_after_inversion, cropped_path.poses.end());
path = cropped_path;
return first_after_inversion;
}
inline size_t findClosestPathPt(const std::vector<float> & vec, float dist, size_t init = 0)
{
auto iter = std::lower_bound(vec.begin() + init, vec.end(), dist);
if (iter == vec.begin() + init) {
return 0;
}
if (dist - *(iter - 1) < *iter - dist) {
return iter - 1 - vec.begin();
}
return iter - vec.begin();
}
} // namespace mppi::utils
#endif // NAV2_MPPI_CONTROLLER__TOOLS__UTILS_HPP_