A controller for driving a differential drive base to a pose goal or along a path specified by multiple poses. More...
#include <controller.hpp>
Public Member Functions | |
DiffDrivePoseController (ros::NodeHandle &nh, std::string &name) | |
bool | init () |
Set-up necessary publishers/subscribers and variables. | |
void | spinOnce () |
Calculates velocity commands to move the diff-drive base to the (next) pose goal. | |
virtual | ~DiffDrivePoseController () |
Private Member Functions | |
void | controlMaxVelCB (const std_msgs::Float32ConstPtr msg) |
Callback for updating the controller's maximum linear control velocity. | |
void | disableCB (const std_msgs::EmptyConstPtr msg) |
Callback for disabling the controler. | |
void | enableCB (const std_msgs::EmptyConstPtr msg) |
Callback for enabling the controler. | |
void | getControlOutput () |
Calculates the controller output based on the current pose difference. | |
bool | getPoseDiff () |
Determines the pose difference in polar coordinates. | |
void | setControlOutput () |
Sends out the new velocity commands for the left and right wheel based on the current controller output. | |
Private Attributes | |
std::string | base_frame_name_ |
frame name of the base | |
double | beta_ |
ros::Publisher | command_velocity_publisher_ |
publisher for sending out base velocity commands | |
ros::Subscriber | control_velocity_subscriber_ |
subscriber for setting the controller's linear velocity | |
double | cur_ |
path to goal curvature | |
double | delta_ |
current heading of the base [rad] | |
ros::Subscriber | disable_controller_subscriber_ |
subscriber for disabling the controller | |
ros::Subscriber | enable_controller_subscriber_ |
subscriber for enabling the controller | |
std::string | goal_frame_name_ |
frame name of the goal (pose) | |
double | k_1_ |
constant factor determining the ratio of the rate of change in theta to the rate of change in r | |
double | k_2_ |
constant factor applied to the heading error feedback | |
double | lambda_ |
std::string | name_ |
ros::NodeHandle | nh_ |
double | r_ |
distance to pose goal [m] | |
tf::StampedTransform | tf_goal_pose_rel_ |
transform for the goal pose relative to the base pose | |
tf::TransformListener | tf_listener_ |
tf used to get goal pose relative to the base pose | |
double | theta_ |
direction of the pose goal [rad] | |
double | v_ |
linear base velocity [m/s] | |
double | v_max_ |
maximum linear base velocity [m/s] | |
double | w_ |
angular base velocity [rad/s] | |
double | w_max_ |
maximum angular base velocity [rad/s] |
A controller for driving a differential drive base to a pose goal or along a path specified by multiple poses.
This controller implements a control law drives a differental drive base towards a planar pose goal, i.e. 2D position (x,y) + 1D orientation (theta). It also allows path following by specifying multiple pose goals. The control law contains a transition strategy, which insures that the base moves through each pose and transitions smoothly to the next pose goal.
This controller is an implementation of control law based on the following work: {DBLP:conf/icra/ParkK11, author = {Jong Jin Park and Benjamin Kuipers}, title = {A smooth control law for graceful motion of differential wheeled mobile robots in 2D environment}, booktitle = {ICRA}, year = {2011}, pages = {4896-4902}, ee = {http://dx.doi.org/10.1109/ICRA.2011.5980167}, crossref = {DBLP:conf/icra/2011}, bibsource = {DBLP, http://dblp.uni-trier.de} }
This controller can be enabled/disabled.
Definition at line 77 of file controller.hpp.
yocs::DiffDrivePoseController::DiffDrivePoseController | ( | ros::NodeHandle & | nh, |
std::string & | name | ||
) | [inline] |
Definition at line 80 of file controller.hpp.
virtual yocs::DiffDrivePoseController::~DiffDrivePoseController | ( | ) | [inline, virtual] |
Definition at line 83 of file controller.hpp.
void yocs::DiffDrivePoseController::controlMaxVelCB | ( | const std_msgs::Float32ConstPtr | msg | ) | [private] |
Callback for updating the controller's maximum linear control velocity.
msg | maximum linear control velocity |
Definition at line 317 of file controller.hpp.
void yocs::DiffDrivePoseController::disableCB | ( | const std_msgs::EmptyConstPtr | msg | ) | [private] |
Callback for disabling the controler.
msg | empty message |
Definition at line 335 of file controller.hpp.
void yocs::DiffDrivePoseController::enableCB | ( | const std_msgs::EmptyConstPtr | msg | ) | [private] |
Callback for enabling the controler.
msg | empty message |
Definition at line 323 of file controller.hpp.
void yocs::DiffDrivePoseController::getControlOutput | ( | ) | [private] |
Calculates the controller output based on the current pose difference.
Definition at line 297 of file controller.hpp.
bool yocs::DiffDrivePoseController::getPoseDiff | ( | ) | [private] |
Determines the pose difference in polar coordinates.
Definition at line 271 of file controller.hpp.
bool yocs::DiffDrivePoseController::init | ( | ) | [virtual] |
Set-up necessary publishers/subscribers and variables.
Implements yocs::Controller.
Definition at line 184 of file controller.hpp.
void yocs::DiffDrivePoseController::setControlOutput | ( | ) | [private] |
Sends out the new velocity commands for the left and right wheel based on the current controller output.
Definition at line 309 of file controller.hpp.
Calculates velocity commands to move the diff-drive base to the (next) pose goal.
Definition at line 244 of file controller.hpp.
std::string yocs::DiffDrivePoseController::base_frame_name_ [private] |
frame name of the base
Definition at line 179 of file controller.hpp.
double yocs::DiffDrivePoseController::beta_ [private] |
constant factor for the curvature-based velocity rule determines how fast the velocity drops when the curvature increases
Definition at line 167 of file controller.hpp.
publisher for sending out base velocity commands
Definition at line 140 of file controller.hpp.
subscriber for setting the controller's linear velocity
Definition at line 138 of file controller.hpp.
double yocs::DiffDrivePoseController::cur_ [private] |
path to goal curvature
Definition at line 158 of file controller.hpp.
double yocs::DiffDrivePoseController::delta_ [private] |
current heading of the base [rad]
Definition at line 148 of file controller.hpp.
subscriber for disabling the controller
Definition at line 136 of file controller.hpp.
subscriber for enabling the controller
Definition at line 134 of file controller.hpp.
std::string yocs::DiffDrivePoseController::goal_frame_name_ [private] |
frame name of the goal (pose)
Definition at line 181 of file controller.hpp.
double yocs::DiffDrivePoseController::k_1_ [private] |
constant factor determining the ratio of the rate of change in theta to the rate of change in r
Definition at line 160 of file controller.hpp.
double yocs::DiffDrivePoseController::k_2_ [private] |
constant factor applied to the heading error feedback
Definition at line 162 of file controller.hpp.
double yocs::DiffDrivePoseController::lambda_ [private] |
constant factor for the curvature-based velocity rule determines the sharpness of the curve: higher lambda -> bigger drop in short term, smaller in the long term
Definition at line 172 of file controller.hpp.
std::string yocs::DiffDrivePoseController::name_ [private] |
Definition at line 130 of file controller.hpp.
Definition at line 129 of file controller.hpp.
double yocs::DiffDrivePoseController::r_ [private] |
distance to pose goal [m]
Definition at line 144 of file controller.hpp.
transform for the goal pose relative to the base pose
Definition at line 177 of file controller.hpp.
tf used to get goal pose relative to the base pose
Definition at line 175 of file controller.hpp.
double yocs::DiffDrivePoseController::theta_ [private] |
direction of the pose goal [rad]
Definition at line 146 of file controller.hpp.
double yocs::DiffDrivePoseController::v_ [private] |
linear base velocity [m/s]
Definition at line 150 of file controller.hpp.
double yocs::DiffDrivePoseController::v_max_ [private] |
maximum linear base velocity [m/s]
Definition at line 152 of file controller.hpp.
double yocs::DiffDrivePoseController::w_ [private] |
angular base velocity [rad/s]
Definition at line 154 of file controller.hpp.
double yocs::DiffDrivePoseController::w_max_ [private] |
maximum angular base velocity [rad/s]
Definition at line 156 of file controller.hpp.