Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
mppi::critics::CostCritic Class Reference

Critic objective function for avoiding obstacles using costmap's inflated cost. More...

#include <nav2_mppi_controller/include/nav2_mppi_controller/critics/cost_critic.hpp>

Inheritance diagram for mppi::critics::CostCritic:
Inheritance graph
[legend]
Collaboration diagram for mppi::critics::CostCritic:
Collaboration graph
[legend]

Public Member Functions

void initialize () override
 Initialize critic.
 
void score (CriticData &data) override
 Evaluate cost related to obstacle avoidance. More...
 
- Public Member Functions inherited from mppi::critics::CriticFunction
 CriticFunction ()=default
 Constructor for mppi::critics::CriticFunction.
 
virtual ~CriticFunction ()=default
 Destructor for mppi::critics::CriticFunction.
 
void on_configure (rclcpp_lifecycle::LifecycleNode::WeakPtr parent, const std::string &parent_name, const std::string &name, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros, ParametersHandler *param_handler)
 Configure critic on bringup. More...
 
std::string getName ()
 Get name of critic.
 

Protected Member Functions

bool inCollision (float cost, float x, float y, float theta)
 Checks if cost represents a collision. More...
 
float costAtPose (float x, float y)
 cost at a robot pose More...
 
float findCircumscribedCost (std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap)
 Find the min cost of the inflation decay function for which the robot MAY be in collision in any orientation. More...
 

Protected Attributes

nav2_costmap_2d::FootprintCollisionChecker< nav2_costmap_2d::Costmap2D * > collision_checker_ {nullptr}
 
float possibly_inscribed_cost_
 
bool consider_footprint_ {true}
 
float circumscribed_radius_ {0}
 
float circumscribed_cost_ {0}
 
float collision_cost_ {0}
 
float critical_cost_ {0}
 
float weight_ {0}
 
float near_goal_distance_
 
std::string inflation_layer_name_
 
unsigned int power_ {0}
 
- Protected Attributes inherited from mppi::critics::CriticFunction
bool enabled_
 
std::string name_
 
std::string parent_name_
 
rclcpp_lifecycle::LifecycleNode::WeakPtr parent_
 
std::shared_ptr< nav2_costmap_2d::Costmap2DROScostmap_ros_
 
nav2_costmap_2d::Costmap2Dcostmap_ {nullptr}
 
ParametersHandlerparameters_handler_
 
rclcpp::Logger logger_ {rclcpp::get_logger("MPPIController")}
 

Detailed Description

Critic objective function for avoiding obstacles using costmap's inflated cost.

Definition at line 35 of file cost_critic.hpp.

Member Function Documentation

◆ costAtPose()

float mppi::critics::CostCritic::costAtPose ( float  x,
float  y 
)
protected

cost at a robot pose

Parameters
xX of pose
yY of pose
Returns
Collision information at pose

Definition at line 214 of file cost_critic.cpp.

Referenced by score().

Here is the caller graph for this function:

◆ findCircumscribedCost()

float mppi::critics::CostCritic::findCircumscribedCost ( std::shared_ptr< nav2_costmap_2d::Costmap2DROS costmap)
protected

Find the min cost of the inflation decay function for which the robot MAY be in collision in any orientation.

Parameters
costmapCostmap2DROS to get minimum inscribed cost (e.g. 128 in inflation layer documentation)
Returns
double circumscribed cost, any higher than this and need to do full footprint collision checking since some element of the robot could be in collision

Definition at line 76 of file cost_critic.cpp.

Referenced by initialize(), and score().

Here is the caller graph for this function:

◆ inCollision()

bool mppi::critics::CostCritic::inCollision ( float  cost,
float  x,
float  y,
float  theta 
)
protected

Checks if cost represents a collision.

Parameters
costPoint cost at pose center
xX of pose
yY of pose
thetatheta of pose
Returns
bool if in collision
Parameters
costCostmap cost
Returns
bool if in collision

Definition at line 188 of file cost_critic.cpp.

References nav2_costmap_2d::FootprintCollisionChecker< CostmapT >::footprintCostAtPose().

Referenced by score().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ score()

void mppi::critics::CostCritic::score ( CriticData data)
overridevirtual

Evaluate cost related to obstacle avoidance.

Parameters
costs[out] add obstacle cost values to this tensor

Implements mppi::critics::CriticFunction.

Definition at line 121 of file cost_critic.cpp.

References costAtPose(), findCircumscribedCost(), and inCollision().

Here is the call graph for this function:

The documentation for this class was generated from the following files: