Public Member Functions | Private Member Functions | Private Attributes | List of all members
yocs::DiffDrivePoseControllerROS Class Reference

A controller for driving a differential drive base to a pose goal or along a path specified by multiple poses. More...

#include <diff_drive_pose_controller_ros.hpp>

Inheritance diagram for yocs::DiffDrivePoseControllerROS:
Inheritance graph
[legend]

Public Member Functions

 DiffDrivePoseControllerROS (ros::NodeHandle &nh, std::string &name)
 
bool init ()
 Set-up necessary publishers/subscribers and variables. More...
 
void spinOnce ()
 Calculates velocity commands to move the diff-drive base to the (next) pose goal. More...
 
virtual ~DiffDrivePoseControllerROS ()
 
- Public Member Functions inherited from yocs::DiffDrivePoseController
 DiffDrivePoseController (std::string name, double v_max, double w_max, double dist_thres=0.01, double orient_thres=0.02, double dist_eps=0.01 *0.2, double orient_eps=0.02 *0.2, double orientation_gain=0.3, double k_1=1.0, double k_2=3.0, double beta=0.4, double lambda=2.0, double v_min=0.01, double v_min_movement=0.01, double w_min_movement=0.01)
 
virtual void getControlOutput (double &v, double &w)
 Get controller result / output after spinning. More...
 
void setCurrentLimits (double v_min, double w_min, double v_max, double w_max)
 
virtual void setInput (double distance_to_goal, double delta, double theta)
 Set input of controller. Should be called before each spinOnce. More...
 
void setVerbosity (const bool &verbose)
 
virtual bool step ()
 Execute one controller step. More...
 
virtual ~DiffDrivePoseController ()
 
- Public Member Functions inherited from yocs::Controller
 Controller ()
 
bool disable ()
 
bool enable ()
 
bool getState ()
 
virtual void spin ()
 
virtual ~Controller ()
 

Private Member Functions

void controlMaxVelCB (const std_msgs::Float32ConstPtr msg)
 Callback for updating the controller's maximum linear control velocity. More...
 
void disableCB (const std_msgs::EmptyConstPtr msg)
 Callback for disabling the controler. More...
 
void enableCB (const std_msgs::StringConstPtr msg)
 Callback for enabling the controler. More...
 
bool getPoseDiff ()
 Determines the pose difference in polar coordinates. More...
 
virtual void onGoalReached ()
 Publishes goal is reached message. More...
 
void setControlOutput ()
 Calculates the controller output based on the current pose difference. More...
 

Private Attributes

std::string base_frame_name_
 frame name of the base More...
 
ros::Publisher command_velocity_publisher_
 publisher for sending out base velocity commands More...
 
ros::Subscriber control_velocity_subscriber_
 subscriber for setting the controller's linear velocity More...
 
ros::Subscriber disable_controller_subscriber_
 subscriber for disabling the controller More...
 
ros::Subscriber enable_controller_subscriber_
 subscriber for enabling the controller More...
 
std::string goal_frame_name_
 frame name of the goal (pose) More...
 
std::string name_
 
ros::NodeHandle nh_
 
ros::Publisher pose_reached_publisher_
 publishes the status of the goal pose tracking More...
 
tf::StampedTransform tf_goal_pose_rel_
 transform for the goal pose relative to the base pose More...
 
tf::TransformListener tf_listener_
 tf used to get goal pose relative to the base pose More...
 

Additional Inherited Members

- Protected Member Functions inherited from yocs::DiffDrivePoseController
virtual void calculateControls ()
 Calculates the controls with the set variables (speed, goal etc.) More...
 
virtual void controlOrientation (double angle_difference)
 
virtual void controlPose ()
 
virtual double enforceMinMax (double &value, double min, double max)
 Enforce value to be between min and max. More...
 
virtual double enforceMinVelocity (double value, double min)
 Enforce the minimum velocity. More...
 
- Protected Attributes inherited from yocs::DiffDrivePoseController
double beta_
 
double cur_
 path to goal curvature More...
 
double delta_
 current heading of the base [rad] More...
 
double dist_eps_
 Error in distance above which pose is considered different. More...
 
double dist_thres_
 lower bound for the distance (v = 0) More...
 
double k_1_
 constant factor determining the ratio of the rate of change in theta to the rate of change in r More...
 
double k_2_
 constant factor applied to the heading error feedback More...
 
double lambda_
 
std::string name_
 
double orient_eps_
 Error in orientation above which pose is considered different. More...
 
double orient_thres_
 lower bound for the orientation (w = 0) More...
 
double orientation_gain_
 p gain for angle controller More...
 
bool pose_reached_
 True, if pose has been reached (v == 0, w == 0) More...
 
double r_
 distance to pose goal [m] More...
 
double theta_
 direction of the pose goal [rad] More...
 
double v_
 linear base velocity [m/s] More...
 
double v_max_
 maximum linear base velocity [m/s] More...
 
double v_min_
 (current) minimum linear base velocity [m/s] More...
 
double v_min_movement_
 minimum linear base velocity at which we still move [m/s] More...
 
bool verbose_
 Enable or disable ros messages. More...
 
