00001 #ifndef RANGESENSOR_H 00002 #define RANGESENSOR_H 00003 #include "pluginlib/class_list_macros.h" 00004 00005 #include "Sensor.h" 00006 #include "XMLTag.h" 00007 00008 #include <sensor_msgs/PointCloud.h> 00009 #include <sensor_msgs/PointCloud2.h> 00010 00011 #include "SwissRangerReading.h" 00012 00013 #define XML_NODE_RANGESENSOR "RangeSensor" 00014 00015 00016 #include <robot_self_filter/self_see_filter.h> 00017 00018 00019 namespace cop 00020 { 00021 class RangeSensor : public cop::Sensor 00022 { 00023 public: 00024 RangeSensor(); 00025 ~RangeSensor(); 00026 00030 virtual void SetData(cop::XMLTag* tag); 00034 virtual std::string GetName() const{return XML_NODE_RANGESENSOR;}; 00035 00041 virtual cop::Reading* GetReading(const long &Frame = -1); 00042 00048 virtual bool CanSee(cop::RelPose &pose) const; 00049 00050 void CallBack(const sensor_msgs::PointCloudConstPtr& cloud); 00051 00052 void CallBackPCL2(const sensor_msgs::PointCloud2ConstPtr& cloud2); 00053 00054 virtual std::pair<std::string, std::vector<double> > GetUnformatedCalibrationValues() const; 00055 00056 00061 virtual bool Start(); 00066 virtual bool Stop(); 00070 cop::RelPose* GetRelPose(){return m_relPose;} 00071 00072 virtual cop::XMLTag* Save(); 00076 virtual bool IsCamera(){return false;} 00077 00078 std::vector<double> m_calibration; 00079 00080 00081 virtual Reading* ApplySelfFilter(Reading* read); 00082 private: 00083 std::string m_stTopic; 00084 ros::Subscriber m_cloudSub; 00085 bool m_grabbing; 00086 bool m_bintegration; 00087 bool m_subscribePointCloud2; 00088 filters::SelfFilter<pcl::PointCloud < pcl::PointXYZ> > *m_self_filter; 00089 std::string m_paramNamespace; 00090 }; 00091 } 00092 #endif