#include <ros/ros.h>
#include <tf/tf.h>
#include "object_manipulator/tools/msg_helpers.h"
#include <std_msgs/ColorRGBA.h>
#include <geometry_msgs/Vector3.h>
#include <geometry_msgs/Point.h>
#include <geometry_msgs/Quaternion.h>
#include <geometry_msgs/Pose.h>
#include <geometry_msgs/Transform.h>
#include <geometry_msgs/PoseStamped.h>
Go to the source code of this file.
Classes | |
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::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) |