Classes | Public Member Functions | Private Member Functions | Private Attributes
four_wheel_steering_controller::FourWheelSteeringController Class Reference

#include <four_wheel_steering_controller.h>

Inheritance diagram for four_wheel_steering_controller::FourWheelSteeringController:
Inheritance graph
[legend]

List of all members.

Classes

struct  Commands
 Velocity command related: More...

Public Member Functions

 FourWheelSteeringController ()
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 &)
 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 cmdFourWheelSteeringCallback (const four_wheel_steering_msgs::FourWheelSteering &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 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_four_wheel_steering_
 FourWheelSteering command related:
Commands command_struct_
Commands command_struct_four_wheel_steering_
bool enable_odom_tf_
 Whether to publish odometry to tf or not:
bool enable_twist_cmd_
 Whether the control is make with four_wheel_steering msg or twist msg:
std::vector
< hardware_interface::JointHandle
front_steering_joints_
std::vector
< hardware_interface::JointHandle
front_wheel_joints_
 Hardware handles:
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_steering_joints_
std::vector
< hardware_interface::JointHandle
rear_wheel_joints_
ros::Subscriber sub_command_
ros::Subscriber sub_command_four_wheel_steering_
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):
double wheel_radius_
 Wheel radius (assuming it's the same for the left and right wheels):

Detailed Description

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

Definition at line 27 of file four_wheel_steering_controller.h.


Constructor & Destructor Documentation

Definition at line 12 of file four_wheel_steering_controller.cpp.


Member Function Documentation

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

Definition at line 476 of file four_wheel_steering_controller.cpp.

void four_wheel_steering_controller::FourWheelSteeringController::cmdFourWheelSteeringCallback ( const four_wheel_steering_msgs::FourWheelSteering &  command) [private]

Velocity command callback.

Parameters:
commandVelocity command message (twist)

Definition at line 513 of file four_wheel_steering_controller.cpp.

void four_wheel_steering_controller::FourWheelSteeringController::cmdVelCallback ( const geometry_msgs::Twist &  command) [private]

Velocity command callback.

Parameters:
commandVelocity command message (twist)

Definition at line 493 of file four_wheel_steering_controller.cpp.

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

Implements controller_interface::ControllerBase.

Definition at line 44 of file four_wheel_steering_controller.h.

bool four_wheel_steering_controller::FourWheelSteeringController::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 535 of file four_wheel_steering_controller.cpp.

Definition at line 76 of file four_wheel_steering_controller.cpp.

bool four_wheel_steering_controller::FourWheelSteeringController::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:
hwVelocity joint interface for the wheels
root_nhNode handle at root namespace
controller_nhNode handle inside the controller namespace

Implements controller_interface::ControllerBase.

Definition at line 26 of file four_wheel_steering_controller.cpp.

Sets the odometry publishing fields.

Parameters:
root_nhRoot node handle
controller_nhNode handle inside the controller namespace

Definition at line 588 of file four_wheel_steering_controller.cpp.

Starts controller.

Parameters:
timeCurrent time

Reimplemented from controller_interface::ControllerBase.

Definition at line 461 of file four_wheel_steering_controller.cpp.

Stops controller.

Parameters:
timeCurrent time

Reimplemented from controller_interface::ControllerBase.

Definition at line 471 of file four_wheel_steering_controller.cpp.

Updates controller, i.e. computes the odometry and sets the new velocity commands.

Parameters:
timeCurrent time
periodTime since the last called to update

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

Implements controller_interface::ControllerBase.

Definition at line 247 of file four_wheel_steering_controller.cpp.


Member Data Documentation

Frame to use for the robot base:

Definition at line 125 of file four_wheel_steering_controller.h.

Timeout to consider cmd_vel commands old:

Definition at line 122 of file four_wheel_steering_controller.h.

Definition at line 98 of file four_wheel_steering_controller.h.

FourWheelSteering command related:

Definition at line 103 of file four_wheel_steering_controller.h.

Definition at line 99 of file four_wheel_steering_controller.h.

Definition at line 104 of file four_wheel_steering_controller.h.

Whether to publish odometry to tf or not:

Definition at line 128 of file four_wheel_steering_controller.h.

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

Definition at line 131 of file four_wheel_steering_controller.h.

Definition at line 84 of file four_wheel_steering_controller.h.

Hardware handles:

Definition at line 82 of file four_wheel_steering_controller.h.

Definition at line 135 of file four_wheel_steering_controller.h.

Speed limiters:

Definition at line 134 of file four_wheel_steering_controller.h.

Definition at line 78 of file four_wheel_steering_controller.h.

Definition at line 137 of file four_wheel_steering_controller.h.

Definition at line 136 of file four_wheel_steering_controller.h.

Definition at line 74 of file four_wheel_steering_controller.h.

Odometry related:

Definition at line 108 of file four_wheel_steering_controller.h.

Definition at line 110 of file four_wheel_steering_controller.h.

Definition at line 79 of file four_wheel_steering_controller.h.

Odometry related:

Definition at line 77 of file four_wheel_steering_controller.h.

Definition at line 85 of file four_wheel_steering_controller.h.

Definition at line 83 of file four_wheel_steering_controller.h.

Definition at line 100 of file four_wheel_steering_controller.h.

Definition at line 105 of file four_wheel_steering_controller.h.

Definition at line 109 of file four_wheel_steering_controller.h.

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

Definition at line 113 of file four_wheel_steering_controller.h.

Wheel base (distance between front and rear wheel):

Definition at line 119 of file four_wheel_steering_controller.h.

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

Definition at line 116 of file four_wheel_steering_controller.h.


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


four_wheel_steering_controller
Author(s): Vincent Rousseau
autogenerated on Sat Jun 8 2019 20:06:24