#include <controller.h>
|
| bool | approach (const geometry_msgs::PoseStamped &target) |
| | Implements something loosely based on "A Smooth Control Law for
Graceful Motion of Differential Wheeled Mobile Robots in 2D Environments" by Park and Kuipers, ICRA 2011. More...
|
| |
| bool | backup (double distance, double rotate_distance) |
| | Back off dock, then rotate. Robot is first reversed by the prescribed distance, and then rotates with respect to it's current orientation. More...
|
| |
| | BaseController (ros::NodeHandle &nh) |
| |
| bool | getCommand (geometry_msgs::Twist &command) |
| | Get the last command sent. More...
|
| |
| void | stop () |
| | send stop command to robot base More...
|
| |
Definition at line 27 of file controller.h.
◆ BaseController()
◆ approach()
| bool BaseController::approach |
( |
const geometry_msgs::PoseStamped & |
target | ) |
|
Implements something loosely based on "A Smooth Control Law for
Graceful Motion of Differential Wheeled Mobile Robots in 2D Environments" by Park and Kuipers, ICRA 2011.
- Returns
- true if base has reached goal.
Definition at line 44 of file controller.cpp.
◆ backup()
| bool BaseController::backup |
( |
double |
distance, |
|
|
double |
rotate_distance |
|
) |
| |
Back off dock, then rotate. Robot is first reversed by the prescribed distance, and then rotates with respect to it's current orientation.
- Parameters
-
| distance | Distance in meters to backup. |
| rotate_distance | Amount of angle in radians for the robot to yaw. |
Definition at line 173 of file controller.cpp.
◆ getCommand()
| bool BaseController::getCommand |
( |
geometry_msgs::Twist & |
command | ) |
|
◆ stop()
| void BaseController::stop |
( |
| ) |
|
◆ beta_
| double BaseController::beta_ |
|
private |
◆ cmd_vel_pub_
◆ command_
| geometry_msgs::Twist BaseController::command_ |
|
private |
◆ dist_
| double BaseController::dist_ |
|
private |
◆ k1_
| double BaseController::k1_ |
|
private |
◆ k2_
| double BaseController::k2_ |
|
private |
◆ lambda_
| double BaseController::lambda_ |
|
private |
◆ listener_
◆ max_angular_velocity_
| double BaseController::max_angular_velocity_ |
|
private |
◆ max_velocity_
| double BaseController::max_velocity_ |
|
private |
◆ min_velocity_
| double BaseController::min_velocity_ |
|
private |
◆ path_pub_
◆ ready_
| bool BaseController::ready_ |
|
private |
◆ start_
| geometry_msgs::PoseStamped BaseController::start_ |
|
private |
◆ turning_
| bool BaseController::turning_ |
|
private |
The documentation for this class was generated from the following files: