#include <waypoint_provider.hpp>
|
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) |
|
Definition at line 33 of file waypoint_provider.hpp.
yocs::WaypointProvider::WaypointProvider |
( |
ros::NodeHandle & |
n, |
|
|
yocs_msgs::WaypointList & |
wps, |
|
|
yocs_msgs::TrajectoryList & |
trajs |
|
) |
| |
yocs::WaypointProvider::~WaypointProvider |
( |
| ) |
|
void yocs::WaypointProvider::createMarkerArrow |
( |
const int |
i, |
|
|
const yocs_msgs::Waypoint & |
wp, |
|
|
visualization_msgs::Marker & |
marker |
|
) |
| |
|
protected |
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 |
void yocs::WaypointProvider::createMarkerLineStrip |
( |
const int |
i, |
|
|
const yocs_msgs::Trajectory & |
traj, |
|
|
visualization_msgs::Marker & |
marker |
|
) |
| |
|
protected |
void yocs::WaypointProvider::generateTrajectoryMarkers |
( |
const yocs_msgs::TrajectoryList & |
trajs, |
|
|
visualization_msgs::MarkerArray & |
traj_markers |
|
) |
| |
|
protected |
void yocs::WaypointProvider::generateWaypointMarkers |
( |
const yocs_msgs::WaypointList & |
wps, |
|
|
visualization_msgs::MarkerArray & |
wp_markers |
|
) |
| |
|
protected |
void yocs::WaypointProvider::init |
( |
| ) |
|
|
protected |
bool yocs::WaypointProvider::processWaypointsService |
( |
yocs_msgs::WaypointListService::Request & |
request, |
|
|
yocs_msgs::WaypointListService::Response & |
response |
|
) |
| |
|
protected |
void yocs::WaypointProvider::spin |
( |
| ) |
|
bool yocs::WaypointProvider::initialized_ |
|
private |
int yocs::WaypointProvider::label_index_ |
|
private |
int yocs::WaypointProvider::marker_index_ |
|
private |
yocs_msgs::TrajectoryList yocs::WaypointProvider::trajectories_ |
|
private |
visualization_msgs::MarkerArray yocs::WaypointProvider::trajectory_markers_ |
|
private |
visualization_msgs::MarkerArray yocs::WaypointProvider::waypoint_markers_ |
|
private |
yocs_msgs::WaypointList yocs::WaypointProvider::waypoints_ |
|
private |
The documentation for this class was generated from the following files: