| Public Member Functions | |
| bool | cancelAllGoals (double timeout=2.0) | 
| void | finalGoalCB (const geometry_msgs::PoseStamped::ConstPtr &goal) | 
| bool | init () | 
| void | publishMarkers (bool clear=false) | 
| void | resetWaypoints () | 
| void | spin () | 
| void | waypointCB (const geometry_msgs::PointStamped::ConstPtr &point) | 
| WaypointsGoalNode () | |
| Private Types | |
| enum | { NONE = 0, GOAL, LOOP } | 
| enum | { IDLE = 0, READY, START, ACTIVE, COMPLETED } | 
| Private Member Functions | |
| bool | equals (const geometry_msgs::PoseStamped &a, const geometry_msgs::PoseStamped &b) | 
| bool | equals (const geometry_msgs::Point &a, const geometry_msgs::Point &b) | 
| bool | readWaypointsFile (std::string file) | 
| Private Attributes | |
| double | close_enough_ | 
| ros::Subscriber | final_goal_sub_ | 
| double | frequency_ | 
| geometry_msgs::PoseStamped | goal_ | 
| double | goal_timeout_ | 
| enum WaypointsGoalNode:: { ... } | mode_ | 
| actionlib::SimpleActionClient < move_base_msgs::MoveBaseAction > | move_base_ac_ | 
| const geometry_msgs::PoseStamped | NOWHERE | 
| std::string | robot_frame_ | 
| enum WaypointsGoalNode:: { ... } | state_ | 
| tf::TransformListener | tf_listener_ | 
| std::vector < geometry_msgs::PointStamped > | waypoints_ | 
| std::string | waypoints_file_ | 
| std::vector < geometry_msgs::PointStamped > ::iterator | waypoints_it_ | 
| ros::Subscriber | waypoints_sub_ | 
| std::string | world_frame_ | 
| ros::Publisher | wp_markers_pub_ | 
Definition at line 55 of file waypoints_navi.cpp.
| anonymous enum  [private] | 
Definition at line 396 of file waypoints_navi.cpp.
| anonymous enum  [private] | 
Definition at line 401 of file waypoints_navi.cpp.
| WaypointsGoalNode::WaypointsGoalNode | ( | ) |  [inline] | 
Definition at line 58 of file waypoints_navi.cpp.
| bool WaypointsGoalNode::cancelAllGoals | ( | double | timeout = 2.0 | ) |  [inline] | 
Definition at line 141 of file waypoints_navi.cpp.
| bool WaypointsGoalNode::equals | ( | const geometry_msgs::PoseStamped & | a, | 
| const geometry_msgs::PoseStamped & | b | ||
| ) |  [inline, private] | 
Definition at line 530 of file waypoints_navi.cpp.
| bool WaypointsGoalNode::equals | ( | const geometry_msgs::Point & | a, | 
| const geometry_msgs::Point & | b | ||
| ) |  [inline, private] | 
Definition at line 538 of file waypoints_navi.cpp.
| void WaypointsGoalNode::finalGoalCB | ( | const geometry_msgs::PoseStamped::ConstPtr & | goal | ) |  [inline] | 
Definition at line 98 of file waypoints_navi.cpp.
| bool WaypointsGoalNode::init | ( | ) |  [inline] | 
Definition at line 62 of file waypoints_navi.cpp.
| void WaypointsGoalNode::publishMarkers | ( | bool | clear = false | ) |  [inline] | 
Definition at line 179 of file waypoints_navi.cpp.
| bool WaypointsGoalNode::readWaypointsFile | ( | std::string | file | ) |  [inline, private] | 
Definition at line 428 of file waypoints_navi.cpp.
| void WaypointsGoalNode::resetWaypoints | ( | ) |  [inline] | 
Definition at line 167 of file waypoints_navi.cpp.
| void WaypointsGoalNode::spin | ( | ) |  [inline] | 
Definition at line 256 of file waypoints_navi.cpp.
| void WaypointsGoalNode::waypointCB | ( | const geometry_msgs::PointStamped::ConstPtr & | point | ) |  [inline] | 
Definition at line 118 of file waypoints_navi.cpp.
| double WaypointsGoalNode::close_enough_  [private] | 
Definition at line 409 of file waypoints_navi.cpp.
Definition at line 422 of file waypoints_navi.cpp.
| double WaypointsGoalNode::frequency_  [private] | 
Definition at line 408 of file waypoints_navi.cpp.
| geometry_msgs::PoseStamped WaypointsGoalNode::goal_  [private] | 
Definition at line 418 of file waypoints_navi.cpp.
| double WaypointsGoalNode::goal_timeout_  [private] | 
Definition at line 410 of file waypoints_navi.cpp.
| enum { ... }   WaypointsGoalNode::mode_  [private] | 
| actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> WaypointsGoalNode::move_base_ac_  [private] | 
Definition at line 425 of file waypoints_navi.cpp.
| const geometry_msgs::PoseStamped WaypointsGoalNode::NOWHERE  [private] | 
Definition at line 394 of file waypoints_navi.cpp.
| std::string WaypointsGoalNode::robot_frame_  [private] | 
Definition at line 411 of file waypoints_navi.cpp.
| enum { ... }   WaypointsGoalNode::state_  [private] | 
Definition at line 420 of file waypoints_navi.cpp.
| std::vector<geometry_msgs::PointStamped> WaypointsGoalNode::waypoints_  [private] | 
Definition at line 416 of file waypoints_navi.cpp.
| std::string WaypointsGoalNode::waypoints_file_  [private] | 
Definition at line 414 of file waypoints_navi.cpp.
| std::vector<geometry_msgs::PointStamped>::iterator WaypointsGoalNode::waypoints_it_  [private] | 
Definition at line 417 of file waypoints_navi.cpp.
Definition at line 423 of file waypoints_navi.cpp.
| std::string WaypointsGoalNode::world_frame_  [private] | 
Definition at line 412 of file waypoints_navi.cpp.
Definition at line 421 of file waypoints_navi.cpp.