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_TRANSFORMER_H
00031 #define RVIZ_POINT_CLOUD_TRANSFORMER_H
00032
00033 #include <string>
00034
00035 #include <ros/message_forward.h>
00036 #include <rviz/properties/forwards.h>
00037
00038 #include <OGRE/OgreVector3.h>
00039 #include <OGRE/OgreColourValue.h>
00040
00041 namespace Ogre
00042 {
00043 class Matrix4;
00044 }
00045
00046 namespace sensor_msgs
00047 {
00048 ROS_DECLARE_MESSAGE(PointCloud2);
00049 }
00050
00051 namespace rviz
00052 {
00053
00054 struct PointCloudPoint
00055 {
00056 Ogre::Vector3 position;
00057 Ogre::ColourValue color;
00058 };
00059 typedef std::vector<PointCloudPoint> V_PointCloudPoint;
00060
00061 struct PointCloud
00062 {
00063 V_PointCloudPoint points;
00064 };
00065
00066 typedef boost::function<void(void)> RetransformFunc;
00067
00068 class PointCloudTransformer
00069 {
00070 public:
00071 void causeRetransform() { if (retransform_func_) retransform_func_(); }
00072
00073 virtual void init(const RetransformFunc& retransform_func) { retransform_func_ = retransform_func; }
00074
00079 enum SupportLevel
00080 {
00081 Support_None = 0,
00082 Support_XYZ = 1 << 1,
00083 Support_Color = 1 << 2,
00084 Support_Both = Support_XYZ|Support_Color,
00085 };
00086
00090 virtual uint8_t supports(const sensor_msgs::PointCloud2ConstPtr& cloud) = 0;
00096 virtual bool transform(const sensor_msgs::PointCloud2ConstPtr& cloud, uint32_t mask, const Ogre::Matrix4& transform, PointCloud& out) = 0;
00097
00103 virtual uint8_t score(const sensor_msgs::PointCloud2ConstPtr& cloud) { return 0; }
00104
00108 virtual void reset() {}
00113 virtual void createProperties(PropertyManager* property_man, const CategoryPropertyWPtr& parent, const std::string& prefix, uint32_t mask, V_PropertyBaseWPtr& out_props) {}
00114
00115 private:
00116 RetransformFunc retransform_func_;
00117 };
00118
00119 }
00120
00121 #endif