00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 #include <ros/ros.h>
00035
00036 #include <visualization_msgs/Marker.h>
00037 #include <visualization_msgs/MarkerArray.h>
00038
00039 #include "object_manipulator/tools/msg_helpers.h"
00040 #include "object_manipulator/tools/shape_tools.h"
00041
00042 namespace object_manipulator {
00043
00044 void drawCylinder (ros::Publisher &pub, const shapes::Cylinder &shape, const char *ns,
00045 int id, const ros::Duration lifetime, const std_msgs::ColorRGBA color, bool destroy, bool frame_locked)
00046 {
00047 visualization_msgs::Marker marker;
00048 marker.header = shape.header;
00049 marker.ns = ns;
00050 marker.id = id;
00051 marker.type = visualization_msgs::Marker::CYLINDER;
00052 marker.action = destroy?((int32_t)visualization_msgs::Marker::DELETE):((int32_t)visualization_msgs::Marker::ADD);
00053 tf::poseTFToMsg(shape.frame, marker.pose);
00054 tf::vector3TFToMsg(shape.dims, marker.scale);
00055 marker.color = color;
00056 marker.lifetime = lifetime;
00057 marker.frame_locked = frame_locked;
00058 pub.publish(marker);
00059 }
00060
00061 void drawBox (ros::Publisher &pub, const shapes::Box &shape, const char *ns,
00062 int id, const ros::Duration lifetime, const std_msgs::ColorRGBA color, bool destroy, bool frame_locked)
00063 {
00064 visualization_msgs::Marker marker;
00065 marker.header = shape.header;
00066 marker.ns = ns;
00067 marker.id = id;
00068 marker.type = visualization_msgs::Marker::CUBE;
00069 marker.action = destroy?((int32_t)visualization_msgs::Marker::DELETE):((int32_t)visualization_msgs::Marker::ADD);
00070 tf::poseTFToMsg(shape.frame, marker.pose);
00071 tf::vector3TFToMsg(shape.dims, marker.scale);
00072 marker.color = color;
00073 marker.lifetime = lifetime;
00074 marker.frame_locked = frame_locked;
00075 pub.publish(marker);
00076 }
00077
00078 void drawSphere (ros::Publisher &pub, const shapes::Sphere &shape, const char *ns,
00079 int id, const ros::Duration lifetime, const std_msgs::ColorRGBA color, bool destroy, bool frame_locked)
00080 {
00081 visualization_msgs::Marker marker;
00082 marker.header = shape.header;
00083 marker.ns = ns;
00084 marker.id = id;
00085 marker.type = visualization_msgs::Marker::SPHERE;
00086 marker.action = destroy?((int32_t)visualization_msgs::Marker::DELETE):((int32_t)visualization_msgs::Marker::ADD);
00087 tf::poseTFToMsg(shape.frame, marker.pose);
00088 tf::vector3TFToMsg(shape.dims, marker.scale);
00089 marker.color = color;
00090 marker.lifetime = lifetime;
00091 marker.frame_locked = frame_locked;
00092 pub.publish(marker);
00093 }
00094
00095 void drawArrow (ros::Publisher &pub, const shapes::Arrow &shape, const char *ns,
00096 int id, const ros::Duration lifetime, const std_msgs::ColorRGBA color, bool destroy, bool frame_locked)
00097 {
00098 visualization_msgs::Marker marker;
00099 marker.header = shape.header;
00100 marker.ns = ns;
00101 marker.id = id;
00102 marker.type = visualization_msgs::Marker::ARROW;
00103 marker.action = destroy?((int32_t)visualization_msgs::Marker::DELETE):((int32_t)visualization_msgs::Marker::ADD);
00104 tf::poseTFToMsg(shape.frame, marker.pose);
00105 tf::vector3TFToMsg(shape.dims, marker.scale);
00106 marker.color = color;
00107 marker.lifetime = lifetime;
00108 marker.frame_locked = frame_locked;
00109 pub.publish(marker);
00110 }
00111
00112 void drawMesh (ros::Publisher &pub, const shapes::Mesh &shape, const char *ns,
00113 int id, const ros::Duration lifetime, const std_msgs::ColorRGBA color, bool destroy, bool frame_locked)
00114 {
00115 visualization_msgs::Marker marker;
00116 marker.header = shape.header;
00117 marker.ns = ns;
00118 marker.id = id;
00119 marker.type = visualization_msgs::Marker::MESH_RESOURCE;
00120 marker.mesh_resource = shape.mesh_resource;
00121 marker.mesh_use_embedded_materials = shape.use_embedded_materials;
00122 marker.action = destroy?((int32_t)visualization_msgs::Marker::DELETE):((int32_t)visualization_msgs::Marker::ADD);
00123 tf::poseTFToMsg(shape.frame, marker.pose);
00124 tf::vector3TFToMsg(shape.dims, marker.scale);
00125 marker.color = color;
00126 marker.lifetime = lifetime;
00127 marker.frame_locked = frame_locked;
00128 pub.publish(marker);
00129 }
00130
00131 }