mesh_display_custom.h
Go to the documentation of this file.
00001 /*
00002  * MeshDisplayCustom declaration.
00003  *
00004  * Author: Felipe Bacim.
00005  *
00006  * help with selection of robot parts 
00007  */
00008 /*
00009  * Copyright (c) 2008, Willow Garage, Inc.
00010  * All rights reserved.
00011  *
00012  * Redistribution and use in source and binary forms, with or without
00013  * modification, are permitted provided that the following conditions are met:
00014  *
00015  *     * Redistributions of source code must retain the above copyright
00016  *       notice, this list of conditions and the following disclaimer.
00017  *     * Redistributions in binary form must reproduce the above copyright
00018  *       notice, this list of conditions and the following disclaimer in the
00019  *       documentation and/or other materials provided with the distribution.
00020  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00021  *       contributors may be used to endorse or promote products derived from
00022  *       this software without specific prior written permission.
00023  *
00024  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00025  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00026  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00027  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00028  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00029  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00030  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00031  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00032  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00033  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  * POSSIBILITY OF SUCH DAMAGE.
00035  */
00036 
00037 #ifndef RVIZ_MESH_DISPLAY_H
00038 #define RVIZ_MESH_DISPLAY_H
00039 
00040 #include "rviz/display.h"
00041 #include "rviz/frame_manager.h"
00042 #include "rviz/image/image_display_base.h"
00043 #include "rviz/image/ros_image_texture.h"
00044 
00045 #include <image_transport/image_transport.h>
00046 #include <sensor_msgs/CameraInfo.h>
00047 #include <message_filters/subscriber.h>
00048 #include <tf/message_filter.h>
00049 
00050 #include <geometry_msgs/Pose.h>
00051 #include <geometry_msgs/PoseStamped.h>
00052 #include <shape_msgs/Mesh.h>
00053 #include <std_msgs/Float64.h>
00054 
00055 #include <tf/transform_listener.h>
00056 
00057 #include <OGRE/OgreVector3.h>
00058 #include "OGRE/OgreRoot.h"
00059 #include "OGRE/OgreRenderSystem.h"
00060 #include "OGRE/OgreRenderWindow.h"
00061 #include "OGRE/OgreWindowEventUtilities.h"
00062 #include "OGRE/OgreManualObject.h"
00063 #include "OGRE/OgreEntity.h"
00064 #include <OGRE/OgreSceneNode.h>
00065 #include <OGRE/OgreRenderTargetListener.h>
00066 #include <OGRE/OgreRenderQueueListener.h>
00067 
00068 #include <rviz_textured_quads/TexturedQuad.h>
00069 #include <rviz_textured_quads/TexturedQuadArray.h>
00070 
00071 #include <Eigen/Core>
00072 #include <Eigen/Geometry>
00073 
00074 #include <tf/tf.h>
00075 #include <tf_conversions/tf_eigen.h>
00076 #include <eigen_conversions/eigen_msg.h>
00077 
00078 #include <map>
00079 #include <vector>
00080 
00081 #include "text_node.h"
00082 
00083 namespace Ogre
00084 {
00085 class Entity;
00086 class SceneNode;
00087 class ManualObject;
00088 }
00089 
00090 namespace rviz
00091 {
00092 class Axes;
00093 class RenderPanel;
00094 class FloatProperty;
00095 class RosTopicProperty;
00096 class ColorProperty;
00097 class VectorProperty;
00098 class StringProperty;
00099 class QuaternionProperty;
00100 }
00101 
00102 namespace rviz
00103 {
00104 
00109 class MeshDisplayCustom: public rviz::Display,  public Ogre::RenderTargetListener, public Ogre::RenderQueueListener
00110 {
00111 Q_OBJECT
00112 public:
00113   MeshDisplayCustom();
00114   virtual ~MeshDisplayCustom();
00115 
00116   // Overrides from Display
00117   virtual void onInitialize();
00118   virtual void update( float wall_dt, float ros_dt );
00119   virtual void reset();
00120 
00121 private Q_SLOTS:
00122   void updateMeshProperties();
00123   void updateDisplayImages();
00124 
00125 protected:
00126   virtual void load(int index);
00127 
00128   // overrides from Display
00129   virtual void onEnable();
00130   virtual void onDisable();
00131 
00132   // This is called by incomingMessage().
00133   void processImage(int index, const sensor_msgs::Image& msg);
00134 
00135   virtual void subscribe();
00136   virtual void unsubscribe();
00137 
00138 private:
00139   void clear();
00140   bool updateCamera(int index, bool update_image);
00141 
00142   void createProjector(int index);
00143   void addDecalToMaterial(int index, const Ogre::String& matName);
00144   void updateImageMeshes( const rviz_textured_quads::TexturedQuadArray::ConstPtr& images );
00145   
00146   void constructQuads( const rviz_textured_quads::TexturedQuadArray::ConstPtr& images );
00147   shape_msgs::Mesh constructMesh( geometry_msgs::Pose mesh_origin, float width, float height, float border_size );
00148   void clearStates(int num_quads);
00149 
00150   float time_since_last_transform_;
00151 
00152   RosTopicProperty* display_images_topic_property_;
00153   ColorProperty* text_color_property_;
00154   FloatProperty* text_height_property_;
00155   FloatProperty* text_bottom_offset_;
00156 
00157   std::vector<shape_msgs::Mesh> last_meshes_;
00158   std::vector<geometry_msgs::Pose> mesh_poses_;
00159   std::vector<int> img_widths_, img_heights_;
00160   std::vector<float> physical_widths_, physical_heights_;
00161   std::vector<std::vector<float> > border_colors_;
00162   std::vector<float> border_sizes_;
00163   std::vector<rviz_textured_quads::TextNode*> text_nodes_;
00164 
00165   ros::NodeHandle nh_;
00166 
00167   std::vector<sensor_msgs::Image::ConstPtr> last_images_;
00168 
00169   std::vector<Ogre::SceneNode*> mesh_nodes_;
00170   std::vector<Ogre::ManualObject*> manual_objects_;
00171   std::vector<Ogre::MaterialPtr> mesh_materials_;
00172   std::vector<ROSImageTexture*> textures_;
00173 
00174   ros::Subscriber pose_sub_;
00175   ros::Subscriber rviz_display_images_sub_;
00176 
00177   std::vector<Ogre::Frustum*> decal_frustums_;
00178   std::vector<std::vector<Ogre::Frustum*> > filter_frustums_; //need multiple filters (back, up, down, left, right)
00179   std::vector<Ogre::SceneNode*> projector_nodes_;
00180 
00181   std::vector<RenderPanel*> render_panel_list_;
00182   RenderPanel* render_panel_; // this is the active render panel
00183 
00184   bool initialized_;
00185 
00186   boost::mutex mesh_mutex_;
00187 };
00188 
00189 } // namespace rviz
00190 
00191 #endif
00192 
00193 


rviz_textured_quads
Author(s): Mohit Shridhar
autogenerated on Thu Jun 6 2019 19:50:52