Class Controller

Inheritance Relationships

Base Type

Class Documentation

class Controller : public robot_controllers_interface::Handle

Base class for a controller. Is derived from a Handle, so that controllers can be passed from ControllerManager::getHandle(), thus allowing controllers to access other controllers (to stack their commands.

Public Functions

inline Controller()

Default constructor, does almost nothing, all setup is done in init().

inline virtual ~Controller()

Ensure proper cleanup with virtual destructor.

inline virtual int init(const std::string &name, std::shared_ptr<rclcpp::Node> node, std::shared_ptr<ControllerManager> manager)

Initialize the controller and any required data structures.

Parameters:
  • name – Name of this controller.

  • node – Node handle for this controller.

  • manager – The controller manager instance, this is needed for the controller to get information about joints, etc.

Returns:

0 if succesfully configured, negative values are error codes.

virtual bool start() = 0

Attempt to start the controller. This should be called only by the ControllerManager instance.

Returns:

True if successfully started, false otherwise.

virtual bool stop(bool force) = 0

Attempt to stop the controller. This should be called only by the ControllerManager instance.

Parameters:

force – Should we force the controller to stop? Some controllers may wish to continue running until they absolutely have to stop.

Returns:

True if successfully stopped, false otherwise.

virtual bool reset() = 0

Cleanly reset the controller to it’s initial state. Some controllers may choose to stop themselves. This is mainly used in the case of the the robot exiting some fault condition.

Returns:

True if successfully reset, false otherwise.

virtual void update(const rclcpp::Time &time, const rclcpp::Duration &dt) = 0

This is the update loop for the controller.

Parameters:
  • time – The system time.

  • dt – The timestep since last call to update.

inline virtual std::string getName()

Get the name of this controller.

inline virtual std::string getType()

Get the type of this controller.

virtual std::vector<std::string> getCommandedNames() = 0

Get the names of joints/controllers which this controller commands.

virtual std::vector<std::string> getClaimedNames() = 0

Get the names of joints/controllers which this controller exclusively claims.