#include <diff_drive_controller.h>
Classes | |
struct | Commands |
Velocity command related: More... | |
Public Member Functions | |
DiffDriveController () | |
bool | init (hardware_interface::VelocityJointInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) |
Initialize controller. | |
void | starting (const ros::Time &time) |
Starts controller. | |
void | stopping (const ros::Time &time) |
Stops controller. | |
void | update (const ros::Time &time, const ros::Duration &period) |
Updates controller, i.e. computes the odometry and sets the new velocity commands. | |
Private Member Functions | |
void | brake () |
Brakes the wheels, i.e. sets the velocity to 0. | |
void | cmdVelCallback (const geometry_msgs::Twist &command) |
Velocity command callback. | |
bool | getWheelNames (ros::NodeHandle &controller_nh, const std::string &wheel_param, std::vector< std::string > &wheel_names) |
Get the wheel names from a wheel param. | |
bool | setOdomParamsFromUrdf (ros::NodeHandle &root_nh, const std::string &left_wheel_name, const std::string &right_wheel_name) |
Sets odometry parameters from the URDF, i.e. the wheel radius and separation. | |
void | setOdomPubFields (ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) |
Sets the odometry publishing fields. | |
Private Attributes | |
std::string | base_frame_id_ |
Frame to use for the robot base: | |
double | cmd_vel_timeout_ |
Timeout to consider cmd_vel commands old: | |
realtime_tools::RealtimeBuffer < Commands > | command_ |
Commands | command_struct_ |
bool | enable_odom_tf_ |
Whether to publish odometry to tf or not: | |
Commands | last_cmd_ |
ros::Time | last_state_publish_time_ |
std::vector < hardware_interface::JointHandle > | left_wheel_joints_ |
Hardware handles: | |
SpeedLimiter | limiter_ang_ |
SpeedLimiter | limiter_lin_ |
std::string | name_ |
geometry_msgs::TransformStamped | odom_frame_ |
boost::shared_ptr < realtime_tools::RealtimePublisher < nav_msgs::Odometry > > | odom_pub_ |
Odometry related: | |
Odometry | odometry_ |
ros::Duration | publish_period_ |
Publish rate related: | |
std::vector < hardware_interface::JointHandle > | right_wheel_joints_ |
ros::Subscriber | sub_command_ |
boost::shared_ptr < realtime_tools::RealtimePublisher < tf::tfMessage > > | tf_odom_pub_ |
size_t | wheel_joints_size_ |
Number of wheel joints: | |
double | wheel_radius_ |
Wheel radius (assuming it's the same for the left and right wheels): | |
double | wheel_radius_multiplier_ |
double | wheel_separation_ |
Wheel separation, wrt the midpoint of the wheel width: | |
double | wheel_separation_multiplier_ |
Wheel separation and radius calibration multipliers: |
This class makes some assumptions on the model of the robot:
Definition at line 63 of file diff_drive_controller.h.
Definition at line 108 of file diff_drive_controller.cpp.
void diff_drive_controller::DiffDriveController::brake | ( | ) | [private] |
Brakes the wheels, i.e. sets the velocity to 0.
Definition at line 328 of file diff_drive_controller.cpp.
void diff_drive_controller::DiffDriveController::cmdVelCallback | ( | const geometry_msgs::Twist & | command | ) | [private] |
Velocity command callback.
command | Velocity command message (twist) |
Definition at line 338 of file diff_drive_controller.cpp.
bool diff_drive_controller::DiffDriveController::getWheelNames | ( | ros::NodeHandle & | controller_nh, |
const std::string & | wheel_param, | ||
std::vector< std::string > & | wheel_names | ||
) | [private] |
Get the wheel names from a wheel param.
[in] | controller_nh | Controller node handler |
[in] | wheel_param | Param name |
[out] | wheel_names | Vector with the whel names |
Definition at line 358 of file diff_drive_controller.cpp.
bool diff_drive_controller::DiffDriveController::init | ( | hardware_interface::VelocityJointInterface * | hw, |
ros::NodeHandle & | root_nh, | ||
ros::NodeHandle & | controller_nh | ||
) | [virtual] |
Initialize controller.
hw | Velocity joint interface for the wheels |
root_nh | Node handle at root namespace |
controller_nh | Node handle inside the controller namespace |
Reimplemented from controller_interface::Controller< hardware_interface::VelocityJointInterface >.
Definition at line 121 of file diff_drive_controller.cpp.
bool diff_drive_controller::DiffDriveController::setOdomParamsFromUrdf | ( | ros::NodeHandle & | root_nh, |
const std::string & | left_wheel_name, | ||
const std::string & | right_wheel_name | ||
) | [private] |
Sets odometry parameters from the URDF, i.e. the wheel radius and separation.
root_nh | Root node handle |
left_wheel_name | Name of the left wheel joint |
right_wheel_name | Name of the right wheel joint |
Definition at line 401 of file diff_drive_controller.cpp.
void diff_drive_controller::DiffDriveController::setOdomPubFields | ( | ros::NodeHandle & | root_nh, |
ros::NodeHandle & | controller_nh | ||
) | [private] |
Sets the odometry publishing fields.
root_nh | Root node handle |
controller_nh | Node handle inside the controller namespace |
Definition at line 460 of file diff_drive_controller.cpp.
void diff_drive_controller::DiffDriveController::starting | ( | const ros::Time & | time | ) | [virtual] |
Starts controller.
time | Current time |
Reimplemented from controller_interface::ControllerBase.
Definition at line 315 of file diff_drive_controller.cpp.
void diff_drive_controller::DiffDriveController::stopping | ( | const ros::Time & | time | ) | [virtual] |
Stops controller.
time | Current time |
Reimplemented from controller_interface::ControllerBase.
Definition at line 323 of file diff_drive_controller.cpp.
void diff_drive_controller::DiffDriveController::update | ( | const ros::Time & | time, |
const ros::Duration & | period | ||
) | [virtual] |
Updates controller, i.e. computes the odometry and sets the new velocity commands.
time | Current time |
period | Time since the last called to update |
Implements controller_interface::ControllerBase.
Definition at line 228 of file diff_drive_controller.cpp.
std::string diff_drive_controller::DiffDriveController::base_frame_id_ [private] |
Frame to use for the robot base:
Definition at line 142 of file diff_drive_controller.h.
double diff_drive_controller::DiffDriveController::cmd_vel_timeout_ [private] |
Timeout to consider cmd_vel commands old:
Definition at line 139 of file diff_drive_controller.h.
realtime_tools::RealtimeBuffer<Commands> diff_drive_controller::DiffDriveController::command_ [private] |
Definition at line 118 of file diff_drive_controller.h.
Definition at line 119 of file diff_drive_controller.h.
bool diff_drive_controller::DiffDriveController::enable_odom_tf_ [private] |
Whether to publish odometry to tf or not:
Definition at line 145 of file diff_drive_controller.h.
Definition at line 151 of file diff_drive_controller.h.
Definition at line 103 of file diff_drive_controller.h.
std::vector<hardware_interface::JointHandle> diff_drive_controller::DiffDriveController::left_wheel_joints_ [private] |
Hardware handles:
Definition at line 106 of file diff_drive_controller.h.
Definition at line 153 of file diff_drive_controller.h.
Definition at line 152 of file diff_drive_controller.h.
std::string diff_drive_controller::DiffDriveController::name_ [private] |
Definition at line 99 of file diff_drive_controller.h.
geometry_msgs::TransformStamped diff_drive_controller::DiffDriveController::odom_frame_ [private] |
Definition at line 126 of file diff_drive_controller.h.
boost::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::Odometry> > diff_drive_controller::DiffDriveController::odom_pub_ [private] |
Odometry related:
Definition at line 123 of file diff_drive_controller.h.
Definition at line 125 of file diff_drive_controller.h.
Publish rate related:
Definition at line 102 of file diff_drive_controller.h.
std::vector<hardware_interface::JointHandle> diff_drive_controller::DiffDriveController::right_wheel_joints_ [private] |
Definition at line 107 of file diff_drive_controller.h.
Definition at line 120 of file diff_drive_controller.h.
boost::shared_ptr<realtime_tools::RealtimePublisher<tf::tfMessage> > diff_drive_controller::DiffDriveController::tf_odom_pub_ [private] |
Definition at line 124 of file diff_drive_controller.h.
size_t diff_drive_controller::DiffDriveController::wheel_joints_size_ [private] |
Number of wheel joints:
Definition at line 148 of file diff_drive_controller.h.
double diff_drive_controller::DiffDriveController::wheel_radius_ [private] |
Wheel radius (assuming it's the same for the left and right wheels):
Definition at line 132 of file diff_drive_controller.h.
double diff_drive_controller::DiffDriveController::wheel_radius_multiplier_ [private] |
Definition at line 136 of file diff_drive_controller.h.
double diff_drive_controller::DiffDriveController::wheel_separation_ [private] |
Wheel separation, wrt the midpoint of the wheel width:
Definition at line 129 of file diff_drive_controller.h.
Wheel separation and radius calibration multipliers:
Definition at line 135 of file diff_drive_controller.h.