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 >
virtual bool init (T *, ros::NodeHandle &)
 
virtual bool init (T *, ros::NodeHandle &, ros::NodeHandle &)
 
- Public Member Functions inherited from controller_interface::ControllerBase
virtual void aborting (const ros::Time &)
 
virtual void aborting (const ros::Time &)
 
bool abortRequest (const ros::Time &time)
 
bool abortRequest (const ros::Time &time)
 
 ControllerBase ()=default
 
 ControllerBase (const ControllerBase &)=delete
 
 ControllerBase (ControllerBase &&)=delete
 
bool isAborted () const
 
bool isAborted () const
 
bool isInitialized () const
 
bool isInitialized () const
 
bool isRunning () const
 
bool isRunning () const
 
bool isStopped () const
 
bool isStopped () const
 
bool isWaiting () const
 
bool isWaiting () const
 
ControllerBaseoperator= (const ControllerBase &)=delete
 
ControllerBaseoperator= (ControllerBase &&)=delete
 
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 void waiting (const ros::Time &)
 
virtual void waiting (const ros::Time &)
 
bool waitRequest (const ros::Time &time)
 
bool waitRequest (const ros::Time &time)
 
virtual ~ControllerBase ()=default
 

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 publishWheelData (const ros::Time &time, const ros::Duration &period, Commands &curr_cmd, double wheel_separation, double left_wheel_radius, double right_wheel_radius)
 
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...
 
std::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_
 
std::shared_ptr< realtime_tools::RealtimePublisher< control_msgs::JointTrajectoryControllerState > > controller_state_pub_
 Controller state publisher. More...
 
std::shared_ptr< ReconfigureServerdyn_reconf_server_
 
boost::recursive_mutex dyn_reconf_server_mutex_
 
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...
 
std::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...
 
bool publish_wheel_joint_controller_state_
 Publish wheel data: More...
 
std::vector< hardware_interface::JointHandleright_wheel_joints_
 
double right_wheel_radius_multiplier_
 
ros::Subscriber sub_command_
 
std::shared_ptr< realtime_tools::RealtimePublisher< tf::tfMessage > > tf_odom_pub_
 
ros::Time time_previous_
 
double vel_left_desired_previous_
 Previous velocities from the encoders: More...
 
std::vector< double > vel_left_previous_
 Previous velocities from the encoders: More...
 
double vel_right_desired_previous_
 
std::vector< double > vel_right_previous_
 
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
 ABORTED
 
 CONSTRUCTED
 
 INITIALIZED
 
 RUNNING
 
enum controller_interface::ControllerBase:: { ... }  state_
 
 STOPPED
 
 WAITING
 
- Protected Member Functions inherited from controller_interface::Controller< hardware_interface::VelocityJointInterface >
std::string getHardwareInterfaceType () const
 
bool initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) override
 

Detailed Description

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

Definition at line 68 of file diff_drive_controller.h.

Member Typedef Documentation

◆ ReconfigureServer

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

Dynamic Reconfigure server.

Definition at line 236 of file diff_drive_controller.h.

Constructor & Destructor Documentation

◆ DiffDriveController()

diff_drive_controller::DiffDriveController::DiffDriveController ( )

Definition at line 146 of file diff_drive_controller.cpp.

Member Function Documentation

◆ brake()

void diff_drive_controller::DiffDriveController::brake ( )
private

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

Definition at line 520 of file diff_drive_controller.cpp.

◆ cmdVelCallback()

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

Velocity command callback.

Parameters
commandVelocity command message (twist)

Definition at line 530 of file diff_drive_controller.cpp.

◆ getWheelNames()

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

◆ init()

bool diff_drive_controller::DiffDriveController::init ( hardware_interface::VelocityJointInterface hw,
ros::NodeHandle root_nh,
ros::NodeHandle controller_nh 
)

Initialize controller.

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

Definition at line 165 of file diff_drive_controller.cpp.

◆ publishWheelData()

void diff_drive_controller::DiffDriveController::publishWheelData ( const ros::Time time,
const ros::Duration period,
Commands curr_cmd,
double  wheel_separation,
double  left_wheel_radius,
double  right_wheel_radius 
)
private
Parameters
timeCurrent time
periodTime since the last called to update
curr_cmdCurrent velocity command
wheel_separationwheel separation with multiplier
left_wheel_radiusleft wheel radius with multiplier
right_wheel_radiusright wheel radius with multiplier

Definition at line 763 of file diff_drive_controller.cpp.

◆ reconfCallback()

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

◆ setOdomParamsFromUrdf()

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

◆ setOdomPubFields()

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

◆ starting()

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

Starts controller.

Parameters
timeCurrent time

Reimplemented from controller_interface::ControllerBase.

Definition at line 504 of file diff_drive_controller.cpp.

◆ stopping()

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

Stops controller.

Parameters
timeCurrent time

Reimplemented from controller_interface::ControllerBase.

Definition at line 515 of file diff_drive_controller.cpp.

◆ update()

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

◆ updateDynamicParams()

void diff_drive_controller::DiffDriveController::updateDynamicParams ( )
private

Update the dynamic parameters in the RT loop.

Definition at line 750 of file diff_drive_controller.cpp.

Member Data Documentation

◆ allow_multiple_cmd_vel_publishers_

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 165 of file diff_drive_controller.h.

◆ base_frame_id_

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

Frame to use for the robot base:

Definition at line 168 of file diff_drive_controller.h.

◆ cmd_vel_pub_

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

Publish executed commands.

Definition at line 140 of file diff_drive_controller.h.

◆ cmd_vel_timeout_

double diff_drive_controller::DiffDriveController::cmd_vel_timeout_
private

Timeout to consider cmd_vel commands old:

