Steered-wheel base controller. More...
#include <algorithm>
#include <exception>
#include <set>
#include <stdexcept>
#include <string>
#include <vector>
#include <angles/angles.h>
#include <boost/foreach.hpp>
#include <boost/math/special_functions/sign.hpp>
#include <boost/shared_ptr.hpp>
#include <control_toolbox/pid.h>
#include <controller_interface/controller_base.h>
#include <Eigen/Core>
#include <Eigen/Geometry>
#include <Eigen/SVD>
#include <geometry_msgs/Twist.h>
#include <hardware_interface/joint_command_interface.h>
#include <kdl/chainfksolverpos_recursive.hpp>
#include <kdl_parser/kdl_parser.hpp>
#include <nav_msgs/Odometry.h>
#include <pluginlib/class_list_macros.h>
#include <realtime_tools/realtime_publisher.h>
#include <tf/tfMessage.h>
#include <tf/transform_datatypes.h>
#include <urdf/model.h>
Go to the source code of this file.
Classes | |
class | steered_wheel_base_controller::SteeredWheelBaseController |
struct | steered_wheel_base_controller::SteeredWheelBaseController::VelCmd |
Namespaces | |
namespace | steered_wheel_base_controller |
Steered-wheel base controller.
This file contains the source code for SteeredWheelBaseController, a base controller for mobile robots. It works with bases that have two or more independently-steerable driven wheels and zero or more omnidirectional passive wheels (e.g. swivel casters).
Subscribed Topics: cmd_vel (geometry_msgs/Twist) Velocity command, defined in the frame specified by the base_link parameter. The linear.x and linear.y fields specify the base's desired linear velocity, measured in meters per second. The angular.z field specifies the base's desired angular velocity, measured in radians per second.
Published Topics: odom (nav_msgs/Odometry) Odometry.
Parameters: ~robot_description_name (string, default: robot_description) Name of a parameter on the Parameter Server. The named parameter's value is URDF data that describes the robot. ~base_link (string, default: base_link) Link that specifies the frame in which cmd_vel is defined. The link specified by base_link must exist in the robot's URDF data. ~cmd_vel_timeout (float, default: 0.5) If cmd_vel_timeout is greater than zero and this controller does not receive a velocity command for more than cmd_vel_timeout seconds, wheel motion is paused until a command is received. If cmd_vel_timeout is less than or equal to zero, the command timeout is disabled.
~linear_speed_limit (float, default: 1.0) Linear speed limit. If linear_speed_limit is less than zero, the linear speed limit is disabled. Unit: m/s. ~linear_acceleration_limit (float, default: 1.0) Linear acceleration limit. If linear_acceleration_limit is less than zero, the linear acceleration limit is disabled. Unit: m/s**2. ~linear_deceleration_limit (float, default: -1.0) Linear deceleration limit. If linear_deceleration_limit is less than or equal to zero, the linear deceleration limit is disabled. Unit: m/s**2.
~yaw_speed_limit (float, default: 1.0) Yaw speed limit. If yaw_speed_limit is less than zero, the yaw speed limit is disabled. Unit: rad/s. ~yaw_acceleration_limit (float, default: 1.0) Yaw acceleration limit. If yaw_acceleration_limit is less than zero, the yaw acceleration limit is disabled. Unit: rad/s**2. ~yaw_deceleration_limit (float, default: -1.0) Yaw deceleration limit. If yaw_deceleration_limit is less than or equal to zero, the yaw deceleration limit is disabled. Unit: rad/s**2.
~full_axle_speed_angle (float, default: 0.7854) If the difference between a wheel's desired and measured steering angles is less than or equal to full_axle_speed_angle, the wheel's axle will rotate at the speed determined by the current velocity command, subject to the speed, acceleration, and deceleration limits. full_axle_speed_angle must be less than zero_axle_speed_angle. Range: [0, pi]. Unit: radian. ~zero_axle_speed_angle (float, default: 1.5708) If the difference between a wheel's desired and measured steering angles is greater than or equal to zero_axle_speed_angle, the wheel's axle will stop rotating, subject to the deceleration limits. zero_axle_speed_angle must be greater than full_axle_speed_angle. Range: [0, pi]. Unit: radian.
~wheels (sequence of mappings, default: empty) Two or more steered wheels.
Key-Value Pairs:
steering_joint (string) Steering joint. axle_joint (string) Axle joint. diameter (float) Wheel diameter. It must be greater than zero. Unit: meter. ~wheel_diameter_scale (float, default: 1.0) Scale applied to each wheel's diameter. It is used to correct for tire deformation. wheel_diameter_scale must be greater than zero. ~pid_gains/<joint name>=""> (mapping, default: empty) PID controller gains for the specified joint. Needed only for effort-controlled joints and velocity-controlled steering joints.
~odometry_publishing_frequency (float, default: 30.0) Odometry publishing frequency. If it is less than or equal to zero, odometry computation is disabled. Unit: hertz. ~publish_odometry_to_base_transform (bool, default: true) If "true," publish the transform from <odometry_frame> to <base_frame>. The transform is published to /tf. ~odometry_frame (string, default: odom) Odometry frame. ~base_frame (string, default: base_link) Base frame in the <odometry_frame>-to-<base_frame> transform provided by this controller. base_frame allows the controller to publish transforms from odometry_frame to a frame that is not a link in the robot's URDF data. For example, base_frame can be set to "base_footprint". This controller computes coordinates in <base_link> and they are not transformed into <base_frame>, so the transform from <base_link> to <base_frame> should consist a translation along the z axis only. The x and y translation values and all the rotation values should be zero. ~initial_x (float, default: 0.0) X coordinate of the base frame's initial position in the odometry frame. Unit: meter. ~initial_y (float, default: 0.0) Y coordinate of the base frame's initial position in the odometry frame. Unit: meter. ~initial_yaw (float, default: 0.0) Initial orientation of the base frame in the odometry frame. Range: [-pi, pi]. Unit: radian. ~x_sd (float, default: 0.0) Standard deviation of the x coordinate of the base frame's position in the odometry frame. x_sd must be greater than or equal to zero. Unit: meter. ~y_sd (float, default: 0.0) Standard deviation of the y coordinate of the base frame's position in the odometry frame. y_sd must be greater than or equal to zero. Unit: meter. ~yaw_sd (float, default: 0.0) Standard deviation of the yaw angle of the base frame's orientation in the odometry frame. yaw_sd must be greater than or equal to zero. Unit: radian. ~x_speed_sd (float, default: 0.0) Standard deviation of the base's x speed in the base frame. x_speed_sd must be greater than or equal to zero. Unit: m/s. ~y_speed_sd (float, default: 0.0) Standard deviation of the base's y speed in the base frame. y_speed_sd must be greater than or equal to zero. Unit: m/s. ~yaw_speed_sd (float, default: 0.0) Standard deviation of the base's yaw speed in the base frame. yaw_speed_sd must be greater than or equal to zero. Unit: rad/s.
Provided tf Transforms: <odometry_frame> to <base_frame> Specifies the base frame's pose in the odometry frame. This transform is provided only if odometry computation is enabled and publish_odometry_to_base_transform is "true."
Definition in file steered_wheel_base_controller.cpp.