#include <ackermann_steering_controller.h>

Classes | |
| struct | Commands |
| Velocity command related: More... | |
Public Member Functions | |
| AckermannSteeringController () | |
| 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::PositionJointInterface, hardware_interface::VelocityJointInterface > | |
| 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 |
| 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 | cmdVelCallback (const geometry_msgs::Twist &command) |
| Velocity command callback. More... | |
| bool | setOdomParamsFromUrdf (ros::NodeHandle &root_nh, const std::string rear_wheel_name, const std::string front_steer_name, bool lookup_wheel_separation_h, bool lookup_wheel_radius) |
| Sets odometry parameters from the URDF, i.e. the wheel radius and separation. More... | |
| void | setOdomPubFields (ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) |
| Sets the odometry publishing fields. More... | |
This class makes some assumptions on the model of the robot:
Definition at line 96 of file ackermann_steering_controller.h.
| ackermann_steering_controller::AckermannSteeringController::AckermannSteeringController | ( | ) |
Definition at line 108 of file ackermann_steering_controller.cpp.
|
private |
Brakes the wheels, i.e. sets the velocity to 0.
Definition at line 354 of file ackermann_steering_controller.cpp.
|
private |
Velocity command callback.
| command | Velocity command message (twist) |
Definition at line 363 of file ackermann_steering_controller.cpp.
|
virtual |
Initialize controller.
| hw | Velocity 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::PositionJointInterface, hardware_interface::VelocityJointInterface >.
Definition at line 125 of file ackermann_steering_controller.cpp.
|
private |
Sets odometry parameters from the URDF, i.e. the wheel radius and separation.
| root_nh | Root node handle |
| left_wheel_name | Name of the left wheel joint |
| right_wheel_name | Name of the right wheel joint |
Definition at line 393 of file ackermann_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 468 of file ackermann_steering_controller.cpp.
|
virtual |
Starts controller.
| time | Current time |
Reimplemented from controller_interface::ControllerBase.
Definition at line 339 of file ackermann_steering_controller.cpp.
|
virtual |
Stops controller.
| time | Current time |
Reimplemented from controller_interface::ControllerBase.
Definition at line 349 of file ackermann_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 259 of file ackermann_steering_controller.cpp.
|
private |
Whether to allow multiple publishers on cmd_vel topic or not:
Definition at line 211 of file ackermann_steering_controller.h.
|
private |
Frame to use for the robot base:
Definition at line 214 of file ackermann_steering_controller.h.
|
private |
Timeout to consider cmd_vel commands old:
Definition at line 208 of file ackermann_steering_controller.h.
|
private |
Definition at line 187 of file ackermann_steering_controller.h.
|
private |
Definition at line 188 of file ackermann_steering_controller.h.
|
private |
Whether to publish odometry to tf or not:
Definition at line 220 of file ackermann_steering_controller.h.
|
private |
Definition at line 176 of file ackermann_steering_controller.h.
|
private |
Definition at line 230 of file ackermann_steering_controller.h.
|
private |
Speed limiters:
Definition at line 229 of file ackermann_steering_controller.h.
|
private |
Definition at line 171 of file ackermann_steering_controller.h.
|
private |
Definition at line 232 of file ackermann_steering_controller.h.
|
private |
Definition at line 231 of file ackermann_steering_controller.h.
|
private |
Definition at line 167 of file ackermann_steering_controller.h.
|
private |
Frame to use for odometry and odom tf:
Definition at line 217 of file ackermann_steering_controller.h.
|
private |
Odometry related:
Definition at line 192 of file ackermann_steering_controller.h.
|
private |
Definition at line 194 of file ackermann_steering_controller.h.
|
private |
Definition at line 172 of file ackermann_steering_controller.h.
|
private |
Odometry related:
Definition at line 170 of file ackermann_steering_controller.h.
|
private |
Hardware handles:
Definition at line 175 of file ackermann_steering_controller.h.
|
private |
Number of steer joints:
Definition at line 226 of file ackermann_steering_controller.h.
|
private |
Definition at line 205 of file ackermann_steering_controller.h.
|
private |
Definition at line 189 of file ackermann_steering_controller.h.
|
private |
Definition at line 193 of file ackermann_steering_controller.h.
|
private |
Number of wheel joints:
Definition at line 223 of file ackermann_steering_controller.h.
|
private |
Wheel radius (assuming it's the same for the left and right wheels):
Definition at line 200 of file ackermann_steering_controller.h.
|
private |
Definition at line 204 of file ackermann_steering_controller.h.
|
private |
Wheel separation, wrt the midpoint of the wheel width:
Definition at line 197 of file ackermann_steering_controller.h.
|
private |
Wheel separation and radius calibration multipliers:
Definition at line 203 of file ackermann_steering_controller.h.