Public Member Functions | Private Attributes | List of all members
BaseController Class Reference

#include <controller.h>

Public Member Functions

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...
 

Private Attributes

double beta_
 
ros::Publisher cmd_vel_pub_
 
geometry_msgs::Twist command_
 
double dist_
 
double k1_
 
double k2_
 
double lambda_
 
tf::TransformListener listener_
 
double max_angular_velocity_
 
double max_velocity_
 
double min_velocity_
 
ros::Publisher path_pub_
 
bool ready_
 
geometry_msgs::PoseStamped start_
 
bool turning_
 

Detailed Description

Definition at line 27 of file controller.h.

Constructor & Destructor Documentation

◆ BaseController()

BaseController::BaseController ( ros::NodeHandle nh)
explicit

Definition at line 28 of file controller.cpp.

Member Function Documentation

◆ 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
distanceDistance in meters to backup.
rotate_distanceAmount 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)

Get the last command sent.

Definition at line 263 of file controller.cpp.

◆ stop()

void BaseController::stop ( )

send stop command to robot base

Definition at line 269 of file controller.cpp.

Member Data Documentation

◆ beta_

double BaseController::beta_
private

Definition at line 72 of file controller.h.

◆ cmd_vel_pub_

ros::Publisher BaseController::cmd_vel_pub_
private

Definition at line 58 of file controller.h.

◆ command_

geometry_msgs::Twist BaseController::command_
private

Definition at line 62 of file controller.h.

◆ dist_

double BaseController::dist_
private

Definition at line 74 of file controller.h.

◆ k1_

double BaseController::k1_
private

Definition at line 67 of file controller.h.

◆ k2_

double BaseController::k2_
private

Definition at line 68 of file controller.h.

◆ lambda_

double BaseController::lambda_
private

Definition at line 73 of file controller.h.

◆ listener_

tf::TransformListener BaseController::listener_
private

Definition at line 61 of file controller.h.

◆ max_angular_velocity_

double BaseController::max_angular_velocity_
private

Definition at line 71 of file controller.h.

◆ max_velocity_

double BaseController::max_velocity_
private

Definition at line 70 of file controller.h.

◆ min_velocity_

double BaseController::min_velocity_
private

Definition at line 69 of file controller.h.

◆ path_pub_

ros::Publisher BaseController::path_pub_
private

Definition at line 59 of file controller.h.

◆ ready_

bool BaseController::ready_
private

Definition at line 80 of file controller.h.

◆ start_

geometry_msgs::PoseStamped BaseController::start_
private

Definition at line 79 of file controller.h.

◆ turning_

bool BaseController::turning_
private

Definition at line 81 of file controller.h.


The documentation for this class was generated from the following files:


fetch_open_auto_dock
Author(s): Michael Ferguson, Griswald Brooks
autogenerated on Mon Feb 28 2022 22:21:37