#include <ackermann_steering_controller.h>
Classes | |
struct | Commands |
Velocity command related: More... | |
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 64 of file ackermann_steering_controller.h.
ackermann_steering_controller::AckermannSteeringController::AckermannSteeringController | ( | ) |
Definition at line 111 of file ackermann_steering_controller.cpp.
|
private |
Brakes the wheels, i.e. sets the velocity to 0.
Definition at line 357 of file ackermann_steering_controller.cpp.
|
private |
Velocity command callback.
command | Velocity command message (twist) |
Definition at line 366 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 128 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 396 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 471 of file ackermann_steering_controller.cpp.
|
virtual |
Starts controller.
time | Current time |
Reimplemented from controller_interface::ControllerBase.
Definition at line 342 of file ackermann_steering_controller.cpp.
|
virtual |
Stops controller.
time | Current time |
Reimplemented from controller_interface::ControllerBase.
Definition at line 352 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 262 of file ackermann_steering_controller.cpp.
|
private |
Whether to allow multiple publishers on cmd_vel topic or not:
Definition at line 147 of file ackermann_steering_controller.h.
|
private |
Frame to use for the robot base:
Definition at line 150 of file ackermann_steering_controller.h.
|
private |
Timeout to consider cmd_vel commands old:
Definition at line 144 of file ackermann_steering_controller.h.
|
private |
Definition at line 123 of file ackermann_steering_controller.h.
|
private |
Definition at line 124 of file ackermann_steering_controller.h.
|
private |
Whether to publish odometry to tf or not:
Definition at line 156 of file ackermann_steering_controller.h.
|
private |
Definition at line 112 of file ackermann_steering_controller.h.
|
private |
Definition at line 166 of file ackermann_steering_controller.h.
|
private |
Speed limiters:
Definition at line 165 of file ackermann_steering_controller.h.
|
private |
Definition at line 107 of file ackermann_steering_controller.h.
|
private |
Definition at line 168 of file ackermann_steering_controller.h.
|
private |
Definition at line 167 of file ackermann_steering_controller.h.
|
private |
Definition at line 103 of file ackermann_steering_controller.h.
|
private |
Frame to use for odometry and odom tf:
Definition at line 153 of file ackermann_steering_controller.h.
|
private |
Odometry related:
Definition at line 128 of file ackermann_steering_controller.h.
|
private |
Definition at line 130 of file ackermann_steering_controller.h.
|
private |
Definition at line 108 of file ackermann_steering_controller.h.
|
private |
Odometry related:
Definition at line 106 of file ackermann_steering_controller.h.
|
private |
Hardware handles:
Definition at line 111 of file ackermann_steering_controller.h.
|
private |
Number of steer joints:
Definition at line 162 of file ackermann_steering_controller.h.
|
private |
Definition at line 141 of file ackermann_steering_controller.h.
|
private |
Definition at line 125 of file ackermann_steering_controller.h.
|
private |
Definition at line 129 of file ackermann_steering_controller.h.
|
private |
Number of wheel joints:
Definition at line 159 of file ackermann_steering_controller.h.
|
private |
Wheel radius (assuming it's the same for the left and right wheels):
Definition at line 136 of file ackermann_steering_controller.h.
|
private |
Definition at line 140 of file ackermann_steering_controller.h.
|
private |
Wheel separation, wrt the midpoint of the wheel width:
Definition at line 133 of file ackermann_steering_controller.h.
|
private |
Wheel separation and radius calibration multipliers:
Definition at line 139 of file ackermann_steering_controller.h.