Classes | Public Member Functions | Private Types | Private Member Functions | Private Attributes
steer_drive_controller::SteerDriveController Class Reference

#include <steer_drive_controller.h>

Inheritance diagram for steer_drive_controller::SteerDriveController:
Inheritance graph
[legend]

List of all members.

Classes

struct  Commands
 Velocity command related: More...

Public Member Functions

bool init (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
 Initialize controller.
void starting (const ros::Time &time)
 Starts controller.
 SteerDriveController ()
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 Types

enum  INDEX_WHEEL { INDEX_RIGHT = 0, INDEX_LEFT = 1 }
enum  INDX_STEER { INDX_STEER_FRNT = 0, INDX_STEER_BACK = 1 }
enum  INDX_WHEEL { INDX_WHEEL_FRNT = 0, INDX_WHEEL_MID = 1, INDX_WHEEL_BACK = 2 }

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 rear_wheel_name, const std::string front_steer_name, bool lookup_wheel_separation_h, 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

bool allow_multiple_cmd_vel_publishers_
 Whether to allow multiple publishers on cmd_vel topic or not:
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:
hardware_interface::JointHandle front_steer_joint_
Commands last0_cmd_
Commands last1_cmd_
 Speed limiters:
ros::Time last_state_publish_time_
SpeedLimiter limiter_ang_
SpeedLimiter limiter_lin_
std::string name_
std::string ns_
std::string odom_frame_id_
 Frame to use for odometry and odom tf:
boost::shared_ptr
< realtime_tools::RealtimePublisher
< nav_msgs::Odometry > > 
odom_pub_
 Odometry related:
Odometry odometry_
bool open_loop_
ros::Duration publish_period_
 Odometry related:
hardware_interface::JointHandle rear_wheel_joint_
 Hardware handles:
size_t steer_joints_size_
 Number of steer joints:
double steer_pos_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:
double wheel_radius_
 Wheel radius (assuming it's the same for the left and right wheels):
double wheel_radius_multiplier_
double wheel_separation_h_
 Wheel separation, wrt the midpoint of the wheel width:
double wheel_separation_h_multiplier_
 Wheel separation and radius calibration multipliers:

Detailed Description

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

Definition at line 67 of file steer_drive_controller.h.


Member Enumeration Documentation

Enumerator:
INDEX_RIGHT 
INDEX_LEFT 

Definition at line 84 of file steer_drive_controller.h.

Enumerator:
INDX_STEER_FRNT 
INDX_STEER_BACK 

Definition at line 79 of file steer_drive_controller.h.

Enumerator:
INDX_WHEEL_FRNT 
INDX_WHEEL_MID 
INDX_WHEEL_BACK 

Definition at line 74 of file steer_drive_controller.h.


Constructor & Destructor Documentation

Definition at line 112 of file steer_drive_controller.cpp.


Member Function Documentation

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

Definition at line 359 of file steer_drive_controller.cpp.

void steer_drive_controller::SteerDriveController::cmdVelCallback ( const geometry_msgs::Twist &  command) [private]

Velocity command callback.

Parameters:
commandVelocity command message (twist)

Definition at line 368 of file steer_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::MultiInterfaceController< hardware_interface::PositionJointInterface, hardware_interface::VelocityJointInterface >.

Definition at line 130 of file steer_drive_controller.cpp.

bool steer_drive_controller::SteerDriveController::setOdomParamsFromUrdf ( ros::NodeHandle root_nh,
const std::string  rear_wheel_name,
const std::string  front_steer_name,
bool  lookup_wheel_separation_h,
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 398 of file steer_drive_controller.cpp.

Sets the odometry publishing fields.

Parameters:
root_nhRoot node handle
controller_nhNode handle inside the controller namespace

Definition at line 473 of file steer_drive_controller.cpp.

Starts controller.

Parameters:
timeCurrent time

Reimplemented from controller_interface::ControllerBase.

Definition at line 344 of file steer_drive_controller.cpp.

Stops controller.

Parameters:
timeCurrent time

Reimplemented from controller_interface::ControllerBase.

Definition at line 354 of file steer_drive_controller.cpp.

void steer_drive_controller::SteerDriveController::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 264 of file steer_drive_controller.cpp.


Member Data Documentation

Whether to allow multiple publishers on cmd_vel topic or not:

Definition at line 166 of file steer_drive_controller.h.

Frame to use for the robot base:

Definition at line 169 of file steer_drive_controller.h.

Timeout to consider cmd_vel commands old:

Definition at line 163 of file steer_drive_controller.h.

Definition at line 142 of file steer_drive_controller.h.

Definition at line 143 of file steer_drive_controller.h.

Whether to publish odometry to tf or not:

Definition at line 175 of file steer_drive_controller.h.

Definition at line 131 of file steer_drive_controller.h.

Definition at line 185 of file steer_drive_controller.h.

Speed limiters:

Definition at line 184 of file steer_drive_controller.h.

Definition at line 126 of file steer_drive_controller.h.

Definition at line 187 of file steer_drive_controller.h.

Definition at line 186 of file steer_drive_controller.h.

Definition at line 122 of file steer_drive_controller.h.

Definition at line 190 of file steer_drive_controller.h.

Frame to use for odometry and odom tf:

Definition at line 172 of file steer_drive_controller.h.

Odometry related:

Definition at line 147 of file steer_drive_controller.h.

Definition at line 149 of file steer_drive_controller.h.

Definition at line 127 of file steer_drive_controller.h.

Odometry related:

Definition at line 125 of file steer_drive_controller.h.

Hardware handles:

Definition at line 130 of file steer_drive_controller.h.

Number of steer joints:

Definition at line 181 of file steer_drive_controller.h.

Definition at line 160 of file steer_drive_controller.h.

Definition at line 144 of file steer_drive_controller.h.

Definition at line 148 of file steer_drive_controller.h.

Number of wheel joints:

Definition at line 178 of file steer_drive_controller.h.

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

Definition at line 155 of file steer_drive_controller.h.

Definition at line 159 of file steer_drive_controller.h.

Wheel separation, wrt the midpoint of the wheel width:

Definition at line 152 of file steer_drive_controller.h.

Wheel separation and radius calibration multipliers:

Definition at line 158 of file steer_drive_controller.h.


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


steer_drive_controller
Author(s): CIR-KIT , Masaru Morita
autogenerated on Sat Jun 8 2019 19:20:25