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 &)
 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, bool lookup_wheel_separation, bool lookup_wheel_radius)
 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 last0_cmd_
Commands last1_cmd_
 Speed limiters:
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_
boost::shared_ptr
< realtime_tools::RealtimePublisher
< nav_msgs::Odometry > > 
odom_pub_
 Odometry related:
Odometry odometry_
bool open_loop_
ros::Duration publish_period_
 Odometry 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:

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 110 of file diff_drive_controller.cpp.


Member Function Documentation

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

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

Parameters:
[in]controller_nhController node handler
[in]wheel_paramParam name
[out]wheel_namesVector with the whel names
Returns:
true if the wheel_param is available and the wheel_names are retrieved successfully from the param server; false otherwise

Definition at line 392 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 124 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,
bool  lookup_wheel_separation,
bool  lookup_wheel_radius 
) [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 445 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 514 of file diff_drive_controller.cpp.

Starts controller.

Parameters:
timeCurrent time

Reimplemented from controller_interface::ControllerBase.

Definition at line 347 of file diff_drive_controller.cpp.

Stops controller.

Parameters:
timeCurrent time

Reimplemented from controller_interface::ControllerBase.

Definition at line 357 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 250 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 119 of file diff_drive_controller.h.

Definition at line 120 of file diff_drive_controller.h.

Whether to publish odometry to tf or not:

Definition at line 145 of file diff_drive_controller.h.

Definition at line 152 of file diff_drive_controller.h.

Speed limiters:

Definition at line 151 of file diff_drive_controller.h.

Definition at line 103 of file diff_drive_controller.h.

Hardware handles:

Definition at line 107 of file diff_drive_controller.h.

Definition at line 154 of file diff_drive_controller.h.

Definition at line 153 of file diff_drive_controller.h.

Definition at line 99 of file diff_drive_controller.h.

Odometry related:

Definition at line 124 of file diff_drive_controller.h.

Definition at line 126 of file diff_drive_controller.h.

Definition at line 104 of file diff_drive_controller.h.

Odometry related:

Definition at line 102 of file diff_drive_controller.h.

Definition at line 108 of file diff_drive_controller.h.

Definition at line 121 of file diff_drive_controller.h.

Definition at line 125 of file diff_drive_controller.h.

Number of wheel joints:

Definition at line 148 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 Sat Aug 13 2016 04:20:35