#include <RangeSensor.h>

| Public Member Functions | |
| virtual Reading * | ApplySelfFilter (Reading *read) | 
| void | CallBack (const sensor_msgs::PointCloudConstPtr &cloud) | 
| void | CallBackPCL2 (const sensor_msgs::PointCloud2ConstPtr &cloud2) | 
| virtual bool | CanSee (cop::RelPose &pose) const | 
| virtual std::string | GetName () const | 
| virtual cop::Reading * | GetReading (const long &Frame=-1) | 
| cop::RelPose * | GetRelPose () | 
| virtual std::pair< std::string, std::vector< double > > | GetUnformatedCalibrationValues () const | 
| virtual bool | IsCamera () | 
| RangeSensor () | |
| virtual cop::XMLTag * | Save () | 
| virtual void | SetData (cop::XMLTag *tag) | 
| virtual bool | Start () | 
| overwrite to start up the data reading, is called at least once after creation | |
| virtual bool | Stop () | 
| overwrite to stop call this in the destructor if necessary, will be used to shut down cameras | |
| ~RangeSensor () | |
| Public Attributes | |
| std::vector< double > | m_calibration | 
| Private Attributes | |
| bool | m_bintegration | 
| ros::Subscriber | m_cloudSub | 
| bool | m_grabbing | 
| std::string | m_paramNamespace | 
| filters::SelfFilter < pcl::PointCloud < pcl::PointXYZ > > * | m_self_filter | 
| std::string | m_stTopic | 
| bool | m_subscribePointCloud2 | 
Definition at line 21 of file RangeSensor.h.
Definition at line 31 of file RangeSensor.cpp.
Definition at line 42 of file RangeSensor.cpp.
| Reading * RangeSensor::ApplySelfFilter | ( | Reading * | read | ) |  [virtual] | 
Reimplemented from cop::Sensor.
Definition at line 125 of file RangeSensor.cpp.
| void RangeSensor::CallBack | ( | const sensor_msgs::PointCloudConstPtr & | cloud | ) | 
Definition at line 157 of file RangeSensor.cpp.
| void RangeSensor::CallBackPCL2 | ( | const sensor_msgs::PointCloud2ConstPtr & | cloud2 | ) | 
Definition at line 190 of file RangeSensor.cpp.
| bool RangeSensor::CanSee | ( | cop::RelPose & | pose | ) | const  [virtual] | 
CanSee Checks if a pose is inside the view of this sensor
| pose | pose that has to be looked at | 
Reimplemented from cop::Sensor.
Definition at line 102 of file RangeSensor.cpp.
| virtual std::string cop::RangeSensor::GetName | ( | ) | const  [inline, virtual] | 
Get Type of the camera by its Name
Reimplemented from cop::Sensor.
Reimplemented in SwissRangerRemoteSensor.
Definition at line 34 of file RangeSensor.h.
| cop::Reading * RangeSensor::GetReading | ( | const long & | Frame = -1 | ) |  [virtual] | 
GetReading
| Frame | frame number, to specify an offset or a specific file | 
| char* | with an error message in case of failure | 
Implements cop::Sensor.
Definition at line 75 of file RangeSensor.cpp.
| cop::RelPose* cop::RangeSensor::GetRelPose | ( | ) |  [inline] | 
Reimplemented from cop::Sensor.
Definition at line 70 of file RangeSensor.h.
| std::pair< std::string, std::vector< double > > RangeSensor::GetUnformatedCalibrationValues | ( | ) | const  [virtual] | 
Reimplemented from cop::Sensor.
Definition at line 229 of file RangeSensor.cpp.
| virtual bool cop::RangeSensor::IsCamera | ( | ) |  [inline, virtual] | 
Can this Sensor be used like a camera, (incl. Calibration, Showing, usw.)
Definition at line 76 of file RangeSensor.h.
| cop::XMLTag * RangeSensor::Save | ( | ) |  [virtual] | 
Implements cop::Sensor.
Definition at line 266 of file RangeSensor.cpp.
| void RangeSensor::SetData | ( | cop::XMLTag * | tag | ) |  [virtual] | 
This can be overwritten to get the data necessary to reconstruct a saved reading
Reimplemented from cop::Sensor.
Definition at line 52 of file RangeSensor.cpp.
| bool RangeSensor::Start | ( | ) |  [virtual] | 
overwrite to start up the data reading, is called at least once after creation
Start
Implements cop::Sensor.
Definition at line 239 of file RangeSensor.cpp.
| bool RangeSensor::Stop | ( | ) |  [virtual] | 
overwrite to stop call this in the destructor if necessary, will be used to shut down cameras
Start
Reimplemented from cop::Sensor.
Definition at line 258 of file RangeSensor.cpp.
| bool cop::RangeSensor::m_bintegration  [private] | 
Definition at line 86 of file RangeSensor.h.
Definition at line 78 of file RangeSensor.h.
| ros::Subscriber cop::RangeSensor::m_cloudSub  [private] | 
Definition at line 84 of file RangeSensor.h.
| bool cop::RangeSensor::m_grabbing  [private] | 
Definition at line 85 of file RangeSensor.h.
| std::string cop::RangeSensor::m_paramNamespace  [private] | 
Definition at line 89 of file RangeSensor.h.
| filters::SelfFilter<pcl::PointCloud < pcl::PointXYZ> >* cop::RangeSensor::m_self_filter  [private] | 
Definition at line 88 of file RangeSensor.h.
| std::string cop::RangeSensor::m_stTopic  [private] | 
Definition at line 83 of file RangeSensor.h.
| bool cop::RangeSensor::m_subscribePointCloud2  [private] | 
Definition at line 87 of file RangeSensor.h.