Class CriticFunction

Inheritance Relationships

Derived Types

Class Documentation

class CriticFunction

Abstract critic objective function to score trajectories.

Subclassed by mppi::critics::ConstraintCritic, mppi::critics::CostCritic, mppi::critics::GoalAngleCritic, mppi::critics::GoalCritic, mppi::critics::ObstaclesCritic, mppi::critics::PathAlignCritic, mppi::critics::PathAlignLegacyCritic, mppi::critics::PathAngleCritic, mppi::critics::PathFollowCritic, mppi::critics::PreferForwardCritic, mppi::critics::TwirlingCritic, mppi::critics::VelocityDeadbandCritic

Public Functions

CriticFunction() = default

Constructor for mppi::critics::CriticFunction.

virtual ~CriticFunction() = default

Destructor for mppi::critics::CriticFunction.

inline 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.

Parameters:
  • parent – WeakPtr to node

  • parent_name – name of the controller

  • name – Name of plugin

  • costmap_ros – Costmap2DROS object of environment

  • dynamic_parameter_handlerParameter handler object

virtual void score(CriticData &data) = 0

Main function to score trajectory.

Parameters:

data – Critic data to use in scoring

virtual void initialize() = 0

Initialize critic.

inline std::string getName()

Get name of critic.

Protected Attributes

bool enabled_
std::string name_
std::string parent_name_
rclcpp_lifecycle::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")}