Nav2 Navigation Stack - jazzy
jazzy
ROS 2 Navigation Stack
|
controller interface that acts as a virtual base class for all controller plugins More...
#include <nav2_core/include/nav2_core/controller.hpp>
Public Types | |
using | Ptr = std::shared_ptr< nav2_core::Controller > |
Public Member Functions | |
virtual | ~Controller () |
Virtual destructor. | |
virtual void | configure (const rclcpp_lifecycle::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 deactive 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. | |
controller interface that acts as a virtual base class for all controller plugins
Definition at line 60 of file controller.hpp.
|
inlinevirtual |
Cancel the current control action.
Reimplemented in nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController.
Definition at line 124 of file controller.hpp.
|
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.
pose | Current robot pose |
velocity | Current robot velocity |
goal_checker | Pointer to the current goal checker the task is utilizing |
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.
|
pure virtual |
parent | pointer to user's node |
costmap_ros | A pointer to the costmap |
Implemented in nav2_rotation_shim_controller::RotationShimController, nav2_graceful_controller::GracefulController, dwb_core::DWBLocalPlanner, nav2_mppi_controller::MPPIController, and nav2_system_tests::UnknownErrorController.
|
pure virtual |
local setPlan - Sets the global plan
path | The global plan |
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.
|
pure virtual |
Limits the maximum linear speed of the robot.
speed_limit | expressed in absolute value (in m/s) or in percentage from maximum robot speed. |
percentage | Setting 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.