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 #ifndef RVIZ_POINT_CLOUD_BASE_H
00031 #define RVIZ_POINT_CLOUD_BASE_H
00032
00033 #include <pluginlib/class_loader.h>
00034
00035 #include "point_cloud_transformer.h"
00036
00037 #include "rviz/display.h"
00038 #include "rviz/helpers/color.h"
00039 #include "rviz/properties/forwards.h"
00040 #include "rviz/selection/forwards.h"
00041
00042 #include "ogre_tools/point_cloud.h"
00043
00044 #include <message_filters/time_sequencer.h>
00045
00046 #include "sensor_msgs/PointCloud.h"
00047 #include "sensor_msgs/PointCloud2.h"
00048
00049 #include <ros/spinner.h>
00050 #include <ros/callback_queue.h>
00051
00052 #include <boost/shared_ptr.hpp>
00053 #include <boost/thread/mutex.hpp>
00054 #include <boost/thread/recursive_mutex.hpp>
00055
00056 #include <deque>
00057 #include <queue>
00058 #include <vector>
00059
00060 namespace rviz
00061 {
00062
00063 class PointCloudSelectionHandler;
00064 typedef boost::shared_ptr<PointCloudSelectionHandler> PointCloudSelectionHandlerPtr;
00065 class PointCloudTransformer;
00066 typedef boost::shared_ptr<PointCloudTransformer> PointCloudTransformerPtr;
00067
00076 class PointCloudBase : public Display
00077 {
00078 private:
00079 struct CloudInfo
00080 {
00081 CloudInfo();
00082 ~CloudInfo();
00083
00084 float time_;
00085
00086 Ogre::Matrix4 transform_;
00087 sensor_msgs::PointCloud2ConstPtr message_;
00088 uint32_t num_points_;
00089
00090 PointCloud transformed_points_;
00091 };
00092 typedef boost::shared_ptr<CloudInfo> CloudInfoPtr;
00093 typedef std::deque<CloudInfoPtr> D_CloudInfo;
00094 typedef std::vector<CloudInfoPtr> V_CloudInfo;
00095 typedef std::queue<CloudInfoPtr> Q_CloudInfo;
00096
00097 public:
00102 enum Style
00103 {
00104 Points,
00105 Billboards,
00106 BillboardSpheres,
00107 Boxes,
00108
00109 StyleCount,
00110 };
00111
00116 enum ChannelRender
00117 {
00118 Intensity,
00119 Curvature,
00120 ColorRGBSpace,
00121 NormalSphere,
00122
00123 ChannelRenderCount,
00124 };
00125
00126 PointCloudBase();
00127 ~PointCloudBase();
00128
00129 void onInitialize();
00130
00135 void setStyle( int style );
00141 void setBillboardSize( float size );
00146 void setDecayTime( float time );
00147
00148 float getBillboardSize() { return billboard_size_; }
00149 int getStyle() { return style_; }
00150 float getDecayTime() { return point_decay_time_; }
00151
00152 float getAlpha() { return alpha_; }
00153 void setAlpha( float alpha );
00154
00155 bool getSelectable() { return selectable_; }
00156 void setSelectable(bool selectable);
00157
00158
00159 virtual void fixedFrameChanged();
00160 virtual void createProperties();
00161 virtual void reset();
00162 virtual void update(float wall_dt, float ros_dt);
00163
00164 void causeRetransform();
00165
00166 protected:
00167 virtual void onEnable();
00168 virtual void onDisable();
00169
00170 typedef std::vector<ogre_tools::PointCloud::Point> V_Point;
00171 typedef std::vector<V_Point> VV_Point;
00172
00176 bool transformCloud(const CloudInfoPtr& cloud, V_Point& points, bool fully_update_transformers);
00177
00178 void processMessage(const sensor_msgs::PointCloud2ConstPtr& cloud);
00179 void addMessage(const sensor_msgs::PointCloudConstPtr& cloud);
00180 void addMessage(const sensor_msgs::PointCloud2ConstPtr& cloud);
00181 void updateStatus();
00182
00183 void setXYZTransformer(const std::string& name);
00184 void setColorTransformer(const std::string& name);
00185 const std::string& getXYZTransformer() { return xyz_transformer_; }
00186 const std::string& getColorTransformer() { return color_transformer_; }
00187 PointCloudTransformerPtr getXYZTransformer(const sensor_msgs::PointCloud2ConstPtr& cloud);
00188 PointCloudTransformerPtr getColorTransformer(const sensor_msgs::PointCloud2ConstPtr& cloud);
00189 void updateTransformers(const sensor_msgs::PointCloud2ConstPtr& cloud, bool fully_update);
00190 void retransform();
00191 void onTransformerOptions(V_string& ops, uint32_t mask);
00192
00193 void loadTransformers();
00194
00195 ros::AsyncSpinner spinner_;
00196 ros::CallbackQueue cbqueue_;
00197
00198 D_CloudInfo clouds_;
00199 boost::mutex clouds_mutex_;
00200 bool new_cloud_;
00201
00202 ogre_tools::PointCloud* cloud_;
00203 Ogre::SceneNode* scene_node_;
00204
00205 VV_Point new_points_;
00206 V_CloudInfo new_clouds_;
00207 boost::mutex new_clouds_mutex_;
00208
00209 float alpha_;
00210
00211 struct TransformerInfo
00212 {
00213 PointCloudTransformerPtr transformer;
00214 V_PropertyBaseWPtr xyz_props;
00215 V_PropertyBaseWPtr color_props;
00216
00217 std::string readable_name;
00218 std::string lookup_name;
00219 };
00220 typedef std::map<std::string, TransformerInfo> M_TransformerInfo;
00221
00222 boost::recursive_mutex transformers_mutex_;
00223 M_TransformerInfo transformers_;
00224 std::string xyz_transformer_;
00225 std::string color_transformer_;
00226 bool new_xyz_transformer_;
00227 bool new_color_transformer_;
00228 bool needs_retransform_;
00229
00230 int style_;
00231 float billboard_size_;
00232 float point_decay_time_;
00233
00234 bool selectable_;
00235 CollObjectHandle coll_handle_;
00236 PointCloudSelectionHandlerPtr coll_handler_;
00237
00238 uint32_t messages_received_;
00239 uint32_t total_point_count_;
00240
00241 pluginlib::ClassLoader<PointCloudTransformer>* transformer_class_loader_;
00242
00243 BoolPropertyWPtr selectable_property_;
00244 FloatPropertyWPtr billboard_size_property_;
00245 FloatPropertyWPtr alpha_property_;
00246 EditEnumPropertyWPtr xyz_transformer_property_;
00247 EditEnumPropertyWPtr color_transformer_property_;
00248 EnumPropertyWPtr style_property_;
00249 FloatPropertyWPtr decay_time_property_;
00250
00251 friend class PointCloudSelectionHandler;
00252 };
00253
00254 }
00255
00256 #endif // RVIZ_POINT_CLOUD_BASE_H