Classes | Public Member Functions | Private Member Functions | Private Attributes | List of all members
four_wheel_steering_controller::FourWheelSteeringController Class Reference

#include <four_wheel_steering_controller.h>

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

Classes

struct  Command
 Velocity command related: More...
 
struct  Command4ws
 
struct  CommandTwist
 

Public Member Functions

 FourWheelSteeringController ()
 
bool init (hardware_interface::RobotHW *robot_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::MultiInterfaceController< hardware_interface::VelocityJointInterface, hardware_interface::PositionJointInterface >
virtual bool init (hardware_interface::RobotHW *, ros::NodeHandle &)
 
 MultiInterfaceController (bool allow_optional_interfaces=false)
 
virtual ~MultiInterfaceController ()
 
- 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 cmdFourWheelSteeringCallback (const four_wheel_steering_msgs::FourWheelSteering &command)
 Velocity and steering command callback. 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 setOdomPubFields (ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
 Sets the odometry publishing fields. More...
 
void updateCommand (const ros::Time &time, const ros::Duration &period)
 Compute and publish command. More...
 
void updateOdometry (const ros::Time &time)
 Update and publish odometry. 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< Command4wscommand_four_wheel_steering_
 FourWheelSteering command related: More...
 
Command4ws command_struct_four_wheel_steering_
 
CommandTwist command_struct_twist_
 
realtime_tools::RealtimeBuffer< CommandTwistcommand_twist_
 
bool enable_odom_tf_
 Whether to publish odometry to tf or not: More...
 
bool enable_twist_cmd_
 Whether the control is make with four_wheel_steering msg or twist msg: More...
 
std::vector< hardware_interface::JointHandlefront_steering_joints_
 
std::vector< hardware_interface::JointHandlefront_wheel_joints_
 Hardware handles: More...
 
CommandTwist last0_cmd_
 
CommandTwist last1_cmd_
 Speed limiters: More...
 
ros::Time last_state_publish_time_
 
SpeedLimiter limiter_ang_
 
SpeedLimiter limiter_lin_
 
std::string name_
 
boost::shared_ptr< realtime_tools::RealtimePublisher< four_wheel_steering_msgs::FourWheelSteeringStamped > > odom_4ws_pub_
 
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...
 
std::vector< hardware_interface::JointHandlerear_steering_joints_
 
std::vector< hardware_interface::JointHandlerear_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): More...
 
double wheel_base_
 Wheel base (distance between front and rear wheel): More...
 
double wheel_radius_
 Wheel radius (assuming it's the same for the left and right wheels): More...
 
double wheel_steering_y_offset_
 

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::MultiInterfaceController< hardware_interface::VelocityJointInterface, hardware_interface::PositionJointInterface >
virtual bool initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources)
 
- Static Protected Member Functions inherited from controller_interface::MultiInterfaceController< hardware_interface::VelocityJointInterface, hardware_interface::PositionJointInterface >
static void clearClaims (hardware_interface::RobotHW *robot_hw)
 
static void extractInterfaceResources (hardware_interface::RobotHW *robot_hw_in, hardware_interface::RobotHW *robot_hw_out)
 
static bool hasRequiredInterfaces (hardware_interface::RobotHW *robot_hw)
 
static void populateClaimedResources (hardware_interface::RobotHW *robot_hw, ClaimedResources &claimed_resources)
 
- Protected Attributes inherited from controller_interface::MultiInterfaceController< hardware_interface::VelocityJointInterface, hardware_interface::PositionJointInterface >
bool allow_optional_interfaces_
 
hardware_interface::RobotHW robot_hw_ctrl_
 

Detailed Description

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

Definition at line 60 of file four_wheel_steering_controller.h.

Constructor & Destructor Documentation

four_wheel_steering_controller::FourWheelSteeringController::FourWheelSteeringController ( )

Definition at line 46 of file four_wheel_steering_controller.cpp.

Member Function Documentation

void four_wheel_steering_controller::FourWheelSteeringController::brake ( )
private

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

Definition at line 500 of file four_wheel_steering_controller.cpp.

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

Velocity and steering command callback.

Parameters
commandVelocity and steering command message (4ws)

Definition at line 544 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 517 of file four_wheel_steering_controller.cpp.

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 572 of file four_wheel_steering_controller.cpp.

bool four_wheel_steering_controller::FourWheelSteeringController::init ( hardware_interface::RobotHW robot_hw,
ros::NodeHandle root_nh,
ros::NodeHandle controller_nh 
)
virtual

Initialize controller.

Parameters
robot_hwVelocity and position 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::VelocityJointInterface, hardware_interface::PositionJointInterface >.

Definition at line 60 of file four_wheel_steering_controller.cpp.

void four_wheel_steering_controller::FourWheelSteeringController::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 625 of file four_wheel_steering_controller.cpp.

void four_wheel_steering_controller::FourWheelSteeringController::starting ( const ros::Time time)
virtual

Starts controller.

Parameters
timeCurrent time

Reimplemented from controller_interface::ControllerBase.

Definition at line 240 of file four_wheel_steering_controller.cpp.

void four_wheel_steering_controller::FourWheelSteeringController::stopping ( const ros::Time )
virtual

Stops controller.

Parameters
timeCurrent time

Reimplemented from controller_interface::ControllerBase.

Definition at line 250 of file four_wheel_steering_controller.cpp.

void four_wheel_steering_controller::FourWheelSteeringController::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 234 of file four_wheel_steering_controller.cpp.

void four_wheel_steering_controller::FourWheelSteeringController::updateCommand ( const ros::Time time,
const ros::Duration period 
)
private

Compute and publish command.

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 !

Definition at line 337 of file four_wheel_steering_controller.cpp.

void four_wheel_steering_controller::FourWheelSteeringController::updateOdometry ( const ros::Time time)
private

Update and publish odometry.

Parameters
timeCurrent time

Definition at line 255 of file four_wheel_steering_controller.cpp.

Member Data Documentation

std::string four_wheel_steering_controller::FourWheelSteeringController::base_frame_id_
private

Frame to use for the robot base:

Definition at line 164 of file four_wheel_steering_controller.h.

double four_wheel_steering_controller::FourWheelSteeringController::cmd_vel_timeout_
private

Timeout to consider cmd_vel commands old:

Definition at line 161 of file four_wheel_steering_controller.h.

realtime_tools::RealtimeBuffer<Command4ws> four_wheel_steering_controller::FourWheelSteeringController::command_four_wheel_steering_
private

FourWheelSteering command related:

Definition at line 138 of file four_wheel_steering_controller.h.

Command4ws four_wheel_steering_controller::FourWheelSteeringController::command_struct_four_wheel_steering_
private

Definition at line 139 of file four_wheel_steering_controller.h.

CommandTwist four_wheel_steering_controller::FourWheelSteeringController::command_struct_twist_
private

Definition at line 134 of file four_wheel_steering_controller.h.

realtime_tools::RealtimeBuffer<CommandTwist> four_wheel_steering_controller::FourWheelSteeringController::command_twist_
private

Definition at line 133 of file four_wheel_steering_controller.h.

bool four_wheel_steering_controller::FourWheelSteeringController::enable_odom_tf_
private

Whether to publish odometry to tf or not:

Definition at line 167 of file four_wheel_steering_controller.h.

bool four_wheel_steering_controller::FourWheelSteeringController::enable_twist_cmd_
private

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

Definition at line 170 of file four_wheel_steering_controller.h.

std::vector<hardware_interface::JointHandle> four_wheel_steering_controller::FourWheelSteeringController::front_steering_joints_
private

Definition at line 107 of file four_wheel_steering_controller.h.

std::vector<hardware_interface::JointHandle> four_wheel_steering_controller::FourWheelSteeringController::front_wheel_joints_
private

Hardware handles:

Definition at line 105 of file four_wheel_steering_controller.h.

CommandTwist four_wheel_steering_controller::FourWheelSteeringController::last0_cmd_
private

Definition at line 174 of file four_wheel_steering_controller.h.

CommandTwist four_wheel_steering_controller::FourWheelSteeringController::last1_cmd_
private

Speed limiters:

Definition at line 173 of file four_wheel_steering_controller.h.

ros::Time four_wheel_steering_controller::FourWheelSteeringController::last_state_publish_time_
private

Definition at line 101 of file four_wheel_steering_controller.h.

SpeedLimiter four_wheel_steering_controller::FourWheelSteeringController::limiter_ang_
private

Definition at line 176 of file four_wheel_steering_controller.h.

SpeedLimiter four_wheel_steering_controller::FourWheelSteeringController::limiter_lin_
private

Definition at line 175 of file four_wheel_steering_controller.h.

std::string four_wheel_steering_controller::FourWheelSteeringController::name_
private

Definition at line 97 of file four_wheel_steering_controller.h.

boost::shared_ptr<realtime_tools::RealtimePublisher<four_wheel_steering_msgs::FourWheelSteeringStamped> > four_wheel_steering_controller::FourWheelSteeringController::odom_4ws_pub_
private

Definition at line 144 of file four_wheel_steering_controller.h.

boost::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::Odometry> > four_wheel_steering_controller::FourWheelSteeringController::odom_pub_
private

Odometry related:

Definition at line 143 of file four_wheel_steering_controller.h.

Odometry four_wheel_steering_controller::FourWheelSteeringController::odometry_
private

Definition at line 146 of file four_wheel_steering_controller.h.

bool four_wheel_steering_controller::FourWheelSteeringController::open_loop_
private

Definition at line 102 of file four_wheel_steering_controller.h.

ros::Duration four_wheel_steering_controller::FourWheelSteeringController::publish_period_
private

Odometry related:

Definition at line 100 of file four_wheel_steering_controller.h.

std::vector<hardware_interface::JointHandle> four_wheel_steering_controller::FourWheelSteeringController::rear_steering_joints_
private

Definition at line 108 of file four_wheel_steering_controller.h.

std::vector<hardware_interface::JointHandle> four_wheel_steering_controller::FourWheelSteeringController::rear_wheel_joints_
private

Definition at line 106 of file four_wheel_steering_controller.h.

ros::Subscriber four_wheel_steering_controller::FourWheelSteeringController::sub_command_
private

Definition at line 135 of file four_wheel_steering_controller.h.

ros::Subscriber four_wheel_steering_controller::FourWheelSteeringController::sub_command_four_wheel_steering_
private

Definition at line 140 of file four_wheel_steering_controller.h.

boost::shared_ptr<realtime_tools::RealtimePublisher<tf::tfMessage> > four_wheel_steering_controller::FourWheelSteeringController::tf_odom_pub_
private

Definition at line 145 of file four_wheel_steering_controller.h.

double four_wheel_steering_controller::FourWheelSteeringController::track_
private

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

Definition at line 149 of file four_wheel_steering_controller.h.

double four_wheel_steering_controller::FourWheelSteeringController::wheel_base_
private

Wheel base (distance between front and rear wheel):

Definition at line 158 of file four_wheel_steering_controller.h.

double four_wheel_steering_controller::FourWheelSteeringController::wheel_radius_
private

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

Definition at line 155 of file four_wheel_steering_controller.h.

double four_wheel_steering_controller::FourWheelSteeringController::wheel_steering_y_offset_
private

Distance between a wheel joint (from the midpoint of the wheel width) and the associated steering joint: We consider that the distance is the same for every wheel

Definition at line 152 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 Thu Apr 11 2019 03:08:25