Public Member Functions | Static Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes
cop::Sensor Class Reference

Provides an interface for camera usage. More...

#include <Sensor.h>

List of all members.

Public Member Functions

virtual ReadingApplySelfFilter (Reading *read)
virtual bool CanSee (RelPose &pose) const
virtual bool DeleteReading ()
 removes entries of the reading buffer, this function will not release still references functions (
virtual std::string GetName () const
virtual ReadingGetReading (const long &frame=-1)=0
RelPoseGetRelPose ()
std::string GetSensorID () const
virtual void GetShowLock ()
virtual std::pair< std::string,
std::vector< double > > 
GetUnformatedCalibrationValues () const
virtual bool IsCamera () const
virtual void ProjectPoint3DToSensor (const double &x, const double &y, const double &z, double &row, double &column) const
void Publish3DData (const std::vector< double > &x, const std::vector< double > &y, const std::vector< double > &z)
virtual void PushBackAsync ()
virtual void ReleaseShowLock ()
virtual bool RequiresSensorList ()
 Stereo works as a composition of names sensors.
virtual XMLTagSave ()=0
virtual void SaveTo (XMLTag *tag)
 Sensor ()
 Sensor (RelPose *pose)
virtual void SetSensorList (std::vector< Sensor * >)
 Stereo works as a composition of names sensors.
virtual void Show (const long frame=-1)
 should display the sensors currenbt reading, if wanted
virtual bool Start ()=0
 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
virtual void WaitForNewData ()
 Wait the condition variable m_mutexImageList.
virtual ~Sensor ()

Static Public Member Functions

static SensorSensorFactory (XMLTag *tag)
 Load sensor parameter from xml Only derivatives of Camera can use this constructor to initialize values.

Protected Types

typedef boost::mutex::scoped_lock lock

Protected Member Functions

ReadingGetReading_Lock (size_t index)
virtual void PushBack (Reading *img)
virtual void SetData (XMLTag *tag)

Protected Attributes

long m_deletedOffset
long m_FrameCount
std::vector< Reading * > m_images
unsigned long m_max_cameraImages
boost::mutex m_mutexImageList
boost::mutex m_mutexShow
boost::condition m_newDataArrived
RelPosem_relPose
std::string m_stSensorName
std::vector< Reading * > m_temp_images

Detailed Description

Provides an interface for camera usage.

Class Sensor

Definition at line 55 of file Sensor.h.


Member Typedef Documentation

typedef boost::mutex::scoped_lock cop::Sensor::lock [protected]

Definition at line 207 of file Sensor.h.


Constructor & Destructor Documentation

cop::Sensor::Sensor ( ) [inline]

Definition at line 62 of file Sensor.h.

cop::Sensor::Sensor ( RelPose pose) [inline]

Definition at line 71 of file Sensor.h.

Sensor::~Sensor ( ) [virtual]

The destructor is virtual

Definition at line 42 of file Sensor.cpp.


Member Function Documentation

virtual Reading* cop::Sensor::ApplySelfFilter ( Reading read) [inline, virtual]

Definition at line 192 of file Sensor.h.

virtual bool cop::Sensor::CanSee ( RelPose pose) const [inline, virtual]

CanSee Checks if a pose is inside the view of this sensor

Parameters:
posepose that has to be looked at

Definition at line 111 of file Sensor.h.

bool Sensor::DeleteReading ( ) [virtual]

removes entries of the reading buffer, this function will not release still references functions (

DeleteReading

See also:
cop::Reading::Free)

Definition at line 93 of file Sensor.cpp.

virtual std::string cop::Sensor::GetName ( ) const [inline, virtual]

Get Type of the camera by its Name

Definition at line 93 of file Sensor.h.

virtual Reading* cop::Sensor::GetReading ( const long &  frame = -1) [pure virtual]

GetReading

Parameters:
frameframe number, to specify an offset or a specific file
Exceptions:
char*with an error message in case of failure
Reading * Sensor::GetReading_Lock ( size_t  index) [protected]

Definition at line 160 of file Sensor.cpp.

Returns:
the pose of this sensor

Definition at line 129 of file Sensor.h.

std::string cop::Sensor::GetSensorID ( ) const [inline]

GetSensorID This contains optinally an identifier for the sensor (Loaded from)

Definition at line 141 of file Sensor.h.

virtual void cop::Sensor::GetShowLock ( ) [inline, virtual]

GetShowLock()

Definition at line 179 of file Sensor.h.

virtual std::pair<std::string, std::vector<double> > cop::Sensor::GetUnformatedCalibrationValues ( ) const [inline, virtual]

GetUnformatedCalibrationValues

Returns:
a pair of a fomrat string describing the content and a list of doubles

Definition at line 158 of file Sensor.h.

virtual bool cop::Sensor::IsCamera ( ) const [inline, virtual]

Can this Sensor be used like a camera, (incl. Calibration, Showing, usw.)

Definition at line 135 of file Sensor.h.

void Sensor::ProjectPoint3DToSensor ( const double &  x,
const double &  y,
const double &  z,
double &  row,
double &  column 
) const [virtual]

Helper function for projecting 3D data to the images

Definition at line 189 of file Sensor.cpp.

void Sensor::Publish3DData ( const std::vector< double > &  x,
const std::vector< double > &  y,
const std::vector< double > &  z 
)

Helper function for sending 3D display data to rviz

Remarks:
only takes points which are in map and from time now

Definition at line 201 of file Sensor.cpp.

void Sensor::PushBack ( Reading img) [protected, virtual]

Definition at line 227 of file Sensor.cpp.

virtual void cop::Sensor::PushBackAsync ( ) [inline, virtual]

Definition at line 190 of file Sensor.h.

virtual void cop::Sensor::ReleaseShowLock ( ) [inline, virtual]

ReleaseShowLock()

Definition at line 183 of file Sensor.h.

virtual bool cop::Sensor::RequiresSensorList ( ) [inline, virtual]

Stereo works as a composition of names sensors.

m_stSensorName

Definition at line 147 of file Sensor.h.

virtual XMLTag* cop::Sensor::Save ( ) [pure virtual]
void Sensor::SaveTo ( XMLTag tag) [virtual]

Definition at line 154 of file Sensor.cpp.

Sensor * Sensor::SensorFactory ( XMLTag tag) [static]

Load sensor parameter from xml Only derivatives of Camera can use this constructor to initialize values.

Definition at line 53 of file Sensor.cpp.

void Sensor::SetData ( XMLTag tag) [protected, virtual]

Definition at line 131 of file Sensor.cpp.

virtual void cop::Sensor::SetSensorList ( std::vector< Sensor * >  ) [inline, virtual]

Stereo works as a composition of names sensors.

SetSensorList

Definition at line 152 of file Sensor.h.

virtual void cop::Sensor::Show ( const long  frame = -1) [inline, virtual]

should display the sensors currenbt reading, if wanted

Show

Parameters:
framenumber, to specify an temporal offset or a specific file

Definition at line 99 of file Sensor.h.

virtual bool cop::Sensor::Start ( ) [pure virtual]

overwrite to start up the data reading, is called at least once after creation

Start

virtual bool cop::Sensor::Stop ( ) [inline, virtual]

overwrite to stop call this in the destructor if necessary, will be used to shut down cameras

Start

Definition at line 121 of file Sensor.h.

void Sensor::WaitForNewData ( ) [virtual]

Wait the condition variable m_mutexImageList.

Definition at line 84 of file Sensor.cpp.


Member Data Documentation

long cop::Sensor::m_deletedOffset [protected]

Definition at line 203 of file Sensor.h.

long cop::Sensor::m_FrameCount [protected]

Definition at line 202 of file Sensor.h.

std::vector<Reading*> cop::Sensor::m_images [protected]

Definition at line 200 of file Sensor.h.

unsigned long cop::Sensor::m_max_cameraImages [protected]

Definition at line 204 of file Sensor.h.

boost::mutex cop::Sensor::m_mutexImageList [protected]

Definition at line 208 of file Sensor.h.

boost::mutex cop::Sensor::m_mutexShow [protected]

Definition at line 209 of file Sensor.h.

boost::condition cop::Sensor::m_newDataArrived [protected]

Definition at line 210 of file Sensor.h.

Definition at line 199 of file Sensor.h.

std::string cop::Sensor::m_stSensorName [protected]

Definition at line 205 of file Sensor.h.

std::vector<Reading*> cop::Sensor::m_temp_images [protected]

Definition at line 201 of file Sensor.h.


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


cognitive_perception
Author(s): Ulrich F Klank
autogenerated on Mon Oct 6 2014 10:48:46