Public Member Functions | Protected Member Functions | Private Attributes
yocs::WaypointManager Class Reference

#include <waypoint_manager.hpp>

List of all members.

Public Member Functions

void spin ()
 WaypointManager (ros::NodeHandle &n, yocs_msgs::WaypointList &wp)
 ~WaypointManager ()

Protected Member Functions

void createArrowMarker (const int i, const yocs_msgs::Waypoint &wp, visualization_msgs::Marker &marker)
void createLabelMarker (const int i, const yocs_msgs::Waypoint &wp, visualization_msgs::Marker &marker)
void generateVizmarkers (const yocs_msgs::WaypointList &wp, visualization_msgs::MarkerArray &wp_viz)
void init ()
bool processWaypointsService (yocs_msgs::WaypointListService::Request &request, yocs_msgs::WaypointListService::Response &response)

Private Attributes

bool initialized_
int label_index_
int marker_index_
ros::NodeHandle nh_
yocs_msgs::WaypointList waypoints_
ros::Publisher waypoints_pub_
ros::ServiceServer waypoints_srv_
visualization_msgs::MarkerArray waypoints_viz_
ros::Publisher waypoints_viz_pub_

Detailed Description

Definition at line 30 of file waypoint_manager.hpp.


Constructor & Destructor Documentation

yocs::WaypointManager::WaypointManager ( ros::NodeHandle n,
yocs_msgs::WaypointList &  wp 
)

Definition at line 15 of file waypoint_manager.cpp.

Definition at line 32 of file waypoint_manager.cpp.


Member Function Documentation

void yocs::WaypointManager::createArrowMarker ( const int  i,
const yocs_msgs::Waypoint &  wp,
visualization_msgs::Marker &  marker 
) [protected]

Definition at line 67 of file waypoint_manager.cpp.

void yocs::WaypointManager::createLabelMarker ( const int  i,
const yocs_msgs::Waypoint &  wp,
visualization_msgs::Marker &  marker 
) [protected]

Definition at line 86 of file waypoint_manager.cpp.

void yocs::WaypointManager::generateVizmarkers ( const yocs_msgs::WaypointList &  wp,
visualization_msgs::MarkerArray &  wp_viz 
) [protected]

Definition at line 48 of file waypoint_manager.cpp.

void yocs::WaypointManager::init ( ) [protected]
bool yocs::WaypointManager::processWaypointsService ( yocs_msgs::WaypointListService::Request &  request,
yocs_msgs::WaypointListService::Response &  response 
) [protected]

Definition at line 34 of file waypoint_manager.cpp.

Definition at line 106 of file waypoint_manager.cpp.


Member Data Documentation

Definition at line 46 of file waypoint_manager.hpp.

Definition at line 56 of file waypoint_manager.hpp.

Definition at line 55 of file waypoint_manager.hpp.

Definition at line 47 of file waypoint_manager.hpp.

yocs_msgs::WaypointList yocs::WaypointManager::waypoints_ [private]

Definition at line 52 of file waypoint_manager.hpp.

Definition at line 48 of file waypoint_manager.hpp.

Definition at line 50 of file waypoint_manager.hpp.

visualization_msgs::MarkerArray yocs::WaypointManager::waypoints_viz_ [private]

Definition at line 53 of file waypoint_manager.hpp.

Definition at line 49 of file waypoint_manager.hpp.


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


yocs_waypoint_manager
Author(s): Jihoon Lee
autogenerated on Sun Nov 23 2014 12:41:12