Classes | Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
diff_drive_controller::DiffDriveController Class Reference

#include <diff_drive_controller.h>

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

Classes

struct  Commands
 Velocity command related: More...
 
struct  DynamicParams
 

Public Member Functions

 DiffDriveController ()
 
bool init (hardware_interface::VelocityJointInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
 Initialize controller. More...
 
void starting (const ros::Time &time)
 Starts controller. More...
 
void stopping (const ros::Time &)
 Stops controller. More...
 
void update (const ros::Time &time, const ros::Duration &period)
 Updates controller, i.e. computes the odometry and sets the new velocity commands. More...
 
- Public Member Functions inherited from controller_interface::Controller< hardware_interface::VelocityJointInterface >
 Controller ()
 
virtual bool init (hardware_interface::VelocityJointInterface *, ros::NodeHandle &)
 
virtual ~Controller ()
 
- Public Member Functions inherited from controller_interface::ControllerBase
 ControllerBase ()
 
bool isRunning ()
 
bool isRunning ()
 
bool startRequest (const ros::Time &time)
 
bool startRequest (const ros::Time &time)
 
bool stopRequest (const ros::Time &time)
 
bool stopRequest (const ros::Time &time)
 
void updateRequest (const ros::Time &time, const ros::Duration &period)
 
void updateRequest (const ros::Time &time, const ros::Duration &period)
 
virtual ~ControllerBase ()
 

Private Types

typedef dynamic_reconfigure::Server< DiffDriveControllerConfig > ReconfigureServer
 Dynamic Reconfigure server. More...
 

Private Member Functions

void brake ()
 Brakes the wheels, i.e. sets the velocity to 0. More...
 
void cmdVelCallback (const geometry_msgs::Twist &command)
 Velocity command callback. More...
 
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. More...
 
void reconfCallback (DiffDriveControllerConfig &config, uint32_t)
 Callback for dynamic_reconfigure server. More...
 
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. More...
 
void setOdomPubFields (ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
 Sets the odometry publishing fields. More...
 
void updateDynamicParams ()
 Update the dynamic parameters in the RT loop. More...
 

Private Attributes

bool allow_multiple_cmd_vel_publishers_
 Whether to allow multiple publishers on cmd_vel topic or not: More...
 
std::string base_frame_id_
 Frame to use for the robot base: More...
 
boost::shared_ptr< realtime_tools::RealtimePublisher< geometry_msgs::TwistStamped > > cmd_vel_pub_
 Publish executed commands. More...
 
double cmd_vel_timeout_
 Timeout to consider cmd_vel commands old: More...
 
realtime_tools::RealtimeBuffer< Commandscommand_
 
Commands command_struct_
 
boost::shared_ptr< ReconfigureServerdyn_reconf_server_
 
realtime_tools::RealtimeBuffer< DynamicParamsdynamic_params_
 
bool enable_odom_tf_
 Whether to publish odometry to tf or not: More...
 
Commands last0_cmd_
 
Commands last1_cmd_
 Speed limiters: More...
 
ros::Time last_state_publish_time_
 
std::vector< hardware_interface::JointHandleleft_wheel_joints_
 Hardware handles: More...
 
double left_wheel_radius_multiplier_
 
SpeedLimiter limiter_ang_
 
SpeedLimiter limiter_lin_
 
std::string name_
 
std::string odom_frame_id_
 Frame to use for odometry and odom tf: More...
 
boost::shared_ptr< realtime_tools::RealtimePublisher< nav_msgs::Odometry > > odom_pub_
 Odometry related: More...
 
Odometry odometry_
 
bool open_loop_
 
bool publish_cmd_
 Publish limited velocity: More...
 
ros::Duration publish_period_
 Odometry related: More...
 
std::vector< hardware_interface::JointHandleright_wheel_joints_
 
double right_wheel_radius_multiplier_
 
ros::Subscriber sub_command_
 
boost::shared_ptr< realtime_tools::RealtimePublisher< tf::tfMessage > > tf_odom_pub_
 
size_t wheel_joints_size_
 Number of wheel joints: More...
 
double wheel_radius_
 Wheel radius (assuming it's the same for the left and right wheels): More...
 
double wheel_separation_
 Wheel separation, wrt the midpoint of the wheel width: More...
 
double wheel_separation_multiplier_
 Wheel separation and radius calibration multipliers: More...
 

Additional Inherited Members

- Public Types inherited from controller_interface::ControllerBase
typedef std::vector< hardware_interface::InterfaceResourcesClaimedResources
 
- Public Attributes inherited from controller_interface::ControllerBase
 CONSTRUCTED
 
 INITIALIZED
 
 RUNNING
 
enum controller_interface::ControllerBase:: { ... }  state_
 
- Protected Member Functions inherited from controller_interface::Controller< hardware_interface::VelocityJointInterface >
std::string getHardwareInterfaceType () const
 
virtual bool initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources)
 

Detailed Description

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

Definition at line 66 of file diff_drive_controller.h.

Member Typedef Documentation

typedef dynamic_reconfigure::Server<DiffDriveControllerConfig> diff_drive_controller::DiffDriveController::ReconfigureServer
private

Dynamic Reconfigure server.

Definition at line 217 of file diff_drive_controller.h.

Constructor & Destructor Documentation

diff_drive_controller::DiffDriveController::DiffDriveController ( )

Definition at line 152 of file diff_drive_controller.cpp.

Member Function Documentation

void diff_drive_controller::DiffDriveController::brake ( )
private

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

Definition at line 479 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 489 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 518 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.

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

void diff_drive_controller::DiffDriveController::reconfCallback ( DiffDriveControllerConfig &  config,
uint32_t   
)
private

Callback for dynamic_reconfigure server.

Parameters
configThe config set from dynamic_reconfigure server
levelnot used at this time.
See also
dyn_reconf_server_

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

Parameters
root_nhRoot node handle
controller_nhNode handle inside the controller namespace

Definition at line 640 of file diff_drive_controller.cpp.

void diff_drive_controller::DiffDriveController::starting ( const ros::Time time)
virtual

Starts controller.

Parameters
timeCurrent time

Reimplemented from controller_interface::ControllerBase.

Definition at line 464 of file diff_drive_controller.cpp.

void diff_drive_controller::DiffDriveController::stopping ( const ros::Time )
virtual

Stops controller.

Parameters
timeCurrent time

Reimplemented from controller_interface::ControllerBase.

Definition at line 474 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 352 of file diff_drive_controller.cpp.

void diff_drive_controller::DiffDriveController::updateDynamicParams ( )
private

Update the dynamic parameters in the RT loop.

Definition at line 703 of file diff_drive_controller.cpp.

Member Data Documentation

bool diff_drive_controller::DiffDriveController::allow_multiple_cmd_vel_publishers_
private

Whether to allow multiple publishers on cmd_vel topic or not:

Definition at line 149 of file diff_drive_controller.h.

std::string diff_drive_controller::DiffDriveController::base_frame_id_
private

Frame to use for the robot base:

Definition at line 152 of file diff_drive_controller.h.

boost::shared_ptr<realtime_tools::RealtimePublisher<geometry_msgs::TwistStamped> > diff_drive_controller::DiffDriveController::cmd_vel_pub_
private

Publish executed commands.

Definition at line 127 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 146 of file diff_drive_controller.h.

realtime_tools::RealtimeBuffer<Commands> diff_drive_controller::DiffDriveController::command_
private

Definition at line 122 of file diff_drive_controller.h.

Commands diff_drive_controller::DiffDriveController::command_struct_
private

Definition at line 123 of file diff_drive_controller.h.

boost::shared_ptr<ReconfigureServer> diff_drive_controller::DiffDriveController::dyn_reconf_server_
private

Definition at line 218 of file diff_drive_controller.h.

realtime_tools::RealtimeBuffer<DynamicParams> diff_drive_controller::DiffDriveController::dynamic_params_
private

Definition at line 214 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 158 of file diff_drive_controller.h.

Commands diff_drive_controller::DiffDriveController::last0_cmd_
private

Definition at line 165 of file diff_drive_controller.h.

Commands diff_drive_controller::DiffDriveController::last1_cmd_
private

Speed limiters:

Definition at line 164 of file diff_drive_controller.h.

ros::Time diff_drive_controller::DiffDriveController::last_state_publish_time_
private

Definition at line 106 of file diff_drive_controller.h.

std::vector<hardware_interface::JointHandle> diff_drive_controller::DiffDriveController::left_wheel_joints_
private

Hardware handles:

Definition at line 110 of file diff_drive_controller.h.

double diff_drive_controller::DiffDriveController::left_wheel_radius_multiplier_
private

Definition at line 142 of file diff_drive_controller.h.

SpeedLimiter diff_drive_controller::DiffDriveController::limiter_ang_
private

Definition at line 167 of file diff_drive_controller.h.

SpeedLimiter diff_drive_controller::DiffDriveController::limiter_lin_
private

Definition at line 166 of file diff_drive_controller.h.

std::string diff_drive_controller::DiffDriveController::name_
private

Definition at line 102 of file diff_drive_controller.h.

std::string diff_drive_controller::DiffDriveController::odom_frame_id_
private

Frame to use for odometry and odom tf:

Definition at line 155 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 130 of file diff_drive_controller.h.

Odometry diff_drive_controller::DiffDriveController::odometry_
private

Definition at line 132 of file diff_drive_controller.h.

bool diff_drive_controller::DiffDriveController::open_loop_
private

Definition at line 107 of file diff_drive_controller.h.

bool diff_drive_controller::DiffDriveController::publish_cmd_
private

Publish limited velocity:

Definition at line 170 of file diff_drive_controller.h.

ros::Duration diff_drive_controller::DiffDriveController::publish_period_
private

Odometry related:

Definition at line 105 of file diff_drive_controller.h.

std::vector<hardware_interface::JointHandle> diff_drive_controller::DiffDriveController::right_wheel_joints_
private

Definition at line 111 of file diff_drive_controller.h.

double diff_drive_controller::DiffDriveController::right_wheel_radius_multiplier_
private

Definition at line 143 of file diff_drive_controller.h.

ros::Subscriber diff_drive_controller::DiffDriveController::sub_command_
private

Definition at line 124 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 131 of file diff_drive_controller.h.

size_t diff_drive_controller::DiffDriveController::wheel_joints_size_
private

Number of wheel joints:

Definition at line 161 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 138 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 135 of file diff_drive_controller.h.

double diff_drive_controller::DiffDriveController::wheel_separation_multiplier_
private

Wheel separation and radius calibration multipliers:

Definition at line 141 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 Thu Apr 11 2019 03:08:07