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)
 
- Public Member Functions inherited from controller_interface::ControllerBase
virtual void aborting (const ros::Time &)
 
virtual void aborting (const ros::Time &)
 
bool abortRequest (const ros::Time &time)
 
bool abortRequest (const ros::Time &time)
 
 ControllerBase ()=default
 
 ControllerBase (const ControllerBase &)=delete
 
 ControllerBase (ControllerBase &&)=delete
 
bool isAborted () const
 
bool isAborted () const
 
bool isInitialized () const
 
bool isInitialized () const
 
bool isRunning () const
 
bool isRunning () const
 
bool isStopped () const
 
bool isStopped () const
 
bool isWaiting () const
 
bool isWaiting () const
 
ControllerBaseoperator= (const ControllerBase &)=delete
 
ControllerBaseoperator= (ControllerBase &&)=delete
 
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 void waiting (const ros::Time &)
 
virtual void waiting (const ros::Time &)
 
bool waitRequest (const ros::Time &time)
 
bool waitRequest (const ros::Time &time)
 
virtual ~ControllerBase ()=default
 

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_
 
std::shared_ptr< realtime_tools::RealtimePublisher< four_wheel_steering_msgs::FourWheelSteeringStamped > > odom_4ws_pub_
 
std::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_
 
std::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
 
enum  ControllerState {
  ControllerState::CONSTRUCTED, ControllerState::INITIALIZED, ControllerState::RUNNING, ControllerState::STOPPED,
  ControllerState::WAITING, ControllerState::ABORTED
}
 
- Public Attributes inherited from controller_interface::ControllerBase
ControllerState state_
 
- Protected Member Functions inherited from controller_interface::MultiInterfaceController< hardware_interface::VelocityJointInterface, hardware_interface::PositionJointInterface >
bool initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) override
 
- 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 96 of file four_wheel_steering_controller.h.

Constructor & Destructor Documentation

◆ FourWheelSteeringController()

four_wheel_steering_controller::FourWheelSteeringController::FourWheelSteeringController ( )

Definition at line 77 of file four_wheel_steering_controller.cpp.

Member Function Documentation

◆ brake()

void four_wheel_steering_controller::FourWheelSteeringController::brake ( )
private

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

Definition at line 532 of file four_wheel_steering_controller.cpp.

◆ cmdFourWheelSteeringCallback()

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

◆ cmdVelCallback()

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

Velocity command callback.

Parameters
commandVelocity command message (twist)

Definition at line 549 of file four_wheel_steering_controller.cpp.

◆ getWheelNames()

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

◆ init()

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

◆ setOdomPubFields()

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

◆ starting()

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

◆ stopping()

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

Stops controller.

Parameters
timeCurrent time

Reimplemented from controller_interface::ControllerBase.

Definition at line 281 of file four_wheel_steering_controller.cpp.

◆ update()

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

◆ updateCommand()

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

◆ updateOdometry()

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

Update and publish odometry.

Parameters
timeCurrent time

Definition at line 286 of file four_wheel_steering_controller.cpp.

Member Data Documentation

◆ base_frame_id_

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

Frame to use for the robot base:

Definition at line 233 of file four_wheel_steering_controller.h.

◆ cmd_vel_timeout_

double four_wheel_steering_controller::FourWheelSteeringController::cmd_vel_timeout_
private

Timeout to consider cmd_vel commands old:

Definition at line 230 of file four_wheel_steering_controller.h.

◆ command_four_wheel_steering_

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

FourWheelSteering command related:

Definition at line 207 of file four_wheel_steering_controller.h.

◆ command_struct_four_wheel_steering_

Command4ws four_wheel_steering_controller::FourWheelSteeringController::command_struct_four_wheel_steering_
private

Definition at line 208 of file four_wheel_steering_controller.h.

◆ command_struct_twist_

CommandTwist four_wheel_steering_controller::FourWheelSteeringController::command_struct_twist_
private

Definition at line 203 of file four_wheel_steering_controller.h.

◆ command_twist_

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

Definition at line 202 of file four_wheel_steering_controller.h.

◆ enable_odom_tf_

bool four_wheel_steering_controller::FourWheelSteeringController::enable_odom_tf_
private

Whether to publish odometry to tf or not:

Definition at line 236 of file four_wheel_steering_controller.h.

◆ enable_twist_cmd_

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 239 of file four_wheel_steering_controller.h.

◆ front_steering_joints_

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

Definition at line 176 of file four_wheel_steering_controller.h.

◆ front_wheel_joints_

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

Hardware handles:

Definition at line 174 of file four_wheel_steering_controller.h.

◆ last0_cmd_

CommandTwist four_wheel_steering_controller::FourWheelSteeringController::last0_cmd_
private

Definition at line 243 of file four_wheel_steering_controller.h.

◆ last1_cmd_

CommandTwist four_wheel_steering_controller::FourWheelSteeringController::last1_cmd_
private

Speed limiters:

Definition at line 242 of file four_wheel_steering_controller.h.

◆ last_state_publish_time_

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

Definition at line 170 of file four_wheel_steering_controller.h.

◆ limiter_ang_

SpeedLimiter four_wheel_steering_controller::FourWheelSteeringController::limiter_ang_
private

Definition at line 245 of file four_wheel_steering_controller.h.

◆ limiter_lin_

SpeedLimiter four_wheel_steering_controller::FourWheelSteeringController::limiter_lin_
private

Definition at line 244 of file four_wheel_steering_controller.h.

◆ name_

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

Definition at line 166 of file four_wheel_steering_controller.h.

◆ odom_4ws_pub_

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

Definition at line 213 of file four_wheel_steering_controller.h.

◆ odom_pub_

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

Odometry related:

Definition at line 212 of file four_wheel_steering_controller.h.

◆ odometry_

Odometry four_wheel_steering_controller::FourWheelSteeringController::odometry_
private

Definition at line 215 of file four_wheel_steering_controller.h.

◆ open_loop_

bool four_wheel_steering_controller::FourWheelSteeringController::open_loop_
private

Definition at line 171 of file four_wheel_steering_controller.h.

◆ publish_period_

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

Odometry related:

Definition at line 169 of file four_wheel_steering_controller.h.

◆ rear_steering_joints_

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

Definition at line 177 of file four_wheel_steering_controller.h.

◆ rear_wheel_joints_

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

Definition at line 175 of file four_wheel_steering_controller.h.

◆ sub_command_

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

Definition at line 204 of file four_wheel_steering_controller.h.

◆ sub_command_four_wheel_steering_

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

Definition at line 209 of file four_wheel_steering_controller.h.

◆ tf_odom_pub_

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

Definition at line 214 of file four_wheel_steering_controller.h.

◆ track_

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 218 of file four_wheel_steering_controller.h.

◆ wheel_base_

double four_wheel_steering_controller::FourWheelSteeringController::wheel_base_
private

Wheel base (distance between front and rear wheel):

Definition at line 227 of file four_wheel_steering_controller.h.

◆ wheel_radius_

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 224 of file four_wheel_steering_controller.h.

◆ wheel_steering_y_offset_

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 221 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 Fri May 24 2024 02:41:15