Classes | Public Member Functions | Private Member Functions | Private Attributes | List of all members
double_diff_drive_controller::DoubleDiffDriveController Class Reference

#include <double_diff_drive_controller.h>

Inheritance diagram for double_diff_drive_controller::DoubleDiffDriveController:
Inheritance graph
[legend]

Classes

struct  Commands
 Velocity command related: More...
 

Public Member Functions

 DoubleDiffDriveController ()
 
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 &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 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...
 
void setupRtPublishersMsg (ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
 Sets the odometry publishing fields. More...
 
bool setWheelParamsFromUrdf (ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, const std::string &drive_motor_name, const std::string &steer_motor_name)
 Sets odometry parameters from the URDF, i.e. the wheel radius and separation. More...
 

Private Attributes

std::string base_frame_id_
 Frame to use for the robot base: More...
 
double cmd_vel_timeout_
 Timeout to consider cmd_vel commands old: More...
 
realtime_tools::RealtimeBuffer< Commandscommand_
 
Commands command_struct_
 
double drive_motor_gear_ratio_
 
hardware_interface::JointHandle drive_motor_input_
 Hardware handles: More...
 
bool enable_odom_tf_
 Whether to publish odometry to tf or not: More...
 
Commands last_cmd_
 
ros::Time last_state_publish_time_
 
double left_wheel_radius_multiplier_
 
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: More...
 
Odometry odometry_
 
bool open_loop_
 
ros::Duration publish_period_
 Odometry related: More...
 
double right_wheel_radius_multiplier_
 
double steer_motor_gear_ratio_
 
hardware_interface::JointHandle steer_motor_input_
 
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 64 of file double_diff_drive_controller.h.

Constructor & Destructor Documentation

double_diff_drive_controller::DoubleDiffDriveController::DoubleDiffDriveController ( )

Definition at line 52 of file double_diff_drive_controller.cpp.

Member Function Documentation

void double_diff_drive_controller::DoubleDiffDriveController::brake ( )
private

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

Definition at line 235 of file double_diff_drive_controller.cpp.

void double_diff_drive_controller::DoubleDiffDriveController::cmdVelCallback ( const geometry_msgs::Twist &  command)
private

Velocity command callback.

Parameters
commandVelocity command message (twist)

Definition at line 242 of file double_diff_drive_controller.cpp.

bool double_diff_drive_controller::DoubleDiffDriveController::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 67 of file double_diff_drive_controller.cpp.

void double_diff_drive_controller::DoubleDiffDriveController::setupRtPublishersMsg ( 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 309 of file double_diff_drive_controller.cpp.

bool double_diff_drive_controller::DoubleDiffDriveController::setWheelParamsFromUrdf ( ros::NodeHandle root_nh,
ros::NodeHandle controller_nh,
const std::string &  drive_motor_name,
const std::string &  steer_motor_name 
)
private

Sets odometry parameters from the URDF, i.e. the wheel radius and separation.

Parameters
root_nhRoot node handle
wheel0_nameName of wheel0 joint
wheel1_nameName of wheel1 joint

Definition at line 263 of file double_diff_drive_controller.cpp.

void double_diff_drive_controller::DoubleDiffDriveController::starting ( const ros::Time time)
virtual

Starts controller.

Parameters
timeCurrent time

Reimplemented from controller_interface::ControllerBase.

Definition at line 218 of file double_diff_drive_controller.cpp.

void double_diff_drive_controller::DoubleDiffDriveController::stopping ( const ros::Time time)
virtual

Stops controller.

Parameters
timeCurrent time

Reimplemented from controller_interface::ControllerBase.

Definition at line 229 of file double_diff_drive_controller.cpp.

void double_diff_drive_controller::DoubleDiffDriveController::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 138 of file double_diff_drive_controller.cpp.

Member Data Documentation

std::string double_diff_drive_controller::DoubleDiffDriveController::base_frame_id_
private

Frame to use for the robot base:

Definition at line 147 of file double_diff_drive_controller.h.

double double_diff_drive_controller::DoubleDiffDriveController::cmd_vel_timeout_
private

Timeout to consider cmd_vel commands old:

Definition at line 144 of file double_diff_drive_controller.h.

realtime_tools::RealtimeBuffer<Commands> double_diff_drive_controller::DoubleDiffDriveController::command_
private

Definition at line 121 of file double_diff_drive_controller.h.

Commands double_diff_drive_controller::DoubleDiffDriveController::command_struct_
private

Definition at line 122 of file double_diff_drive_controller.h.

double double_diff_drive_controller::DoubleDiffDriveController::drive_motor_gear_ratio_
private

Definition at line 134 of file double_diff_drive_controller.h.

hardware_interface::JointHandle double_diff_drive_controller::DoubleDiffDriveController::drive_motor_input_
private

Hardware handles:

Definition at line 107 of file double_diff_drive_controller.h.

bool double_diff_drive_controller::DoubleDiffDriveController::enable_odom_tf_
private

Whether to publish odometry to tf or not:

Definition at line 150 of file double_diff_drive_controller.h.

Commands double_diff_drive_controller::DoubleDiffDriveController::last_cmd_
private

Definition at line 156 of file double_diff_drive_controller.h.

ros::Time double_diff_drive_controller::DoubleDiffDriveController::last_state_publish_time_
private

Definition at line 103 of file double_diff_drive_controller.h.

double double_diff_drive_controller::DoubleDiffDriveController::left_wheel_radius_multiplier_
private

Definition at line 140 of file double_diff_drive_controller.h.

SpeedLimiter double_diff_drive_controller::DoubleDiffDriveController::limiter_ang_
private

Definition at line 158 of file double_diff_drive_controller.h.

SpeedLimiter double_diff_drive_controller::DoubleDiffDriveController::limiter_lin_
private

Definition at line 157 of file double_diff_drive_controller.h.

std::string double_diff_drive_controller::DoubleDiffDriveController::name_
private

Definition at line 99 of file double_diff_drive_controller.h.

geometry_msgs::TransformStamped double_diff_drive_controller::DoubleDiffDriveController::odom_frame_
private

Definition at line 129 of file double_diff_drive_controller.h.

boost::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::Odometry> > double_diff_drive_controller::DoubleDiffDriveController::odom_pub_
private

Odometry related:

Definition at line 126 of file double_diff_drive_controller.h.

Odometry double_diff_drive_controller::DoubleDiffDriveController::odometry_
private

Definition at line 128 of file double_diff_drive_controller.h.

bool double_diff_drive_controller::DoubleDiffDriveController::open_loop_
private

Definition at line 104 of file double_diff_drive_controller.h.

ros::Duration double_diff_drive_controller::DoubleDiffDriveController::publish_period_
private

Odometry related:

Definition at line 102 of file double_diff_drive_controller.h.

double double_diff_drive_controller::DoubleDiffDriveController::right_wheel_radius_multiplier_
private

Definition at line 141 of file double_diff_drive_controller.h.

double double_diff_drive_controller::DoubleDiffDriveController::steer_motor_gear_ratio_
private

Definition at line 134 of file double_diff_drive_controller.h.

hardware_interface::JointHandle double_diff_drive_controller::DoubleDiffDriveController::steer_motor_input_
private

Definition at line 108 of file double_diff_drive_controller.h.

ros::Subscriber double_diff_drive_controller::DoubleDiffDriveController::sub_command_
private

Definition at line 123 of file double_diff_drive_controller.h.

boost::shared_ptr<realtime_tools::RealtimePublisher<tf::tfMessage> > double_diff_drive_controller::DoubleDiffDriveController::tf_odom_pub_
private

Definition at line 127 of file double_diff_drive_controller.h.

size_t double_diff_drive_controller::DoubleDiffDriveController::wheel_joints_size_
private

Number of wheel joints:

Definition at line 153 of file double_diff_drive_controller.h.

double double_diff_drive_controller::DoubleDiffDriveController::wheel_radius_
private

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

Definition at line 136 of file double_diff_drive_controller.h.

double double_diff_drive_controller::DoubleDiffDriveController::wheel_separation_
private

Wheel separation, wrt the midpoint of the wheel width:

Definition at line 132 of file double_diff_drive_controller.h.

double double_diff_drive_controller::DoubleDiffDriveController::wheel_separation_multiplier_
private

Wheel separation and radius calibration multipliers:

Definition at line 139 of file double_diff_drive_controller.h.


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


moose_control
Author(s): Tony Baltovski
autogenerated on Wed Mar 10 2021 03:43:55