Class Controller

Class Documentation

class Controller

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

Public Types

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

Public Functions

inline 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
Parameters:
  • parent – pointer to user’s node

  • costmap_ros – A pointer to the costmap

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

Parameters:

path – The global plan

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.

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:
  • pose – Current robot pose

  • velocity – Current robot velocity

  • goal_checker – Pointer to the current goal checker the task is utilizing

Returns:

The best command for the robot to drive

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

Limits the maximum linear speed of the robot.

Parameters:
  • 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.