00001 /* 00002 :q 00003 * Copyright (c) 2010, Nico Blodow (blodow@cs.tum.edu) 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 are met: 00008 * 00009 * * Redistributions of source code must retain the above copyright 00010 * notice, this list of conditions and the following disclaimer. 00011 * * Redistributions in binary form must reproduce the above copyright 00012 * notice, this list of conditions and the following disclaimer in the 00013 * documentation and/or other materials provided with the distribution. 00014 * * Neither the name of Willow Garage, Inc. nor the names of its 00015 * contributors may be used to endorse or promote products derived from 00016 * this software without specific prior written permission. 00017 * 00018 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00019 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00020 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00021 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00022 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00023 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00024 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00025 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00026 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00027 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00028 * POSSIBILITY OF SUCH DAMAGE. 00029 */ 00030 00031 #ifndef RVIZ_TRIANGULAR_MESH_DISPLAY_H_ 00032 #define RVIZ_TRIANGULAR_MESH_DISPLAY_H_ 00033 00034 #include "rviz/display.h" 00035 #include "rviz/helpers/color.h" 00036 #include "rviz/properties/forwards.h" 00037 00038 #include <boost/thread/mutex.hpp> 00039 00040 #include <boost/shared_ptr.hpp> 00041 00042 #include <triangle_mesh_msgs/TriangleMesh.h> 00043 00044 #include <message_filters/subscriber.h> 00045 #include <tf/message_filter.h> 00046 00047 #include <OGRE/OgreMesh.h> 00048 #include <OGRE/OgreSubMesh.h> 00049 #include <OGRE/OgreMeshManager.h> 00050 #include <OGRE/OgreEntity.h> 00051 #include <OGRE/OgreSubEntity.h> 00052 #include <OGRE/OgreHardwareBufferManager.h> 00053 00054 namespace Ogre 00055 { 00056 class SceneNode; 00057 class ManualObject; 00058 } 00059 00060 namespace triangle_mesh 00061 { 00062 00067 class TriangleMeshDisplay : public rviz::Display 00068 { 00069 public: 00070 TriangleMeshDisplay(const std::string& name, rviz::VisualizationManager* manager); 00071 00072 virtual ~TriangleMeshDisplay(); 00073 00074 void setTopic(const std::string& topic); 00075 const std::string& getTopic() 00076 { 00077 return (topic_); 00078 } 00079 00080 void setColor(const rviz::Color& color); 00081 const rviz::Color& getColor() 00082 { 00083 return (color_); 00084 } 00085 00086 void setWireFrameEnabled(const bool& wf); 00087 const bool& getWireFrameEnabled() 00088 { 00089 return (wf_); 00090 } 00091 00092 // Overrides from Display 00093 virtual void targetFrameChanged(); 00094 virtual void fixedFrameChanged(); 00095 virtual void createProperties(); 00096 virtual void update(float wall_dt, float ros_dt); 00097 virtual void reset(); 00098 00099 protected: 00100 void subscribe(); 00101 void unsubscribe(); 00102 void clear(); 00103 void incomingMessage(const triangle_mesh_msgs::TriangleMesh::ConstPtr& message); 00104 void processMessage(const triangle_mesh_msgs::TriangleMesh::ConstPtr& message); 00105 00106 // overrides from Display 00107 virtual void onEnable(); 00108 virtual void onDisable(); 00109 00110 std::string topic_; 00111 rviz::Color color_; 00112 bool wf_; 00113 triangle_mesh_msgs::TriangleMesh::ConstPtr current_message_; 00114 00115 Ogre::SceneNode* scene_node_; 00116 00117 //this stuff needs to be freed every time we get a new message.. 00118 Ogre::MeshPtr mesh_; 00119 Ogre::SubMesh* submesh_; 00120 Ogre::HardwareVertexBufferSharedPtr vbuf; 00121 Ogre::VertexData* data; 00122 Ogre::HardwareIndexBufferSharedPtr ibuf; 00123 Ogre::Entity* entity_; 00124 00125 message_filters::Subscriber<triangle_mesh_msgs::TriangleMesh> sub_; 00126 tf::MessageFilter<triangle_mesh_msgs::TriangleMesh> tf_filter_; 00127 00128 rviz::BoolPropertyWPtr wireframe_property_; 00129 rviz::ColorPropertyWPtr color_property_; 00130 rviz::ROSTopicStringPropertyWPtr topic_property_; 00131 00132 int count; 00133 }; 00134 00135 } // namespace positionstring_rviz_plugin 00136 00137 #endif /* RVIZ_TRIANGULAR_MESH_DISPLAY_H_ */ 00138