Classes | Public Member Functions | Private Member Functions | Private Attributes
ackermann_controller::AckermannController Class Reference

#include <ackermann_controller.h>

Inheritance diagram for ackermann_controller::AckermannController:
Inheritance graph
[legend]

List of all members.

Classes

struct  Commands
 Velocity command related: More...

Public Member Functions

 AckermannController ()
std::string getHardwareInterfaceType () const
 Get the name of this controller's hardware interface type.
bool init (hardware_interface::PositionJointInterface *hw_pos, hardware_interface::VelocityJointInterface *hw_vel, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
virtual bool initRequest (hardware_interface::RobotHW *const robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, std::set< std::string > &claimed_resources)
 Initialize controller.
void starting (const ros::Time &time)
 Starts controller.
void stopping (const ros::Time &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 cmdAckermannCallback (const ackermann_msgs::AckermannDrive &command)
 Velocity command callback.
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.
void handleSteeringSaturation (double &front_left_steering, double &front_right_steering)
 Update the steering command with steering joint limitation to handle saturation

\[ tan(\delta_{FR})=\frac{wheel_base}{\frac{wheel\_base}{tan(\delta_{FL})}+track)} \]

\[ tan(\delta_{FL})=\frac{wheel_base} {\frac{wheel\_base} {tan(\delta_{FR})} -track)} \]

.

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_
realtime_tools::RealtimeBuffer
< Commands
command_ackermann_
 Ackermann command related:
Commands command_struct_
Commands command_struct_ackermann_
bool enable_odom_tf_
 Whether to publish odometry to tf or not:
bool enable_twist_cmd_
 Whether the control is make with ackermann msg or twist msg:
std::vector
< hardware_interface::JointHandle
front_steering_joints_
std::vector
< hardware_interface::JointHandle
front_wheel_joints_
 Hardware handles:
double front_wheel_radius_
 Wheel radius (assuming it's the same for the left and right wheels):
Commands last0_cmd_
Commands last1_cmd_
 Speed limiters:
ros::Time last_state_publish_time_
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
rear_wheel_joints_
double rear_wheel_radius_
double steering_limit_
 Joint steering limits (assuming the limit is the same for the left and right joint)
ros::Subscriber sub_command_
ros::Subscriber sub_command_ackermann_
boost::shared_ptr
< realtime_tools::RealtimePublisher
< tf::tfMessage > > 
tf_odom_pub_
double track_
 Wheel separation (or track), distance between left and right wheels (from the midpoint of the wheel width):
double wheel_base_
 Wheel base (distance between front and rear wheel):

Detailed Description

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

Definition at line 28 of file ackermann_controller.h.


Constructor & Destructor Documentation

Definition at line 15 of file ackermann_controller.cpp.


Member Function Documentation

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

Definition at line 440 of file ackermann_controller.cpp.

void ackermann_controller::AckermannController::cmdAckermannCallback ( const ackermann_msgs::AckermannDrive &  command) [private]

Velocity command callback.

Parameters:
commandVelocity command message (twist)

Definition at line 476 of file ackermann_controller.cpp.

void ackermann_controller::AckermannController::cmdVelCallback ( const geometry_msgs::Twist &  command) [private]

Velocity command callback.

Parameters:
commandVelocity command message (twist)

Definition at line 456 of file ackermann_controller.cpp.

Get the name of this controller's hardware interface type.

Implements controller_interface::ControllerBase.

Definition at line 46 of file ackermann_controller.h.

bool ackermann_controller::AckermannController::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 496 of file ackermann_controller.cpp.

void ackermann_controller::AckermannController::handleSteeringSaturation ( double &  front_left_steering,
double &  front_right_steering 
) [private]

Update the steering command with steering joint limitation to handle saturation

\[ tan(\delta_{FR})=\frac{wheel_base}{\frac{wheel\_base}{tan(\delta_{FL})}+track)} \]

\[ tan(\delta_{FL})=\frac{wheel_base} {\frac{wheel\_base} {tan(\delta_{FR})} -track)} \]

.

Parameters:
front_left_steering$ \delta_{FL} $
front_right_steering$ \delta_{FR} $

Definition at line 596 of file ackermann_controller.cpp.

Definition at line 81 of file ackermann_controller.cpp.

bool ackermann_controller::AckermannController::initRequest ( hardware_interface::RobotHW *const  robot_hw,
ros::NodeHandle root_nh,
ros::NodeHandle controller_nh,
std::set< std::string > &  claimed_resources 
) [virtual]

Initialize controller.

Parameters:
robot_hwVelocity joint interface for the wheels
root_nhNode handle at root namespace
controller_nhNode handle inside the controller namespace
claimed_resourcesVector of JointInterfaces claimed during init

Implements controller_interface::ControllerBase.

Definition at line 31 of file ackermann_controller.cpp.

Sets the odometry publishing fields.

Parameters:
root_nhRoot node handle
controller_nhNode handle inside the controller namespace

Definition at line 549 of file ackermann_controller.cpp.

Starts controller.

Parameters:
timeCurrent time

Reimplemented from controller_interface::ControllerBase.

Definition at line 425 of file ackermann_controller.cpp.

Stops controller.

Parameters:
timeCurrent time

Reimplemented from controller_interface::ControllerBase.

Definition at line 435 of file ackermann_controller.cpp.

void ackermann_controller::AckermannController::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

check limits to not apply the same steering on right and left when saturated !

Implements controller_interface::ControllerBase.

Definition at line 262 of file ackermann_controller.cpp.


Member Data Documentation

Frame to use for the robot base:

Definition at line 129 of file ackermann_controller.h.

Timeout to consider cmd_vel commands old:

Definition at line 126 of file ackermann_controller.h.

Definition at line 98 of file ackermann_controller.h.

Ackermann command related:

Definition at line 103 of file ackermann_controller.h.

Definition at line 99 of file ackermann_controller.h.

Definition at line 104 of file ackermann_controller.h.

Whether to publish odometry to tf or not:

Definition at line 132 of file ackermann_controller.h.

Whether the control is make with ackermann msg or twist msg:

Definition at line 135 of file ackermann_controller.h.

Definition at line 86 of file ackermann_controller.h.

Hardware handles:

Definition at line 84 of file ackermann_controller.h.

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

Definition at line 117 of file ackermann_controller.h.

Definition at line 139 of file ackermann_controller.h.

Speed limiters:

Definition at line 138 of file ackermann_controller.h.

Definition at line 80 of file ackermann_controller.h.

Definition at line 141 of file ackermann_controller.h.

Definition at line 140 of file ackermann_controller.h.

Definition at line 76 of file ackermann_controller.h.

Odometry related:

Definition at line 108 of file ackermann_controller.h.

Definition at line 110 of file ackermann_controller.h.

Definition at line 81 of file ackermann_controller.h.

Odometry related:

Definition at line 79 of file ackermann_controller.h.

Definition at line 85 of file ackermann_controller.h.

Definition at line 117 of file ackermann_controller.h.

Joint steering limits (assuming the limit is the same for the left and right joint)

Definition at line 120 of file ackermann_controller.h.

Definition at line 100 of file ackermann_controller.h.

Definition at line 105 of file ackermann_controller.h.

Definition at line 109 of file ackermann_controller.h.

Wheel separation (or track), distance between left and right wheels (from the midpoint of the wheel width):

Definition at line 114 of file ackermann_controller.h.

Wheel base (distance between front and rear wheel):

Definition at line 123 of file ackermann_controller.h.


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


ackermann_controller
Author(s): Vincent Rousseau
autogenerated on Sat Jun 8 2019 20:06:19