Classes | Namespaces | Functions
shape_tools.h File Reference
#include <ros/ros.h>
#include <tf/tf.h>
#include "object_manipulator/tools/msg_helpers.h"
Include dependency graph for shape_tools.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  object_manipulator::shapes::Arrow
 A representation of an arrow, using a frame and dimensions. More...
class  object_manipulator::shapes::Box
 A representation of a box, using a frame and dimensions. More...
class  object_manipulator::shapes::Cylinder
 A representation of a cylinder, using a frame and dimensions. More...
class  object_manipulator::shapes::Mesh
 A container for a mesh, using a frame and dimensions. More...
class  object_manipulator::shapes::Sphere
 A representation of a sphere/ellipsoid, using a frame and dimensions. More...

Namespaces

namespace  object_manipulator
 

Helper functions for using image regions of PointCloud2s.


namespace  object_manipulator::shapes

Functions

void object_manipulator::drawArrow (ros::Publisher &pub, const shapes::Arrow &shape, const char *ns="arrow", int id=0, const ros::Duration lifetime=ros::Duration(), const std_msgs::ColorRGBA color=msg::createColorMsg(0.5, 0.5, 0.5, 0.5), bool destroy=false, bool frame_locked=false)
void object_manipulator::drawBox (ros::Publisher &pub, const shapes::Box &shape, const char *ns="box", int id=0, const ros::Duration lifetime=ros::Duration(), const std_msgs::ColorRGBA color=msg::createColorMsg(0.5, 0.5, 0.5, 0.5), bool destroy=false, bool frame_locked=false)
void object_manipulator::drawCylinder (ros::Publisher &pub, const shapes::Cylinder &shape, const char *ns="cylinder", int id=0, const ros::Duration lifetime=ros::Duration(), const std_msgs::ColorRGBA color=msg::createColorMsg(0.5, 0.5, 0.5, 0.5), bool destroy=false, bool frame_locked=false)
void object_manipulator::drawMesh (ros::Publisher &pub, const shapes::Mesh &shape, const char *ns="mesh", int id=0, const ros::Duration lifetime=ros::Duration(), const std_msgs::ColorRGBA color=msg::createColorMsg(0.5, 0.5, 0.5, 0.5), bool destroy=false, bool frame_locked=false)
void object_manipulator::drawSphere (ros::Publisher &pub, const shapes::Sphere &shape, const char *ns="sphere", int id=0, const ros::Duration lifetime=ros::Duration(), const std_msgs::ColorRGBA color=msg::createColorMsg(0.5, 0.5, 0.5, 0.5), bool destroy=false, bool frame_locked=false)


object_manipulator
Author(s): Matei Ciocarlie and Kaijen Hsiao
autogenerated on Mon Oct 6 2014 02:59:51