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

#include <waypoint_provider.hpp>

List of all members.

Public Member Functions

void spin ()
 WaypointProvider (ros::NodeHandle &n, yocs_msgs::WaypointList &wps, yocs_msgs::TrajectoryList &trajs)
 ~WaypointProvider ()

Protected Member Functions

void createMarkerArrow (const int i, const yocs_msgs::Waypoint &wp, visualization_msgs::Marker &marker)
void createMarkerLabel (const std::string frame_id, const int id, const std::string ns, const std::string wp_name, const geometry_msgs::Pose wp_pose, visualization_msgs::Marker &marker)
void createMarkerLineStrip (const int i, const yocs_msgs::Trajectory &traj, visualization_msgs::Marker &marker)
void generateTrajectoryMarkers (const yocs_msgs::TrajectoryList &trajs, visualization_msgs::MarkerArray &traj_markers)
void generateWaypointMarkers (const yocs_msgs::WaypointList &wps, visualization_msgs::MarkerArray &wp_markers)
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::TrajectoryList trajectories_
ros::Publisher trajectories_pub_
ros::Publisher trajectory_marker_pub_
visualization_msgs::MarkerArray trajectory_markers_
visualization_msgs::MarkerArray waypoint_markers_
yocs_msgs::WaypointList waypoints_
ros::Publisher waypoints_marker_pub_
ros::Publisher waypoints_pub_
ros::ServiceServer waypoints_srv_

Detailed Description

Definition at line 33 of file waypoint_provider.hpp.


Constructor & Destructor Documentation

yocs::WaypointProvider::WaypointProvider ( ros::NodeHandle n,
yocs_msgs::WaypointList &  wps,
yocs_msgs::TrajectoryList &  trajs 
)

Definition at line 15 of file waypoint_provider.cpp.

Definition at line 38 of file waypoint_provider.cpp.


Member Function Documentation

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

Definition at line 93 of file waypoint_provider.cpp.

void yocs::WaypointProvider::createMarkerLabel ( const std::string  frame_id,
const int  id,
const std::string  ns,
const std::string  wp_name,
const geometry_msgs::Pose  wp_pose,
visualization_msgs::Marker &  marker 
) [protected]

Definition at line 114 of file waypoint_provider.cpp.

void yocs::WaypointProvider::createMarkerLineStrip ( const int  i,
const yocs_msgs::Trajectory &  traj,
visualization_msgs::Marker &  marker 
) [protected]

Definition at line 139 of file waypoint_provider.cpp.

void yocs::WaypointProvider::generateTrajectoryMarkers ( const yocs_msgs::TrajectoryList &  trajs,
visualization_msgs::MarkerArray &  traj_markers 
) [protected]

Definition at line 80 of file waypoint_provider.cpp.

void yocs::WaypointProvider::generateWaypointMarkers ( const yocs_msgs::WaypointList &  wps,
visualization_msgs::MarkerArray &  wp_markers 
) [protected]

Definition at line 55 of file waypoint_provider.cpp.

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

Definition at line 40 of file waypoint_provider.cpp.

Definition at line 164 of file waypoint_provider.cpp.


Member Data Documentation

Definition at line 56 of file waypoint_provider.hpp.

Definition at line 67 of file waypoint_provider.hpp.

Definition at line 66 of file waypoint_provider.hpp.

Definition at line 57 of file waypoint_provider.hpp.

yocs_msgs::TrajectoryList yocs::WaypointProvider::trajectories_ [private]

Definition at line 63 of file waypoint_provider.hpp.

Definition at line 58 of file waypoint_provider.hpp.

Definition at line 59 of file waypoint_provider.hpp.

visualization_msgs::MarkerArray yocs::WaypointProvider::trajectory_markers_ [private]

Definition at line 64 of file waypoint_provider.hpp.

visualization_msgs::MarkerArray yocs::WaypointProvider::waypoint_markers_ [private]

Definition at line 64 of file waypoint_provider.hpp.

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

Definition at line 62 of file waypoint_provider.hpp.

Definition at line 59 of file waypoint_provider.hpp.

Definition at line 58 of file waypoint_provider.hpp.

Definition at line 60 of file waypoint_provider.hpp.


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


yocs_waypoint_provider
Author(s): Jihoon Lee
autogenerated on Thu Jun 6 2019 21:47:44