Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
nav2_mppi_controller::MPPIController Class Reference
Inheritance diagram for nav2_mppi_controller::MPPIController:
Inheritance graph
[legend]
Collaboration diagram for nav2_mppi_controller::MPPIController:
Collaboration graph
[legend]

Public Member Functions

 MPPIController ()=default
 Constructor for mppi::MPPIController.
 
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. More...
 
void cleanup () override
 Cleanup resources.
 
void activate () override
 Activate controller.
 
void deactivate () override
 Deactivate controller.
 
void reset ()
 Reset the controller state between tasks.
 
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. More...
 
void setPlan (const nav_msgs::msg::Path &path) override
 Set new reference path to track. More...
 
void setSpeedLimit (const double &speed_limit, const bool &percentage) override
 Set new speed limit from callback. More...
 
- Public Member Functions inherited from nav2_core::Controller
virtual ~Controller ()
 Virtual destructor.
 

Protected Member Functions

void visualize (nav_msgs::msg::Path transformed_plan)
 Visualize trajectories. More...
 

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::Costmap2DROScostmap_ros_
 
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
 
std::unique_ptr< ParametersHandlerparameters_handler_
 
Optimizer optimizer_
 
PathHandler path_handler_
 
TrajectoryVisualizer trajectory_visualizer_
 
bool visualize_
 
double reset_period_
 
rclcpp::Time last_time_called_
 

Additional Inherited Members

- Public Types inherited from nav2_core::Controller
using Ptr = std::shared_ptr< nav2_core::Controller >
 

Detailed Description

Definition at line 40 of file controller.hpp.

Member Function Documentation

◆ computeVelocityCommands()

geometry_msgs::msg::TwistStamped nav2_mppi_controller::MPPIController::computeVelocityCommands ( const geometry_msgs::msg::PoseStamped &  robot_pose,
const geometry_msgs::msg::Twist &  robot_speed,
nav2_core::GoalChecker goal_checker 
)
overridevirtual

Main method to compute velocities using the optimizer.

Parameters
robot_poseRobot pose
robot_speedRobot speed
goal_checkerPointer to the goal checker for awareness if completed task

Implements nav2_core::Controller.

Definition at line 80 of file controller.cpp.

References mppi::Optimizer::evalControl(), mppi::PathHandler::getTransformedGoal(), reset(), mppi::PathHandler::transformPath(), and visualize().

Here is the call graph for this function:

◆ configure()

void nav2_mppi_controller::MPPIController::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 
)
overridevirtual

Configure controller on bringup.

Parameters
parentWeakPtr to node
nameName of plugin
tfTF buffer to use
costmap_rosCostmap2DROS object of environment

Implements nav2_core::Controller.

Definition at line 25 of file controller.cpp.

References mppi::Optimizer::initialize(), mppi::PathHandler::initialize(), and mppi::TrajectoryVisualizer::on_configure().

Here is the call graph for this function:

◆ setPlan()

void nav2_mppi_controller::MPPIController::setPlan ( const nav_msgs::msg::Path &  path)
overridevirtual

Set new reference path to track.

Parameters
pathPath to track

Implements nav2_core::Controller.

Definition at line 125 of file controller.cpp.

References mppi::PathHandler::setPath().

Here is the call graph for this function:

◆ setSpeedLimit()

void nav2_mppi_controller::MPPIController::setSpeedLimit ( const double &  speed_limit,
const bool &  percentage 
)
overridevirtual

Set new speed limit from callback.

Parameters
speed_limitSpeed limit to use
percentageBool if the speed limit is absolute or relative

Implements nav2_core::Controller.

Definition at line 130 of file controller.cpp.

References mppi::Optimizer::setSpeedLimit().

Here is the call graph for this function:

◆ visualize()

void nav2_mppi_controller::MPPIController::visualize ( nav_msgs::msg::Path  transformed_plan)
protected

Visualize trajectories.

Parameters
transformed_planTransformed input plan

Definition at line 118 of file controller.cpp.

References mppi::TrajectoryVisualizer::add(), mppi::Optimizer::getGeneratedTrajectories(), mppi::Optimizer::getOptimizedTrajectory(), and mppi::TrajectoryVisualizer::visualize().

Referenced by computeVelocityCommands().

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

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