Public Member Functions | Private Attributes
WaypointsNavigation Class Reference

List of all members.

Public Member Functions

void cmdVelCallback (const geometry_msgs::Twist &msg)
tf::StampedTransform getRobotPosGL ()
bool navigationFinished ()
bool onNavigationPoint (const geometry_msgs::Point &dest, double dist_err=0.8)
void publishMarkers ()
bool readFile (const std::string &filename)
void run ()
bool shouldSendGoal ()
void sleep ()
void startNavigationGL (const geometry_msgs::Point &dest)
void startNavigationGL (const geometry_msgs::Pose &dest)
void stopPointCallback (const geometry_msgs::PointStamped &msg)
void syscommandCallback (const std_msgs::String &msg)
 WaypointsNavigation ()

Private Attributes

ros::ServiceClient clear_costmaps_srv_
ros::Subscriber cmd_vel_sub_
geometry_msgs::Pose finish_pose_
bool has_activate_
bool has_restart_
bool in_stop_
bool is_stop_
double last_moved_time_
ros::Publisher marker_pub_
actionlib::SimpleActionClient
< move_base_msgs::MoveBaseAction > 
move_base_action_
ros::Rate rate_
std::string robot_frame_
geometry_msgs::PointStamped stop_point_
ros::Subscriber stop_point_sub_
ros::Subscriber syscommand_sub_
tf::TransformListener tf_listener_
std::vector
< geometry_msgs::PointStamped > 
waypoints_
std::string world_frame_

Detailed Description

Definition at line 58 of file waypoints_nav.cpp.


Constructor & Destructor Documentation

Definition at line 60 of file waypoints_nav.cpp.


Member Function Documentation

void WaypointsNavigation::cmdVelCallback ( const geometry_msgs::Twist &  msg) [inline]

Definition at line 105 of file waypoints_nav.cpp.

Definition at line 229 of file waypoints_nav.cpp.

Definition at line 213 of file waypoints_nav.cpp.

bool WaypointsNavigation::onNavigationPoint ( const geometry_msgs::Point dest,
double  dist_err = 0.8 
) [inline]

Definition at line 217 of file waypoints_nav.cpp.

Definition at line 263 of file waypoints_nav.cpp.

bool WaypointsNavigation::readFile ( const std::string filename) [inline]

Definition at line 126 of file waypoints_nav.cpp.

void WaypointsNavigation::run ( ) [inline]

Definition at line 293 of file waypoints_nav.cpp.

Definition at line 195 of file waypoints_nav.cpp.

void WaypointsNavigation::sleep ( ) [inline]

Definition at line 240 of file waypoints_nav.cpp.

Definition at line 246 of file waypoints_nav.cpp.

Definition at line 253 of file waypoints_nav.cpp.

void WaypointsNavigation::stopPointCallback ( const geometry_msgs::PointStamped &  msg) [inline]

Definition at line 119 of file waypoints_nav.cpp.

void WaypointsNavigation::syscommandCallback ( const std_msgs::String &  msg) [inline]

Definition at line 95 of file waypoints_nav.cpp.


Member Data Documentation

Definition at line 362 of file waypoints_nav.cpp.

Definition at line 359 of file waypoints_nav.cpp.

Definition at line 350 of file waypoints_nav.cpp.

Definition at line 351 of file waypoints_nav.cpp.

Definition at line 354 of file waypoints_nav.cpp.

Definition at line 353 of file waypoints_nav.cpp.

Definition at line 352 of file waypoints_nav.cpp.

Definition at line 363 of file waypoints_nav.cpp.

Definition at line 361 of file waypoints_nav.cpp.

actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> WaypointsNavigation::move_base_action_ [private]

Definition at line 347 of file waypoints_nav.cpp.

Definition at line 357 of file waypoints_nav.cpp.

Definition at line 355 of file waypoints_nav.cpp.

geometry_msgs::PointStamped WaypointsNavigation::stop_point_ [private]

Definition at line 349 of file waypoints_nav.cpp.

Definition at line 360 of file waypoints_nav.cpp.

Definition at line 358 of file waypoints_nav.cpp.

Definition at line 356 of file waypoints_nav.cpp.

std::vector<geometry_msgs::PointStamped> WaypointsNavigation::waypoints_ [private]

Definition at line 348 of file waypoints_nav.cpp.

Definition at line 355 of file waypoints_nav.cpp.


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


waypoints_navigation
Author(s): Daiki Maekawa
autogenerated on Wed Nov 4 2015 11:28:10