Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -144,7 +144,6 @@ class CostCritic : public CriticFunction
std::string inflation_layer_name_;

unsigned int power_{0};
bool enforce_path_inversion_{false};
};

} // namespace mppi::critics
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,6 @@ class GoalAngleCritic : public CriticFunction
float threshold_to_consider_{0};
unsigned int power_{0};
float weight_{0};
bool enforce_path_inversion_{false};
};

} // namespace mppi::critics
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,6 @@ class GoalCritic : public CriticFunction
unsigned int power_{0};
float weight_{0};
float threshold_to_consider_{0};
bool enforce_path_inversion_{false};
};

} // namespace mppi::critics
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,6 @@ class ObstaclesCritic : public CriticFunction

unsigned int power_{0};
float repulsion_weight_, critical_weight_{0};
bool enforce_path_inversion_{false};
std::string inflation_layer_name_;
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,6 @@ class PathAlignCritic : public CriticFunction
bool use_path_orientations_{false};
unsigned int power_{0};
float weight_{0};
bool enforce_path_inversion_{false};
};

} // namespace mppi::critics
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,6 @@ class PathAngleCritic : public CriticFunction

unsigned int power_{0};
float weight_{0};
bool enforce_path_inversion_{false};
};

} // namespace mppi::critics
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,6 @@ class PathFollowCritic : public CriticFunction

unsigned int power_{0};
float weight_{0};
bool enforce_path_inversion_{false};
};

} // namespace mppi::critics
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,6 @@ class PreferForwardCritic : public CriticFunction
unsigned int power_{0};
float weight_{0};
float threshold_to_consider_{0};
bool enforce_path_inversion_{false};
};

} // namespace mppi::critics
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,6 @@ class TwirlingCritic : public CriticFunction
protected:
unsigned int power_{0};
float weight_{0};
bool enforce_path_inversion_{false};
};

} // namespace mppi::critics
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@ struct State

geometry_msgs::msg::PoseStamped pose;
geometry_msgs::msg::Twist speed;
float local_path_length;

/**
* @brief Reset state data
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "geometry_msgs/msg/twist_stamped.hpp"
#include "nav_msgs/msg/path.hpp"
#include "nav2_util/geometry_utils.hpp"

#include "nav2_mppi_controller/models/optimizer_settings.hpp"
#include "nav2_mppi_controller/motion_models.hpp"
Expand Down
75 changes: 0 additions & 75 deletions nav2_mppi_controller/include/nav2_mppi_controller/tools/utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -243,81 +243,6 @@ inline geometry_msgs::msg::Pose getLastPathPose(const models::Path & path)
return pathPose;
}

/**
* @brief Get the target pose to be evaluated by the critic
* @param data Data to use
* @param enforce_path_inversion True to return the cusp point (last pose of the path)
* instead of the original goal
* @return geometry_msgs::msg::Pose Target pose for the critic
*/
inline geometry_msgs::msg::Pose getCriticGoal(
const CriticData & data,
bool enforce_path_inversion)
{
if (enforce_path_inversion) {
return getLastPathPose(data.path);
} else {
return data.goal;
}
}

/**
* @brief Check if the robot pose is within the Goal Checker's tolerances to goal
* @param global_checker Pointer to the goal checker
* @param robot Pose of robot
* @param goal Goal pose
* @return bool If robot is within goal checker tolerances to the goal
*/
inline bool withinPositionGoalTolerance(
nav2_core::GoalChecker * goal_checker,
const geometry_msgs::msg::Pose & robot,
const geometry_msgs::msg::Pose & goal)
{
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.position.x;
auto dy = robot.position.y - goal.position.y;

auto dist_sq = dx * dx + dy * dy;

if (dist_sq < pose_tolerance_sq) {
return true;
}
}

return false;
}

/**
* @brief Check if the robot pose is within tolerance to the goal
* @param pose_tolerance Pose tolerance to use
* @param robot Pose of robot
* @param goal Goal pose
* @return bool If robot is within tolerance to the goal
*/
inline bool withinPositionGoalTolerance(
float pose_tolerance,
const geometry_msgs::msg::Pose & robot,
const geometry_msgs::msg::Pose & goal)
{
const double & dist_sq =
std::pow(goal.position.x - robot.position.x, 2) +
std::pow(goal.position.y - robot.position.y, 2);

const float pose_tolerance_sq = pose_tolerance * pose_tolerance;

if (dist_sq < pose_tolerance_sq) {
return true;
}

return false;
}

