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