Public Member Functions
PurePursuitControllerNode Class Reference

Pure pursuit controller. More...

#include <purePursuitController.h>

List of all members.

Public Member Functions

void angle2quat (vector< float > &angle, vector< float > &quaternion)
Constructors/destructor
 PurePursuitControllerNode (const ros::NodeHandle &nh)
 Constructor.
virtual ~PurePursuitControllerNode ()
 Destructor.
Methods
void spin ()
 Spin once.
bool step (geometry_msgs::Twist &twist)
 Step once.
geometry_msgs::PoseStamped getCurrentPose () const
 Returns the current pose of the robot.
double getLookAheadThreshold () const
 Returns the current lookahead distance threshold.
int getNextWayPoint (int wayPoint)
 Returns the next way point by linear search from the current waypoint.
void resetParam ()

Protected Member Functions

Protected methods
bool pathExecute (pure_pursuit_controller::executePath::Request &req, pure_pursuit_controller::executePath::Response &res)
 Path message execute.
bool goTriExecute (pure_pursuit_controller::executePath::Request &req, pure_pursuit_controller::executePath::Response &res)
bool pathCancel (pure_pursuit_controller::cancelPath::Request &req, pure_pursuit_controller::cancelPath::Response &res)
bool pathCut (pure_pursuit_controller::cutPath::Request &req, pure_pursuit_controller::cutPath::Response &res)
void odometryCallback (const nav_msgs::Odometry &msg)
 Odometry message callback.
void timerCallback (const ros::TimerEvent &event)
 Timer callback.
void getParameters ()

Protected Attributes

Protected members
ros::NodeHandle _nodeHandle
 ROS node handle.
ros::ServiceServer _goTriExecute
ros::ServiceServer _pathExecute
ros::ServiceServer _pathCancel
ros::ServiceServer _pathCut
ros::Publisher _finishGoTri
std::string _pathExecuteServerName
 Path message topic name.
std::string _odometryTopicName
 Odometry message topic name.
std::string _poseFrameId
 Frame id of pose estimates.
int _queueDepth
 Queue size for receiving messages.
bool isFinish
int safeWayNum
bool ifGoTrisector
bool ifFirstPoint
bool ifCutPath
nav_msgs::Path _currentReferencePath
 Current reference path.
geometry_msgs::Twist _currentVelocity
 Current velocity.
double _frequency
 Controller frequency.
int _nextWayPoint
 Next way point.
ros::Publisher _cmdVelocityPublisher
 Commanded velocity publisher.
std::string _cmdVelocityTopicName
 Commanded velocity topic name.
int _initialWayPoint
 Initial way point.
double _velocity
 Velocity.
double _lookAheadRatio
 Lookahead ratio.
double _epsilon
 Epsilon.
tf::TransformListener _tfListener
 Transform listener for robot's pose w.r.t. map.
ros::Timer _timer
 Timer.

Detailed Description

Pure pursuit controller.

The class PurePursuitControllerNode implements a pure pursuit controller.

Definition at line 27 of file purePursuitController.h.


Constructor & Destructor Documentation

Constructor.

cmd_vel_mux/input/teleop ///cmd_vel

Definition at line 31 of file purePursuitController.cpp.

Destructor.

Definition at line 51 of file purePursuitController.cpp.


Member Function Documentation

void PurePursuitControllerNode::angle2quat ( vector< float > &  angle,
vector< float > &  quaternion 
)

Definition at line 60 of file purePursuitController.cpp.

geometry_msgs::PoseStamped PurePursuitControllerNode::getCurrentPose ( ) const

Returns the current pose of the robot.

Definition at line 239 of file purePursuitController.cpp.

Returns the current lookahead distance threshold.

Definition at line 264 of file purePursuitController.cpp.

Returns the next way point by linear search from the current waypoint.

Definition at line 269 of file purePursuitController.cpp.

Definition at line 326 of file purePursuitController.cpp.

Definition at line 85 of file purePursuitController.cpp.

void PurePursuitControllerNode::odometryCallback ( const nav_msgs::Odometry &  msg) [protected]

Odometry message callback.

Definition at line 109 of file purePursuitController.cpp.

Definition at line 96 of file purePursuitController.cpp.

Definition at line 102 of file purePursuitController.cpp.

Path message execute.

Definition at line 75 of file purePursuitController.cpp.

Definition at line 115 of file purePursuitController.cpp.

Spin once.

Definition at line 125 of file purePursuitController.cpp.

bool PurePursuitControllerNode::step ( geometry_msgs::Twist &  twist)

Step once.

Definition at line 154 of file purePursuitController.cpp.

void PurePursuitControllerNode::timerCallback ( const ros::TimerEvent event) [protected]

Timer callback.

Definition at line 130 of file purePursuitController.cpp.


Member Data Documentation

Commanded velocity publisher.

Definition at line 115 of file purePursuitController.h.

Commanded velocity topic name.

Definition at line 117 of file purePursuitController.h.

Current reference path.

Definition at line 107 of file purePursuitController.h.

geometry_msgs::Twist PurePursuitControllerNode::_currentVelocity [protected]

Current velocity.

Definition at line 109 of file purePursuitController.h.

Epsilon.

Definition at line 126 of file purePursuitController.h.

Definition at line 89 of file purePursuitController.h.

Controller frequency.

Definition at line 111 of file purePursuitController.h.

Path message subscriber

Definition at line 84 of file purePursuitController.h.

Initial way point.

Definition at line 120 of file purePursuitController.h.

Lookahead ratio.

Definition at line 124 of file purePursuitController.h.

Next way point.

Definition at line 113 of file purePursuitController.h.

ROS node handle.

Definition at line 81 of file purePursuitController.h.

Odometry message topic name.

Definition at line 94 of file purePursuitController.h.

Definition at line 86 of file purePursuitController.h.

Definition at line 87 of file purePursuitController.h.

Definition at line 85 of file purePursuitController.h.

Path message topic name.

Definition at line 91 of file purePursuitController.h.

std::string PurePursuitControllerNode::_poseFrameId [protected]

Frame id of pose estimates.

Definition at line 96 of file purePursuitController.h.

Queue size for receiving messages.

Definition at line 99 of file purePursuitController.h.

Transform listener for robot's pose w.r.t. map.

Definition at line 128 of file purePursuitController.h.

Timer.

Definition at line 130 of file purePursuitController.h.

Velocity.

Definition at line 122 of file purePursuitController.h.

Definition at line 104 of file purePursuitController.h.

Definition at line 103 of file purePursuitController.h.

Definition at line 102 of file purePursuitController.h.

Definition at line 100 of file purePursuitController.h.

Definition at line 101 of file purePursuitController.h.


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


pure_pursuit_controller
Author(s): Lintao Zheng, Kai Xu
autogenerated on Thu Jun 6 2019 19:50:45