Class MPPIController

Inheritance Relationships

Base Type

  • public nav2_core::Controller

Class Documentation

class MPPIController : public nav2_core::Controller

Public Functions

MPPIController() = default

Constructor for mppi::MPPIController.

virtual void configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, std::string name, const std::shared_ptr<tf2_ros::Buffer> tf, const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) override

Configure controller on bringup.

Parameters:
  • parent – WeakPtr to node

  • name – Name of plugin

  • tf – TF buffer to use

  • costmap_ros – Costmap2DROS object of environment

virtual void cleanup() override

Cleanup resources.

virtual void activate() override

Activate controller.

virtual void deactivate() override

Deactivate controller.

void reset()

Reset the controller state between tasks.

virtual geometry_msgs::msg::TwistStamped computeVelocityCommands(const geometry_msgs::msg::PoseStamped &robot_pose, const geometry_msgs::msg::Twist &robot_speed, nav2_core::GoalChecker *goal_checker) override

Main method to compute velocities using the optimizer.

Parameters:
  • robot_pose – Robot pose

  • robot_speed – Robot speed

  • goal_checker – Pointer to the goal checker for awareness if completed task

virtual void setPlan(const nav_msgs::msg::Path &path) override

Set new reference path to track.

Parameters:

path – Path to track

virtual void setSpeedLimit(const double &speed_limit, const bool &percentage) override

Set new speed limit from callback.

Parameters:
  • speed_limit – Speed limit to use

  • percentage – Bool if the speed limit is absolute or relative

Protected Functions

void visualize(nav_msgs::msg::Path transformed_plan)

Visualize trajectories.

Parameters:

transformed_plan – Transformed input plan

Protected Attributes

std::string name_
rclcpp_lifecycle::LifecycleNode::WeakPtr parent_
rclcpp::Clock::SharedPtr clock_
rclcpp::Logger logger_ = {rclcpp::get_logger("MPPIController")}
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_
std::shared_ptr<tf2_ros::Buffer> tf_buffer_
std::unique_ptr<ParametersHandler> parameters_handler_
Optimizer optimizer_
PathHandler path_handler_
TrajectoryVisualizer trajectory_visualizer_
bool visualize_
double reset_period_
rclcpp::Time last_time_called_