Static Public Member Functions
tabletop_object_detector::MarkerGenerator Class Reference

A convenience class for generating markers based on various clustering and fitting data. More...

#include <marker_generator.h>

List of all members.

Static Public Member Functions

static visualization_msgs::Marker createMarker (std::string frame_id, double duration, double xdim, double ydim, double zdim, double r, double g, double b, int type, int id, std::string ns, geometry_msgs::Pose pose)
 Create a generic Marker.
template<class PointCloudType >
static visualization_msgs::Marker getCloudMarker (const PointCloudType &cloud)
 A marker with all the points in a cloud in a random color.
static visualization_msgs::Marker getConvexHullTableMarker (const arm_navigation_msgs::Shape &mesh)
 A marker showing where a convex hull table is.
static visualization_msgs::Marker getFitMarker (const arm_navigation_msgs::Shape &mesh, double rank)
 A marker showing where a fit model is believed to be.
static visualization_msgs::Marker getTableMarker (float xmin, float xmax, float ymin, float ymax)
 Create a line strip marker that goes around a detected table.

Detailed Description

A convenience class for generating markers based on various clustering and fitting data.

Just a place to group all the different debug marker generators so they don't polute other classes.

Definition at line 55 of file marker_generator.h.


Member Function Documentation

visualization_msgs::Marker tabletop_object_detector::MarkerGenerator::createMarker ( std::string  frame_id,
double  duration,
double  xdim,
double  ydim,
double  zdim,
double  r,
double  g,
double  b,
int  type,
int  id,
std::string  ns,
geometry_msgs::Pose  pose 
) [static]

Create a generic Marker.

Create a generic Marker

Definition at line 160 of file marker_generator.cpp.

template<class PointCloudType >
visualization_msgs::Marker tabletop_object_detector::MarkerGenerator::getCloudMarker ( const PointCloudType &  cloud) [static]

A marker with all the points in a cloud in a random color.

It is the responsibility of the caller to set the appropriate pose for the marker so that it shows up in the right reference frame.

Definition at line 76 of file marker_generator.h.

A marker showing where a convex hull table is.

Create a marker for a convex hull table It is the responsibility of the caller to set the appropriate pose for the marker so that it shows up in the right reference frame.

Definition at line 137 of file marker_generator.cpp.

visualization_msgs::Marker tabletop_object_detector::MarkerGenerator::getFitMarker ( const arm_navigation_msgs::Shape mesh,
double  rank 
) [static]

A marker showing where a fit model is believed to be.

Definition at line 50 of file marker_generator.cpp.

visualization_msgs::Marker tabletop_object_detector::MarkerGenerator::getTableMarker ( float  xmin,
float  xmax,
float  ymin,
float  ymax 
) [static]

Create a line strip marker that goes around a detected table.

The point cloud is a set of points belonging to the plane, in the plane coordinate system (with the origin in the plane and the z axis normal to the plane).

It is the responsibility of the caller to set the appropriate pose for the marker so that it shows up in the right reference frame.

Definition at line 85 of file marker_generator.cpp.


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


tabletop_object_detector
Author(s): Marius Muja and Matei Ciocarlie
autogenerated on Fri Jan 3 2014 11:48:48