|
Nav2 Navigation Stack - rolling
main
ROS 2 Navigation Stack
|
Critic objective function for avoiding obstacles using costmap's inflated cost. More...
#include <nav2_mppi_controller/include/nav2_mppi_controller/critics/cost_critic.hpp>


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 (nav2::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 | 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... | |
| bool | worldToMapFloat (float wx, float wy, unsigned int &mx, unsigned int &my) const |
| An implementation of worldToMap fully using floats. More... | |
| unsigned int | getIndex (unsigned int mx, unsigned int my) const |
| A local implementation of getIndex. More... | |
Protected Attributes | |
| nav2_costmap_2d::FootprintCollisionChecker< nav2_costmap_2d::Costmap2D * > | collision_checker_ {nullptr} |
| float | possible_collision_cost_ |
| bool | consider_footprint_ {true} |
| bool | is_tracking_unknown_ {true} |
| float | circumscribed_radius_ {0.0f} |
| float | circumscribed_cost_ {0.0f} |
| float | collision_cost_ {0.0f} |
| float | critical_cost_ {0.0f} |
| unsigned int | near_collision_cost_ {253} |
| float | weight_ {0} |
| unsigned int | trajectory_point_step_ |
| float | origin_x_ |
| float | origin_y_ |
| float | resolution_ |
| unsigned int | size_x_ |
| unsigned int | size_y_ |
| 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_ |
| nav2::LifecycleNode::WeakPtr | parent_ |
| std::shared_ptr< nav2_costmap_2d::Costmap2DROS > | costmap_ros_ |
| nav2_costmap_2d::Costmap2D * | costmap_ {nullptr} |
| ParametersHandler * | parameters_handler_ |
| rclcpp::Logger | logger_ {rclcpp::get_logger("MPPIController")} |
Critic objective function for avoiding obstacles using costmap's inflated cost.
Definition at line 35 of file cost_critic.hpp.
|
inlineprotected |
Find the min cost of the inflation decay function for which the robot MAY be in collision in any orientation.
| costmap | Costmap2DROS to get minimum inscribed cost (e.g. 128 in inflation layer documentation) |
Definition at line 84 of file cost_critic.cpp.
Referenced by initialize(), and score().

|
inlineprotected |
A local implementation of getIndex.
| mx | unsigned int map X coord |
| my | unsigned into map Y coord |
Definition at line 121 of file cost_critic.hpp.
Referenced by nav2_simple_commander.costmap_2d.PyCostmap2D::getCostXY(), score(), and nav2_simple_commander.costmap_2d.PyCostmap2D::setCost().

|
inlineprotected |
Checks if cost represents a collision.
| cost | Point cost at pose center |
| x | X of pose |
| y | Y of pose |
| theta | theta of pose |
Definition at line 59 of file cost_critic.hpp.
References nav2_costmap_2d::FootprintCollisionChecker< CostmapT >::footprintCostAtPose().
Referenced by score().


|
overridevirtual |
Evaluate cost related to obstacle avoidance.
| costs | [out] add obstacle cost values to this tensor |
Implements mppi::critics::CriticFunction.
Definition at line 130 of file cost_critic.cpp.
References findCircumscribedCost(), nav2_costmap_2d::FootprintCollisionChecker< CostmapT >::getCostmap(), getIndex(), inCollision(), and worldToMapFloat().

|
inlineprotected |
An implementation of worldToMap fully using floats.
| wx | Float world X coord |
| wy | Float world Y coord |
| mx | unsigned int map X coord |
| my | unsigned into map Y coord |
Definition at line 100 of file cost_critic.hpp.
Referenced by score().