/**
* @brief normalize
* Normalizes the angle to be -M_PIF circle to +M_PIF circle
Expand Down
6 changes: 1 addition & 5 deletions nav2_mppi_controller/src/critics/cost_critic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,6 @@ namespace mppi::critics
void CostCritic::initialize()
{
auto getParentParam = parameters_handler_->getParamGetter(parent_name_);
getParentParam(enforce_path_inversion_, "enforce_path_inversion", false);

auto getParam = parameters_handler_->getParamGetter(name_);
getParam(consider_footprint_, "consider_footprint", false);
getParam(power_, "cost_power", 1);
Expand Down Expand Up @@ -135,8 +133,6 @@ void CostCritic::score(CriticData & data)
return;
}

geometry_msgs::msg::Pose goal = utils::getCriticGoal(data, enforce_path_inversion_);

// Setup cost information for various parts of the critic
is_tracking_unknown_ = costmap_ros_->getLayeredCostmap()->isTrackingUnknown();
auto * costmap = collision_checker_.getCostmap();
Expand All @@ -153,7 +149,7 @@ void CostCritic::score(CriticData & data)

// If near the goal, don't apply the preferential term since the goal is near obstacles
bool near_goal = false;
if (utils::withinPositionGoalTolerance(near_goal_distance_, data.state.pose.pose, goal)) {
if (data.state.local_path_length < near_goal_distance_) {
near_goal = true;
}

Expand Down
12 changes: 2 additions & 10 deletions nav2_mppi_controller/src/critics/goal_angle_critic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,6 @@ namespace mppi::critics
void GoalAngleCritic::initialize()
{
auto getParentParam = parameters_handler_->getParamGetter(parent_name_);
getParentParam(enforce_path_inversion_, "enforce_path_inversion", false);

auto getParam = parameters_handler_->getParamGetter(name_);
getParam(power_, "cost_power", 1);
getParam(weight_, "cost_weight", 3.0f);
Expand All @@ -36,17 +34,11 @@ void GoalAngleCritic::initialize()

void GoalAngleCritic::score(CriticData & data)
{
if (!enabled_) {
if (!enabled_ || data.state.local_path_length > threshold_to_consider_) {
return;
}

geometry_msgs::msg::Pose goal = utils::getCriticGoal(data, enforce_path_inversion_);

if (!utils::withinPositionGoalTolerance(
threshold_to_consider_, data.state.pose.pose, goal))
{
return;
}
geometry_msgs::msg::Pose goal = utils::getLastPathPose(data.path);

double goal_yaw = tf2::getYaw(goal.orientation);

Expand Down
13 changes: 2 additions & 11 deletions nav2_mppi_controller/src/critics/goal_critic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,10 +22,7 @@ namespace mppi::critics
void GoalCritic::initialize()
{
auto getParentParam = parameters_handler_->getParamGetter(parent_name_);
getParentParam(enforce_path_inversion_, "enforce_path_inversion", false);

auto getParam = parameters_handler_->getParamGetter(name_);

getParam(power_, "cost_power", 1);
getParam(weight_, "cost_weight", 5.0f);
getParam(threshold_to_consider_, "threshold_to_consider", 1.4f);
Expand All @@ -37,17 +34,11 @@ void GoalCritic::initialize()

void GoalCritic::score(CriticData & data)
{
if (!enabled_) {
if (!enabled_ || data.state.local_path_length > threshold_to_consider_) {
return;
}

geometry_msgs::msg::Pose goal = utils::getCriticGoal(data, enforce_path_inversion_);

if (!utils::withinPositionGoalTolerance(
threshold_to_consider_, data.state.pose.pose, goal))
{
return;
}
geometry_msgs::msg::Pose goal = utils::getLastPathPose(data.path);

auto goal_x = goal.position.x;
auto goal_y = goal.position.y;
Expand Down
6 changes: 1 addition & 5 deletions nav2_mppi_controller/src/critics/obstacles_critic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,6 @@ namespace mppi::critics
void ObstaclesCritic::initialize()
{
auto getParentParam = parameters_handler_->getParamGetter(parent_name_);
getParentParam(enforce_path_inversion_, "enforce_path_inversion", false);

auto getParam = parameters_handler_->getParamGetter(name_);
getParam(consider_footprint_, "consider_footprint", false);
getParam(power_, "cost_power", 1);
Expand Down Expand Up @@ -130,11 +128,9 @@ void ObstaclesCritic::score(CriticData & data)
possible_collision_cost_ = findCircumscribedCost(costmap_ros_);
}

geometry_msgs::msg::Pose goal = utils::getCriticGoal(data, enforce_path_inversion_);

// If near the goal, don't apply the preferential term since the goal is near obstacles
bool near_goal = false;
if (utils::withinPositionGoalTolerance(near_goal_distance_, data.state.pose.pose, goal)) {
if (data.state.local_path_length < near_goal_distance_) {
near_goal = true;
}

Expand Down
14 changes: 1 addition & 13 deletions nav2_mppi_controller/src/critics/path_align_critic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,12 +20,9 @@ namespace mppi::critics
void PathAlignCritic::initialize()
{
auto getParentParam = parameters_handler_->getParamGetter(parent_name_);
getParentParam(enforce_path_inversion_, "enforce_path_inversion", false);

auto getParam = parameters_handler_->getParamGetter(name_);
getParam(power_, "cost_power", 1);
getParam(weight_, "cost_weight", 10.0f);

getParam(max_path_occupancy_ratio_, "max_path_occupancy_ratio", 0.07f);
getParam(offset_from_furthest_, "offset_from_furthest", 20);
getParam(trajectory_point_step_, "trajectory_point_step", 4);
Expand All @@ -42,16 +39,7 @@ void PathAlignCritic::initialize()

void PathAlignCritic::score(CriticData & data)
{
if (!enabled_) {
return;
}

geometry_msgs::msg::Pose goal = utils::getCriticGoal(data, enforce_path_inversion_);

// Don't apply close to goal, let the goal critics take over
if (utils::withinPositionGoalTolerance(
threshold_to_consider_, data.state.pose.pose, goal))
{
if (!enabled_ || data.state.local_path_length < threshold_to_consider_) {
return;
}

Expand Down
11 changes: 1 addition & 10 deletions nav2_mppi_controller/src/critics/path_angle_critic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,6 @@ namespace mppi::critics
void PathAngleCritic::initialize()
{
auto getParentParam = parameters_handler_->getParamGetter(parent_name_);
getParentParam(enforce_path_inversion_, "enforce_path_inversion", false);
float vx_min;
getParentParam(vx_min, "vx_min", -0.35);
if (fabs(vx_min) < 1e-6f) { // zero
Expand Down Expand Up @@ -62,15 +61,7 @@ void PathAngleCritic::initialize()

void PathAngleCritic::score(CriticData & data)
{
if (!enabled_) {
return;
}

geometry_msgs::msg::Pose goal = utils::getCriticGoal(data, enforce_path_inversion_);

if (utils::withinPositionGoalTolerance(
threshold_to_consider_, data.state.pose.pose, goal))
{
if (!enabled_ || data.state.local_path_length < threshold_to_consider_) {
return;
}

Expand Down
10 changes: 1 addition & 9 deletions nav2_mppi_controller/src/critics/path_follow_critic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,10 +22,7 @@ namespace mppi::critics
void PathFollowCritic::initialize()
{
auto getParentParam = parameters_handler_->getParamGetter(parent_name_);
getParentParam(enforce_path_inversion_, "enforce_path_inversion", false);

auto getParam = parameters_handler_->getParamGetter(name_);

getParam(
threshold_to_consider_,
"threshold_to_consider", 1.4f);
Expand All @@ -40,12 +37,7 @@ void PathFollowCritic::score(CriticData & data)
return;
}

geometry_msgs::msg::Pose goal = utils::getCriticGoal(data, enforce_path_inversion_);

if (data.path.x.size() < 2 ||
utils::withinPositionGoalTolerance(
threshold_to_consider_, data.state.pose.pose, goal))
{
if (data.path.x.size() < 2 || data.state.local_path_length < threshold_to_consider_) {
return;
}

Expand Down
8 changes: 1 addition & 7 deletions nav2_mppi_controller/src/critics/prefer_forward_critic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,6 @@ namespace mppi::critics
void PreferForwardCritic::initialize()
{
auto getParentParam = parameters_handler_->getParamGetter(parent_name_);
getParentParam(enforce_path_inversion_, "enforce_path_inversion", false);

auto getParam = parameters_handler_->getParamGetter(name_);
getParam(power_, "cost_power", 1);
getParam(weight_, "cost_weight", 5.0f);
Expand All @@ -41,11 +39,7 @@ void PreferForwardCritic::score(CriticData & data)
return;
}

geometry_msgs::msg::Pose goal = utils::getCriticGoal(data, enforce_path_inversion_);

if (utils::withinPositionGoalTolerance(
threshold_to_consider_, data.state.pose.pose, goal))
{
if (data.state.local_path_length < threshold_to_consider_) {
return;
}

Expand Down
Loading
Loading