double w_
 angular base velocity [rad/s] More...
 
double w_max_
 maximum angular base velocity [rad/s] More...
 
double w_min_
 (current) minimum angular base velocity [rad/s] More...
 
double w_min_movement_
 minimum angular base velocity at which we still move [rad/s] More...
 

Detailed Description

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 76 of file diff_drive_pose_controller_ros.hpp.

Constructor & Destructor Documentation

yocs::DiffDrivePoseControllerROS::DiffDrivePoseControllerROS ( ros::NodeHandle nh,
std::string &  name 
)
inline

Definition at line 79 of file diff_drive_pose_controller_ros.hpp.

virtual yocs::DiffDrivePoseControllerROS::~DiffDrivePoseControllerROS ( )
inlinevirtual

Definition at line 84 of file diff_drive_pose_controller_ros.hpp.

Member Function Documentation

void yocs::DiffDrivePoseControllerROS::controlMaxVelCB ( const std_msgs::Float32ConstPtr  msg)
private

Callback for updating the controller's maximum linear control velocity.

Parameters
msgmaximum linear control velocity

Definition at line 215 of file diff_drive_pose_controller_ros.cpp.

void yocs::DiffDrivePoseControllerROS::disableCB ( const std_msgs::EmptyConstPtr  msg)
private

Callback for disabling the controler.

Parameters
msgempty message

Definition at line 235 of file diff_drive_pose_controller_ros.cpp.

void yocs::DiffDrivePoseControllerROS::enableCB ( const std_msgs::StringConstPtr  msg)
private

Callback for enabling the controler.

Parameters
msggoal frame name

Definition at line 222 of file diff_drive_pose_controller_ros.cpp.

bool yocs::DiffDrivePoseControllerROS::getPoseDiff ( )
private

Determines the pose difference in polar coordinates.

Definition at line 167 of file diff_drive_pose_controller_ros.cpp.

bool yocs::DiffDrivePoseControllerROS::init ( )
virtual

Set-up necessary publishers/subscribers and variables.

Returns
true, if successful

Reimplemented from yocs::DiffDrivePoseController.

Definition at line 40 of file diff_drive_pose_controller_ros.cpp.

void yocs::DiffDrivePoseControllerROS::onGoalReached ( )
privatevirtual

Publishes goal is reached message.

Reimplemented from yocs::DiffDrivePoseController.

Definition at line 197 of file diff_drive_pose_controller_ros.cpp.

void yocs::DiffDrivePoseControllerROS::setControlOutput ( )
private

Calculates the controller output based on the current pose difference.

Definition at line 204 of file diff_drive_pose_controller_ros.cpp.

void yocs::DiffDrivePoseControllerROS::spinOnce ( )

Calculates velocity commands to move the diff-drive base to the (next) pose goal.

Definition at line 139 of file diff_drive_pose_controller_ros.cpp.

Member Data Documentation

std::string yocs::DiffDrivePoseControllerROS::base_frame_name_
private

frame name of the base

Definition at line 156 of file diff_drive_pose_controller_ros.hpp.

ros::Publisher yocs::DiffDrivePoseControllerROS::command_velocity_publisher_
private

publisher for sending out base velocity commands

Definition at line 147 of file diff_drive_pose_controller_ros.hpp.

ros::Subscriber yocs::DiffDrivePoseControllerROS::control_velocity_subscriber_
private

subscriber for setting the controller's linear velocity

Definition at line 145 of file diff_drive_pose_controller_ros.hpp.

ros::Subscriber yocs::DiffDrivePoseControllerROS::disable_controller_subscriber_
private

subscriber for disabling the controller

Definition at line 143 of file diff_drive_pose_controller_ros.hpp.

ros::Subscriber yocs::DiffDrivePoseControllerROS::enable_controller_subscriber_
private

subscriber for enabling the controller

Definition at line 141 of file diff_drive_pose_controller_ros.hpp.

std::string yocs::DiffDrivePoseControllerROS::goal_frame_name_
private

frame name of the goal (pose)

Definition at line 158 of file diff_drive_pose_controller_ros.hpp.

std::string yocs::DiffDrivePoseControllerROS::name_
private

Definition at line 137 of file diff_drive_pose_controller_ros.hpp.

ros::NodeHandle yocs::DiffDrivePoseControllerROS::nh_
private

Definition at line 136 of file diff_drive_pose_controller_ros.hpp.

ros::Publisher yocs::DiffDrivePoseControllerROS::pose_reached_publisher_
private

publishes the status of the goal pose tracking

Definition at line 149 of file diff_drive_pose_controller_ros.hpp.

tf::StampedTransform yocs::DiffDrivePoseControllerROS::tf_goal_pose_rel_
private

transform for the goal pose relative to the base pose

Definition at line 154 of file diff_drive_pose_controller_ros.hpp.

tf::TransformListener yocs::DiffDrivePoseControllerROS::tf_listener_
private

tf used to get goal pose relative to the base pose

Definition at line 152 of file diff_drive_pose_controller_ros.hpp.


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


yocs_diff_drive_pose_controller
Author(s): Marcus Liebhardt
autogenerated on Mon Jun 10 2019 15:53:50