shape_tools.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 *  Copyright (c) 2011, Willow Garage, Inc.
00004 *  All rights reserved.
00005 *
00006 *  Redistribution and use in source and binary forms, with or without
00007 *  modification, are permitted provided that the following conditions
00008 *  are met:
00009 *
00010 *   * Redistributions of source code must retain the above copyright
00011 *     notice, this list of conditions and the following disclaimer.
00012 *   * Redistributions in binary form must reproduce the above
00013 *     copyright notice, this list of conditions and the following
00014 *     disclaimer in the documentation and/or other materials provided
00015 *     with the distribution.
00016 *   * Neither the name of the Willow Garage nor the names of its
00017 *     contributors may be used to endorse or promote products derived
00018 *     from this software without specific prior written permission.
00019 *
00020 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 *  POSSIBILITY OF SUCH DAMAGE.
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; // CUBE, SPHERE, ARROW, 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; // CUBE, SPHERE, ARROW, CYLINDER
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; // CUBE, SPHERE, ARROW, CYLINDER
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; // CUBE, SPHERE, ARROW, CYLINDER
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; // CUBE, SPHERE, ARROW, CYLINDER
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 } // namespace object_manipulator


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