Go to the documentation of this file.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 
00035 
00036 
00037 #ifndef JSK_RVIZ_PLUGINS_CAMERA_INFO_DISPLAY_H_
00038 #define JSK_RVIZ_PLUGINS_CAMERA_INFO_DISPLAY_H_
00039 
00040 #ifndef Q_MOC_RUN
00041 #include <rviz/display.h>
00042 #include <rviz/message_filter_display.h>
00043 #include <rviz/properties/color_property.h>
00044 #include <rviz/properties/bool_property.h>
00045 #include <rviz/properties/float_property.h>
00046 #include <rviz/properties/ros_topic_property.h>
00047 #include <rviz/ogre_helpers/shape.h>
00048 #include <rviz/ogre_helpers/billboard_line.h>
00049 #include <OGRE/OgreSceneNode.h>
00050 #include <image_geometry/pinhole_camera_model.h>
00051 #include <sensor_msgs/Image.h>
00052 #include <OGRE/OgreManualObject.h>
00053 #include <OGRE/OgreTextureManager.h>
00054 #include <OGRE/OgreTexture.h>
00055 #include <cv_bridge/cv_bridge.h>
00056 #include <sensor_msgs/image_encodings.h>
00057 #include <image_transport/subscriber.h>
00058 
00059 #include "image_transport_hints_property.h"
00060 #endif
00061 
00062 namespace jsk_rviz_plugins
00063 {
00064   class TrianglePolygon
00065   {
00066   public:
00067     typedef std::shared_ptr<TrianglePolygon> Ptr;
00068     TrianglePolygon(Ogre::SceneManager* manager,
00069                     Ogre::SceneNode* node,
00070                     const cv::Point3d& O,
00071                     const cv::Point3d& A,
00072                     const cv::Point3d& B,
00073                     const std::string& name,
00074                     const Ogre::ColourValue& color,
00075                     bool use_color,
00076                     bool upper_triangle);
00077     virtual ~TrianglePolygon();
00078   protected:
00079     Ogre::ManualObject* manual_;
00080     Ogre::SceneManager* manager_;
00081   private:
00082     
00083   };
00084   
00085   class CameraInfoDisplay:
00086     public rviz::MessageFilterDisplay<sensor_msgs::CameraInfo>
00087   {
00088     Q_OBJECT
00089   public:
00090     typedef std::shared_ptr<rviz::Shape> ShapePtr;
00091     typedef std::shared_ptr<rviz::BillboardLine> BillboardLinePtr;
00092     CameraInfoDisplay();
00093     virtual ~CameraInfoDisplay();
00094     
00095   protected:
00097     
00099     virtual void onInitialize();
00100     virtual void reset();
00101     virtual void processMessage(const sensor_msgs::CameraInfo::ConstPtr& msg);
00103     
00105     virtual void update(float wall_dt, float ros_dt);
00106     virtual bool isSameCameraInfo(
00107       const sensor_msgs::CameraInfo::ConstPtr& camera_info);
00108     virtual void createCameraInfoShapes(
00109       const sensor_msgs::CameraInfo::ConstPtr& camera_info);
00110     virtual void addPointToEdge(
00111       const cv::Point3d& point);
00112     virtual void addPolygon(
00113       const cv::Point3d& O, const cv::Point3d& A, const cv::Point3d& B, std::string name,
00114       bool use_color, bool upper_triangle);
00115     virtual void prepareMaterial();
00116     virtual void createTextureForBottom(int width, int height);
00117     virtual void imageCallback(const sensor_msgs::Image::ConstPtr& msg);
00118     virtual void drawImageTexture();
00119     virtual void subscribeImage(std::string topic);
00121     
00123     std::vector<TrianglePolygon::Ptr> polygons_;
00124     BillboardLinePtr edges_;
00125     sensor_msgs::CameraInfo::ConstPtr camera_info_;
00126     Ogre::MaterialPtr material_;
00127     Ogre::TexturePtr texture_;
00128     Ogre::MaterialPtr material_bottom_;
00129     Ogre::TexturePtr bottom_texture_;
00130     image_transport::Subscriber image_sub_;
00131     boost::mutex mutex_;
00133     
00135     double alpha_;
00136     double far_clip_distance_;
00137     QColor color_;
00138     QColor edge_color_;
00139     bool show_polygons_;
00140     bool show_edges_;
00141     bool use_image_;
00142     bool image_updated_;
00143     bool not_show_side_polygons_;
00144     cv::Mat image_;
00146     
00148     ImageTransportHintsProperty* image_transport_hints_property_;
00149     rviz::FloatProperty* far_clip_distance_property_;
00150     rviz::FloatProperty* alpha_property_;
00151     rviz::ColorProperty* color_property_;
00152     rviz::ColorProperty* edge_color_property_;
00153     rviz::BoolProperty* show_polygons_property_;
00154     rviz::BoolProperty* not_show_side_polygons_property_;
00155     rviz::BoolProperty* use_image_property_;
00156     rviz::RosTopicProperty* image_topic_property_;
00157     rviz::BoolProperty* show_edges_property_;
00158     
00159   protected Q_SLOTS:
00160     void updateFarClipDistance();
00161     void updateAlpha();
00162     void updateColor();
00163     void updateShowEdges();
00164     void updateShowPolygons();
00165     void updateNotShowSidePolygons();
00166     void updateImageTopic();
00167     void updateUseImage();
00168     void updateEdgeColor();
00169   };
00170   
00171 }
00172 
00173 #endif