#include <landmark_viz.h>
|
| LandmarkViz (const ros::Publisher &cloud_pub, const ros::Publisher &marker_pub) |
|
| LandmarkViz (const ros::Publisher &cloud_pub, const ros::Publisher &marker_pub, const std::string &base_frame) |
|
void | set_landmark (const sensor_msgs::PointCloud2 &cloud, const rapid_msgs::Roi3D &roi) |
|
void | UpdatePose (const geometry_msgs::Pose &pose) |
|
void | Publish () |
|
void | Clear () |
|
Definition at line 14 of file landmark_viz.h.
rapid::viz::LandmarkViz::LandmarkViz |
( |
const ros::Publisher & |
cloud_pub, |
|
|
const ros::Publisher & |
marker_pub |
|
) |
| |
rapid::viz::LandmarkViz::LandmarkViz |
( |
const ros::Publisher & |
cloud_pub, |
|
|
const ros::Publisher & |
marker_pub, |
|
|
const std::string & |
base_frame |
|
) |
| |
void rapid::viz::LandmarkViz::Clear |
( |
| ) |
|
void rapid::viz::LandmarkViz::Publish |
( |
| ) |
|
void rapid::viz::LandmarkViz::set_landmark |
( |
const sensor_msgs::PointCloud2 & |
cloud, |
|
|
const rapid_msgs::Roi3D & |
roi |
|
) |
| |
void rapid::viz::LandmarkViz::UpdatePose |
( |
const geometry_msgs::Pose & |
pose | ) |
|
The documentation for this class was generated from the following file: