Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
Public Types | Public Member Functions | List of all members
nav2_core::Controller Class Referenceabstract

controller interface that acts as a virtual base class for all controller plugins More...

#include <nav2_core/include/nav2_core/controller.hpp>

Inheritance diagram for nav2_core::Controller:
Inheritance graph
[legend]

Public Types

using Ptr = std::shared_ptr< nav2_core::Controller >
 

Public Member Functions

virtual ~Controller ()
 Virtual destructor.
 
virtual void configure (const nav2::LifecycleNode::WeakPtr &, std::string name, std::shared_ptr< tf2_ros::Buffer >, std::shared_ptr< nav2_costmap_2d::Costmap2DROS >)=0
 
virtual void cleanup ()=0
 Method to cleanup resources.
 
virtual void activate ()=0
 Method to active planner and any threads involved in execution.
 
virtual void deactivate ()=0
 Method to deactivate planner and any threads involved in execution.
 
virtual void setPlan (const nav_msgs::msg::Path &path)=0
 local setPlan - Sets the global plan More...
 
virtual geometry_msgs::msg::TwistStamped computeVelocityCommands (const geometry_msgs::msg::PoseStamped &pose, const geometry_msgs::msg::Twist &velocity, nav2_core::GoalChecker *goal_checker)=0
 Controller computeVelocityCommands - calculates the best command given the current pose and velocity. More...
 
virtual bool cancel ()
 Cancel the current control action. More...
 
virtual void setSpeedLimit (const double &speed_limit, const bool &percentage)=0
 Limits the maximum linear speed of the robot. More...
 
virtual void reset ()
 Reset the state of the controller if necessary after task is exited.
 

Detailed Description

controller interface that acts as a virtual base class for all controller plugins

Definition at line 59 of file controller.hpp.

Member Function Documentation

◆ cancel()

virtual bool nav2_core::Controller::cancel ( )
inlinevirtual

Cancel the current control action.

Returns
True if the cancellation was successful. If false is returned, computeVelocityCommands will be called until cancel returns true.

Reimplemented in nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController.

Definition at line 123 of file controller.hpp.

◆ computeVelocityCommands()

virtual geometry_msgs::msg::TwistStamped nav2_core::Controller::computeVelocityCommands ( const geometry_msgs::msg::PoseStamped &  pose,
const geometry_msgs::msg::Twist &  velocity,
nav2_core::GoalChecker goal_checker 
)
pure virtual

Controller computeVelocityCommands - calculates the best command given the current pose and velocity.

It is presumed that the global plan is already set.

This is mostly a wrapper for the protected computeVelocityCommands function which has additional debugging info.

Parameters
poseCurrent robot pose
velocityCurrent robot velocity
goal_checkerPointer to the current goal checker the task is utilizing
Returns
The best command for the robot to drive

Implemented in nav2_mppi_controller::MPPIController, nav2_graceful_controller::GracefulController, nav2_rotation_shim_controller::RotationShimController, nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController, dwb_core::DWBLocalPlanner, and nav2_system_tests::UnknownErrorController.

◆ configure()

virtual void nav2_core::Controller::configure ( const nav2::LifecycleNode::WeakPtr &  ,
std::string  name,
std::shared_ptr< tf2_ros::Buffer >  ,
std::shared_ptr< nav2_costmap_2d::Costmap2DROS  
)
pure virtual

◆ setPlan()

virtual void nav2_core::Controller::setPlan ( const nav_msgs::msg::Path &  path)
pure virtual

◆ setSpeedLimit()

virtual void nav2_core::Controller::setSpeedLimit ( const double &  speed_limit,
const bool &  percentage 
)
pure virtual

Limits the maximum linear speed of the robot.

Parameters
speed_limitexpressed in absolute value (in m/s) or in percentage from maximum robot speed.
percentageSetting speed limit in percentage if true or in absolute values in false case.

Implemented in nav2_rotation_shim_controller::RotationShimController, nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController, nav2_mppi_controller::MPPIController, nav2_graceful_controller::GracefulController, dwb_core::DWBLocalPlanner, and nav2_system_tests::UnknownErrorController.


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