Skip to content

Robot Controller

Goran Huskić edited this page May 21, 2017 · 18 revisions

Robot Controller

The robot controller is the path following control algorithm that makes the robot drive on the desired path (PID, OrthExp, HBZ ...). In this system, we provide a dozen of state-of-the-art controllers, and for the details, please visit Controllers.

The controller basically takes care of the following tasks:

  • Compute a unified move command (see below)
  • Convert the unified command to a model specific command and publishes it on the appropriate topic (e.g. a geometry_msgs::Twist on /cmd_vel)
  • Provide an "emergency break" functionality that allows other modules to immediately stop the robot, for example if an obstacle was detected.

In the common process cycle, first the controller is asked to compute a new move command. This command is passed to the obstacle avoider, who may modify it to avoid collisions. Finally the (maybe modified) command is passed back to the controller who converts it to a ROS message and publishes it.

The Unified Move Command

The move command is stored in a unified format, defined by the class MoveCommand. It contains desired direction and speed, as well as rotation (if supported), without defining any model specific variables. Thus, the move command can be processed outside of the controller by the obstacle avoider without knowledge about the used controller, allowing us to define model/controller-independent obstacle avoiders and exchange them easily.

Implement new Controllers

Basically, all you have to do to implement a new controller, is to create a class that inherits from RobotController. This section is a brief guide on how to do that and how to integrate the new class into the framework so that it can be used.

Naming Convention

The name of the class should satisfy the following template:

RobotController_{KinematicModel}_{ControllerType}

For example the PID controller for car-like robots (Ackermann drive) is called RobotController_Ackermann_PID.

The Interface

There are three abstract methods, each controller has to implement, one for each of the three tasks listed above:

  • virtual MoveCommandStatus computeMoveCommand(MoveCommand* cmd) Checks if the goal is reached and computes a new move command, returned via the output parameter cmd. The returned status can be one of MC_OKAY, MC_REACHED_GOAL, MC_ERROR, where MC_OKAY states, that the robot is still driving, while the other two mean, that the driving is finished, either because the goal is reached or because there was some error.
  • virtual void publishMoveCommand(const MoveCommand &cmd) const Takes a move command, converts it to a ROS message and publishes it. Use the publisher stored in RobotController::cmd_pub_ for publishing. Overwrite initPublisher() if the default publisher does not fit for your controller (see below).
  • virtual void stopMotion() Immediately publishes an appropriate command to the robot, that stops any movement. Make sure that the stop command is really published right away from within this method and not only queued until the next control cycle.

Furthermore, there are some optional methods that can be implemented, if needed:

  • virtual void initPublisher(ros::Publisher* pub) const: Initializes the publisher to send geometry_msgs::Twist messages to /cmd_vel. Overwrite this method, if you need another message type and/or topic.
  • virtual void start(): is called when the execution of a new path is started. Can be used for initialization stuff.
  • virtual void reset(): is called at several points, if new path is set or movement is aborted.
  • Several methods concerning the behaviour system. Those methods are likely to be removed from the general controller interface in the future.

Integrate the Controller

Once the controller class is implemented, it has to be integrated into the framework. To achieve this, . There are two things, you have to edit in this file:

  1. Register your controller to controller_factory by using

    REGISTER_ROBOT_CONTROLLER(RobotController_my_awesome_controller, my_awesome_controller, my_awesome_collision_avoider);
    

    in your robotcontroller_my_awesome_controller.cpp file.

  2. Open the file launch/follower.launch and include your controller like

    <include file="$(find path_follower)/launch/follower_my_awesome_controller.launch" />
    

Specialized Launch File

The launch file has to be named follower_CONTROLLER_NAME.launch. It has to start the path_follower_node and set at least the parameter controller to the name of your new controller. See the launch files of the existing controllers for examples.

Once the specialized launch file is set up, you can use the new controller by setting the environment variable ROBOT_CONTROLLER before running the navigation launch files. The launch file of your controller will then automatically be used.

Example:

export ROBOT_CONTROLLER=my_awesome_controller
roslaunch navigation_launch full.launch