00001 /* 00002 Copyright (c) 2010-2014, Mathieu Labbe - IntRoLab - Universite de Sherbrooke 00003 All rights reserved. 00004 00005 Redistribution and use in source and binary forms, with or without 00006 modification, are permitted provided that the following conditions are met: 00007 * Redistributions of source code must retain the above copyright 00008 notice, this list of conditions and the following disclaimer. 00009 * Redistributions in binary form must reproduce the above copyright 00010 notice, this list of conditions and the following disclaimer in the 00011 documentation and/or other materials provided with the distribution. 00012 * Neither the name of the Universite de Sherbrooke nor the 00013 names of its contributors may be used to endorse or promote products 00014 derived from this software without specific prior written permission. 00015 00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND 00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY 00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES 00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND 00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00026 */ 00027 00028 #ifndef MAP_CLOUD_DISPLAY_H 00029 #define MAP_CLOUD_DISPLAY_H 00030 00031 #include <deque> 00032 #include <queue> 00033 #include <vector> 00034 00035 #include <rtabmap_ros/MapData.h> 00036 #include <rtabmap/core/Transform.h> 00037 00038 #include <pluginlib/class_loader.h> 00039 #include <sensor_msgs/PointCloud2.h> 00040 00041 #include <rviz/ogre_helpers/point_cloud.h> 00042 #include <rviz/message_filter_display.h> 00043 #include <rviz/default_plugin/point_cloud_transformer.h> 00044 00045 namespace rviz { 00046 class IntProperty; 00047 class BoolProperty; 00048 class EnumProperty; 00049 class FloatProperty; 00050 class PointCloudTransformer; 00051 typedef boost::shared_ptr<PointCloudTransformer> PointCloudTransformerPtr; 00052 typedef std::vector<std::string> V_string; 00053 } 00054 00055 using namespace rviz; 00056 00057 namespace rtabmap_ros 00058 { 00059 00060 class PointCloudCommon; 00061 00070 class MapCloudDisplay: public rviz::MessageFilterDisplay<rtabmap_ros::MapData> 00071 { 00072 Q_OBJECT 00073 public: 00074 struct CloudInfo 00075 { 00076 CloudInfo(); 00077 ~CloudInfo(); 00078 00079 // clear the point cloud, but keep selection handler around 00080 void clear(); 00081 00082 Ogre::SceneManager *manager_; 00083 00084 sensor_msgs::PointCloud2ConstPtr message_; 00085 rtabmap::Transform pose_; 00086 int id_; 00087 00088 Ogre::SceneNode *scene_node_; 00089 boost::shared_ptr<rviz::PointCloud> cloud_; 00090 00091 std::vector<rviz::PointCloud::Point> transformed_points_; 00092 }; 00093 typedef boost::shared_ptr<CloudInfo> CloudInfoPtr; 00094 00095 MapCloudDisplay(); 00096 virtual ~MapCloudDisplay(); 00097 00098 virtual void reset(); 00099 virtual void update( float wall_dt, float ros_dt ); 00100 00101 rviz::FloatProperty* point_world_size_property_; 00102 rviz::FloatProperty* point_pixel_size_property_; 00103 rviz::FloatProperty* alpha_property_; 00104 rviz::EnumProperty* xyz_transformer_property_; 00105 rviz::EnumProperty* color_transformer_property_; 00106 rviz::EnumProperty* style_property_; 00107 rviz::IntProperty* cloud_decimation_; 00108 rviz::FloatProperty* cloud_max_depth_; 00109 rviz::FloatProperty* cloud_voxel_size_; 00110 rviz::FloatProperty* cloud_filter_floor_height_; 00111 rviz::FloatProperty* node_filtering_radius_; 00112 rviz::FloatProperty* node_filtering_angle_; 00113 rviz::BoolProperty* download_map_; 00114 rviz::BoolProperty* download_graph_; 00115 00116 public Q_SLOTS: 00117 void causeRetransform(); 00118 00119 private Q_SLOTS: 00120 void updateStyle(); 00121 void updateBillboardSize(); 00122 void updateAlpha(); 00123 void updateXyzTransformer(); 00124 void updateColorTransformer(); 00125 void setXyzTransformerOptions( EnumProperty* prop ); 00126 void setColorTransformerOptions( EnumProperty* prop ); 00127 void updateCloudParameters(); 00128 void downloadMap(); 00129 void downloadGraph(); 00130 00131 protected: 00133 virtual void onInitialize(); 00134 00136 virtual void processMessage( const rtabmap_ros::MapDataConstPtr& cloud ); 00137 00138 private: 00139 void processMapData(const rtabmap_ros::MapData& map); 00140 00144 bool transformCloud(const CloudInfoPtr& cloud, bool fully_update_transformers); 00145 00146 rviz::PointCloudTransformerPtr getXYZTransformer(const sensor_msgs::PointCloud2ConstPtr& cloud); 00147 rviz::PointCloudTransformerPtr getColorTransformer(const sensor_msgs::PointCloud2ConstPtr& cloud); 00148 void updateTransformers( const sensor_msgs::PointCloud2ConstPtr& cloud ); 00149 void retransform(); 00150 00151 void loadTransformers(); 00152 00153 void setPropertiesHidden( const QList<Property*>& props, bool hide ); 00154 void fillTransformerOptions( rviz::EnumProperty* prop, uint32_t mask ); 00155 00156 private: 00157 ros::AsyncSpinner spinner_; 00158 ros::CallbackQueue cbqueue_; 00159 00160 std::map<int, CloudInfoPtr> cloud_infos_; 00161 00162 std::map<int, CloudInfoPtr> new_cloud_infos_; 00163 boost::mutex new_clouds_mutex_; 00164 00165 std::map<int, rtabmap::Transform> current_map_; 00166 boost::mutex current_map_mutex_; 00167 00168 struct TransformerInfo 00169 { 00170 rviz::PointCloudTransformerPtr transformer; 00171 QList<Property*> xyz_props; 00172 QList<Property*> color_props; 00173 00174 std::string readable_name; 00175 std::string lookup_name; 00176 }; 00177 typedef std::map<std::string, TransformerInfo> M_TransformerInfo; 00178 00179 boost::recursive_mutex transformers_mutex_; 00180 M_TransformerInfo transformers_; 00181 bool new_xyz_transformer_; 00182 bool new_color_transformer_; 00183 bool needs_retransform_; 00184 00185 pluginlib::ClassLoader<rviz::PointCloudTransformer>* transformer_class_loader_; 00186 }; 00187 00188 } // namespace rtabmap_ros 00189 00190 #endif