Classes | Public Member Functions | Private Member Functions | Private Attributes
diff_drive_controller::DiffDriveController Class Reference

#include <diff_drive_controller.h>

Inheritance diagram for diff_drive_controller::DiffDriveController:
Inheritance graph
[legend]

List of all members.

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 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_
Commands last_cmd_
ros::Time last_state_publish_time_
hardware_interface::JointHandle left_wheel_joint_
 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:
hardware_interface::JointHandle right_wheel_joint_
ros::Subscriber sub_command_
boost::shared_ptr
< realtime_tools::RealtimePublisher
< tf::tfMessage > > 
tf_odom_pub_
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:

Detailed Description

This class makes some assumptions on the model of the robot:

Definition at line 63 of file diff_drive_controller.h.


Constructor & Destructor Documentation

Definition at line 108 of file diff_drive_controller.cpp.


Member Function Documentation

Brakes the wheels, i.e. sets the velocity to 0.

Definition at line 277 of file diff_drive_controller.cpp.

void diff_drive_controller::DiffDriveController::cmdVelCallback ( const geometry_msgs::Twist &  command) [private]

Velocity command callback.

Parameters:
commandVelocity command message (twist)

Definition at line 284 of file diff_drive_controller.cpp.

Initialize controller.

Parameters:
hwVelocity joint interface for the wheels
root_nhNode handle at root namespace
controller_nhNode handle inside the controller namespace

Reimplemented from controller_interface::Controller< hardware_interface::VelocityJointInterface >.

Definition at line 119 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.

Parameters:
root_nhRoot node handle
left_wheel_nameName of the left wheel joint
right_wheel_nameName of the right wheel joint

Definition at line 304 of file diff_drive_controller.cpp.

Sets the odometry publishing fields.

Parameters:
root_nhRoot node handle
controller_nhNode handle inside the controller namespace

Definition at line 363 of file diff_drive_controller.cpp.

Starts controller.

Parameters:
timeCurrent time

Reimplemented from controller_interface::ControllerBase.

Definition at line 264 of file diff_drive_controller.cpp.

Stops controller.

Parameters:
timeCurrent time

Reimplemented from controller_interface::ControllerBase.

Definition at line 272 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.

Parameters:
timeCurrent time
periodTime since the last called to update

Implements controller_interface::ControllerBase.

Definition at line 195 of file diff_drive_controller.cpp.


Member Data Documentation

Frame to use for the robot base:

Definition at line 142 of file diff_drive_controller.h.

Timeout to consider cmd_vel commands old:

Definition at line 139 of file diff_drive_controller.h.

Definition at line 118 of file diff_drive_controller.h.

Definition at line 119 of file diff_drive_controller.h.

Definition at line 145 of file diff_drive_controller.h.

Definition at line 103 of file diff_drive_controller.h.

Hardware handles:

Definition at line 106 of file diff_drive_controller.h.

Definition at line 147 of file diff_drive_controller.h.

Definition at line 146 of file diff_drive_controller.h.

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.

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.

Definition at line 107 of file diff_drive_controller.h.

Definition at line 120 of file diff_drive_controller.h.

Definition at line 124 of file diff_drive_controller.h.

Wheel radius (assuming it's the same for the left and right wheels):

Definition at line 132 of file diff_drive_controller.h.

Definition at line 136 of file diff_drive_controller.h.

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.


The documentation for this class was generated from the following files:


diff_drive_controller
Author(s): Bence Magyar
autogenerated on Fri Aug 28 2015 12:36:52