steering_controllers_library

Library with shared functionalities for mobile robot controllers with steering drives, with so-called non-holonomic constraints.

The library implements generic odometry and update methods and defines the main interfaces.

The update methods only use inverse kinematics, it does not implement any feedback control loops like path-tracking controllers etc.

For an introduction to mobile robot kinematics and the nomenclature used here, see mobile_robot_kinematics.

Execution logic of the controller

The controller uses velocity input, i.e., stamped twist messages where linear x and angular z components are used. Values in other components are ignored.

In the chain mode the controller provides two reference interfaces, one for linear velocity and one for steering angle position. Other relevant features are:

  • support for front and rear steering configurations;

  • odometry publishing as Odometry and TF message;

  • input command timeout based on a parameter.

The command for the wheels are calculated using odometry library where based on concrete kinematics traction and steering commands are calculated.

Currently implemented kinematics

  • Bicycle - with one steering and one drive joints;

  • Tricylce - with one steering and two drive joints;

  • Ackermann - with two steering and two drive joints.

Description of controller’s interfaces

References (from a preceding controller)

Used when controller is in chained mode (in_chained_mode == true).

  • <controller_name>/linear/velocity double, in m/s

  • <controller_name>/angular/velocity double, in rad/s

representing the body twist.

Command interfaces

If parameter front_steering == true

  • <front_wheels_names[i]>/position double, in rad

  • <rear_wheels_names[i]>/velocity double, in m/s

If parameter front_steering == false

  • <front_wheels_names[i]>/velocity double, in m/s

  • <rear_wheels_names[i]>/position double, in rad

State interfaces

Depending on the position_feedback, different feedback types are expected

  • position_feedback == true –> TRACTION_FEEDBACK_TYPE = position

  • position_feedback == false –> TRACTION_FEEDBACK_TYPE = velocity

If parameter front_steering == true

  • <front_wheels_names[i]>/position double, in rad

  • <rear_wheels_names[i]>/<TRACTION_FEEDBACK_TYPE> double, in m or m/s

If parameter front_steering == false

  • <front_wheels_names[i]>/<TRACTION_FEEDBACK_TYPE> double, in m or m/s

  • <rear_wheels_names[i]>/position double, in rad

Subscribers

Used when controller is not in chained mode (in_chained_mode == false).

Publishers

Parameters

This controller uses the generate_parameter_library to handle its parameters.

For an exemplary parameterization see the test folder of the controller’s package.