Public Member Functions | Public Attributes | Private Attributes
cop::RangeSensor Class Reference

#include <RangeSensor.h>

Inheritance diagram for cop::RangeSensor:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual ReadingApplySelfFilter (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::ReadingGetReading (const long &Frame=-1)
cop::RelPoseGetRelPose ()
virtual std::pair< std::string,
std::vector< double > > 
GetUnformatedCalibrationValues () const
virtual bool IsCamera ()
 RangeSensor ()
virtual cop::XMLTagSave ()
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

Detailed Description

Definition at line 21 of file RangeSensor.h.


Constructor & Destructor Documentation

Definition at line 31 of file RangeSensor.cpp.

Definition at line 42 of file RangeSensor.cpp.


Member Function Documentation

Reading * RangeSensor::ApplySelfFilter ( Reading read) [virtual]

Reimplemented from cop::Sensor.

Definition at line 125 of file RangeSensor.cpp.

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

Parameters:
posepose 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

Parameters:
Frameframe number, to specify an offset or a specific file
Exceptions:
char*with an error message in case of failure

Implements cop::Sensor.

Definition at line 75 of file RangeSensor.cpp.

Returns:
the pose of this sensor

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.


Member Data Documentation

Definition at line 86 of file RangeSensor.h.

std::vector<double> cop::RangeSensor::m_calibration

Definition at line 78 of file RangeSensor.h.

Definition at line 84 of file RangeSensor.h.

Definition at line 85 of file RangeSensor.h.

std::string cop::RangeSensor::m_paramNamespace [private]

Definition at line 89 of file RangeSensor.h.

Definition at line 88 of file RangeSensor.h.

std::string cop::RangeSensor::m_stTopic [private]

Definition at line 83 of file RangeSensor.h.

Definition at line 87 of file RangeSensor.h.


The documentation for this class was generated from the following files:


cop_sr4_plugins
Author(s): U. Klank
autogenerated on Mon Oct 6 2014 10:59:32