#include <four_wheel_steering_controller.h>
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... | |
![]() | |
virtual bool | init (hardware_interface::RobotHW *, ros::NodeHandle &) |
MultiInterfaceController (bool allow_optional_interfaces=false) | |
![]() | |
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 |
ControllerBase & | operator= (const ControllerBase &)=delete |
ControllerBase & | operator= (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... | |
This class makes some assumptions on the model of the robot:
Definition at line 96 of file four_wheel_steering_controller.h.
four_wheel_steering_controller::FourWheelSteeringController::FourWheelSteeringController | ( | ) |
Definition at line 77 of file four_wheel_steering_controller.cpp.
|
private |
Brakes the wheels, i.e. sets the velocity to 0.
Definition at line 532 of file four_wheel_steering_controller.cpp.
|
private |
Velocity and steering command callback.
command | Velocity and steering command message (4ws) |
Definition at line 576 of file four_wheel_steering_controller.cpp.
|
private |
Velocity command callback.
command | Velocity command message (twist) |
Definition at line 549 of file four_wheel_steering_controller.cpp.
|
private |
Get the wheel names from a wheel param.
[in] | controller_nh | Controller node handler |
[in] | wheel_param | Param name |
[out] | wheel_names | Vector with the whel names |
Definition at line 604 of file four_wheel_steering_controller.cpp.
|
virtual |
Initialize controller.
robot_hw | Velocity and position joint interface for the wheels |
root_nh | Node handle at root namespace |
controller_nh | Node 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.
|
private |
Sets the odometry publishing fields.
root_nh | Root node handle |
controller_nh | Node handle inside the controller namespace |
Definition at line 657 of file four_wheel_steering_controller.cpp.
|
virtual |
Starts controller.
time | Current time |
Reimplemented from controller_interface::ControllerBase.
Definition at line 271 of file four_wheel_steering_controller.cpp.
|
virtual |
Stops controller.
time | Current time |
Reimplemented from controller_interface::ControllerBase.
Definition at line 281 of file four_wheel_steering_controller.cpp.
|
virtual |
Updates controller, i.e. computes the odometry and sets the new velocity commands.
time | Current time |
period | Time since the last called to update |
Implements controller_interface::ControllerBase.
Definition at line 265 of file four_wheel_steering_controller.cpp.
|
private |
Compute and publish command.
time | Current time |
period | Time 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.
|
private |
Update and publish odometry.
time | Current time |
Definition at line 286 of file four_wheel_steering_controller.cpp.
|
private |
Frame to use for the robot base:
Definition at line 233 of file four_wheel_steering_controller.h.
|
private |
Timeout to consider cmd_vel commands old:
Definition at line 230 of file four_wheel_steering_controller.h.
|
private |
FourWheelSteering command related:
Definition at line 207 of file four_wheel_steering_controller.h.
|
private |
Definition at line 208 of file four_wheel_steering_controller.h.
|
private |
Definition at line 203 of file four_wheel_steering_controller.h.
|
private |
Definition at line 202 of file four_wheel_steering_controller.h.
|
private |
Whether to publish odometry to tf or not:
Definition at line 236 of file four_wheel_steering_controller.h.
|
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.
|
private |
Definition at line 176 of file four_wheel_steering_controller.h.
|
private |
Hardware handles:
Definition at line 174 of file four_wheel_steering_controller.h.
|
private |
Definition at line 243 of file four_wheel_steering_controller.h.
|
private |
Speed limiters:
Definition at line 242 of file four_wheel_steering_controller.h.
|
private |
Definition at line 170 of file four_wheel_steering_controller.h.
|
private |
Definition at line 245 of file four_wheel_steering_controller.h.
|
private |
Definition at line 244 of file four_wheel_steering_controller.h.
|
private |
Definition at line 166 of file four_wheel_steering_controller.h.
|
private |
Definition at line 213 of file four_wheel_steering_controller.h.
|
private |
Odometry related:
Definition at line 212 of file four_wheel_steering_controller.h.
|
private |
Definition at line 215 of file four_wheel_steering_controller.h.
|
private |
Definition at line 171 of file four_wheel_steering_controller.h.
|
private |
Odometry related:
Definition at line 169 of file four_wheel_steering_controller.h.
|
private |
Definition at line 177 of file four_wheel_steering_controller.h.
|
private |
Definition at line 175 of file four_wheel_steering_controller.h.
|
private |
Definition at line 204 of file four_wheel_steering_controller.h.
|
private |
Definition at line 209 of file four_wheel_steering_controller.h.
|
private |
Definition at line 214 of file four_wheel_steering_controller.h.
|
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.
|
private |
Wheel base (distance between front and rear wheel):
Definition at line 227 of file four_wheel_steering_controller.h.
|
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.
|
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.