Definition at line 162 of file diff_drive_controller.h.

◆ command_

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

Definition at line 135 of file diff_drive_controller.h.

◆ command_struct_

Commands diff_drive_controller::DiffDriveController::command_struct_
private

Definition at line 136 of file diff_drive_controller.h.

◆ controller_state_pub_

std::shared_ptr<realtime_tools::RealtimePublisher<control_msgs::JointTrajectoryControllerState> > diff_drive_controller::DiffDriveController::controller_state_pub_
private

Controller state publisher.

Definition at line 148 of file diff_drive_controller.h.

◆ dyn_reconf_server_

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

Definition at line 237 of file diff_drive_controller.h.

◆ dyn_reconf_server_mutex_

boost::recursive_mutex diff_drive_controller::DiffDriveController::dyn_reconf_server_mutex_
private

Definition at line 238 of file diff_drive_controller.h.

◆ dynamic_params_

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

Definition at line 233 of file diff_drive_controller.h.

◆ enable_odom_tf_

bool diff_drive_controller::DiffDriveController::enable_odom_tf_
private

Whether to publish odometry to tf or not:

Definition at line 174 of file diff_drive_controller.h.

◆ last0_cmd_

Commands diff_drive_controller::DiffDriveController::last0_cmd_
private

Definition at line 181 of file diff_drive_controller.h.

◆ last1_cmd_

Commands diff_drive_controller::DiffDriveController::last1_cmd_
private

Speed limiters:

Definition at line 180 of file diff_drive_controller.h.

◆ last_state_publish_time_

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

Definition at line 108 of file diff_drive_controller.h.

◆ left_wheel_joints_

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

Hardware handles:

Definition at line 112 of file diff_drive_controller.h.

◆ left_wheel_radius_multiplier_

double diff_drive_controller::DiffDriveController::left_wheel_radius_multiplier_
private

Definition at line 158 of file diff_drive_controller.h.

◆ limiter_ang_

SpeedLimiter diff_drive_controller::DiffDriveController::limiter_ang_
private

Definition at line 183 of file diff_drive_controller.h.

◆ limiter_lin_

SpeedLimiter diff_drive_controller::DiffDriveController::limiter_lin_
private

Definition at line 182 of file diff_drive_controller.h.

◆ name_

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

Definition at line 104 of file diff_drive_controller.h.

◆ odom_frame_id_

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

Frame to use for odometry and odom tf:

Definition at line 171 of file diff_drive_controller.h.

◆ odom_pub_

std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::Odometry> > diff_drive_controller::DiffDriveController::odom_pub_
private

Odometry related:

Definition at line 143 of file diff_drive_controller.h.

◆ odometry_

Odometry diff_drive_controller::DiffDriveController::odometry_
private

Definition at line 145 of file diff_drive_controller.h.

◆ open_loop_

bool diff_drive_controller::DiffDriveController::open_loop_
private

Definition at line 109 of file diff_drive_controller.h.

◆ publish_cmd_

bool diff_drive_controller::DiffDriveController::publish_cmd_
private

Publish limited velocity:

Definition at line 186 of file diff_drive_controller.h.

◆ publish_period_

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

Odometry related:

Definition at line 107 of file diff_drive_controller.h.

◆ publish_wheel_joint_controller_state_

bool diff_drive_controller::DiffDriveController::publish_wheel_joint_controller_state_
private

Publish wheel data:

Definition at line 189 of file diff_drive_controller.h.

◆ right_wheel_joints_

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

Definition at line 113 of file diff_drive_controller.h.

◆ right_wheel_radius_multiplier_

double diff_drive_controller::DiffDriveController::right_wheel_radius_multiplier_
private

Definition at line 159 of file diff_drive_controller.h.

◆ sub_command_

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

Definition at line 137 of file diff_drive_controller.h.

◆ tf_odom_pub_

std::shared_ptr<realtime_tools::RealtimePublisher<tf::tfMessage> > diff_drive_controller::DiffDriveController::tf_odom_pub_
private

Definition at line 144 of file diff_drive_controller.h.

◆ time_previous_

ros::Time diff_drive_controller::DiffDriveController::time_previous_
private

Definition at line 116 of file diff_drive_controller.h.

◆ vel_left_desired_previous_

double diff_drive_controller::DiffDriveController::vel_left_desired_previous_
private

Previous velocities from the encoders:

Definition at line 123 of file diff_drive_controller.h.

◆ vel_left_previous_

std::vector<double> diff_drive_controller::DiffDriveController::vel_left_previous_
private

Previous velocities from the encoders:

Definition at line 119 of file diff_drive_controller.h.

◆ vel_right_desired_previous_

double diff_drive_controller::DiffDriveController::vel_right_desired_previous_
private

Definition at line 124 of file diff_drive_controller.h.

◆ vel_right_previous_

std::vector<double> diff_drive_controller::DiffDriveController::vel_right_previous_
private

Definition at line 120 of file diff_drive_controller.h.

◆ wheel_joints_size_

size_t diff_drive_controller::DiffDriveController::wheel_joints_size_
private

Number of wheel joints:

Definition at line 177 of file diff_drive_controller.h.

◆ wheel_radius_

double diff_drive_controller::DiffDriveController::wheel_radius_
private

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

Definition at line 154 of file diff_drive_controller.h.

◆ wheel_separation_

double diff_drive_controller::DiffDriveController::wheel_separation_
private

Wheel separation, wrt the midpoint of the wheel width:

Definition at line 151 of file diff_drive_controller.h.

◆ wheel_separation_multiplier_

double diff_drive_controller::DiffDriveController::wheel_separation_multiplier_
private

Wheel separation and radius calibration multipliers:

Definition at line 157 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 Feb 3 2023 03:19:01