All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines
Public Types | Public Member Functions | Public Attributes
cop::RemoteAttention< Message > Class Template Reference

Specialisation of AttentionAlgorithm that waits for external events. More...

#include <RemoteAttention.h>

Inheritance diagram for cop::RemoteAttention< Message >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef boost::mutex::scoped_lock lock

Public Member Functions

void CallbackToTopic (boost::shared_ptr< Message const > msg)
virtual double CheckSignature (const Signature &object, const std::vector< Sensor * > &sensors)
template<>
std::vector< Signature * > MessageToSignature (boost::shared_ptr< std_msgs::UInt64 const > msg)
virtual std::vector< Signature * > MessageToSignature (boost::shared_ptr< Message const > msg)
virtual std::vector< Signature * > Perform (std::vector< Sensor * > sensors, RelPose *pose, Signature &prototype, int &numOfObjects, double &qualityMeasure)
 the function that is called to execute this current algorithm
 RemoteAttention ()
virtual XMLTagSave ()
 saves the algorithms name and a parameter set
void SaveRemoteProps (XMLTag *tag)
virtual void SetData (XMLTag *tag)
void SetObjectType (ElemType_t neededObjectType)
void Start ()
virtual void Stop ()
virtual ~RemoteAttention ()

Public Attributes

bool m_bNew
bool m_bStarted
std::vector< Signature * > m_latestResult
boost::mutex m_mutexNewData
ElemType_t m_neededObjectType
boost::condition m_newDataArrived
std::string m_stTopic
ros::Subscriber m_subs

Detailed Description

template<typename Message>
class cop::RemoteAttention< Message >

Specialisation of AttentionAlgorithm that waits for external events.

class RemoteAttention

Definition at line 20 of file RemoteAttention.h.


Member Typedef Documentation

template<typename Message >
typedef boost::mutex::scoped_lock cop::RemoteAttention< Message >::lock

Definition at line 32 of file RemoteAttention.h.


Constructor & Destructor Documentation

template<typename Message >
cop::RemoteAttention< Message >::RemoteAttention ( ) [inline]

Constructor

Definition at line 27 of file RemoteAttention.h.

template<typename Message >
virtual cop::RemoteAttention< Message >::~RemoteAttention ( ) [inline, virtual]

Destructor

Definition at line 32 of file RemoteAttention.h.


Member Function Documentation

template<typename Message >
void cop::RemoteAttention< Message >::CallbackToTopic ( boost::shared_ptr< Message const >  msg) [inline]

Definition at line 141 of file RemoteAttention.h.

template<typename Message >
virtual double cop::RemoteAttention< Message >::CheckSignature ( const Signature object,
const std::vector< Sensor * > &  sensors 
) [inline, virtual]

CheckSignatures local check for preconditions

Reimplemented from cop::AttentionAlgorithm.

Definition at line 88 of file RemoteAttention.h.

template<>
std::vector< Signature * > cop::RemoteAttention< std_msgs::UInt64 >::MessageToSignature ( boost::shared_ptr< std_msgs::UInt64 const >  msg)

Definition at line 64 of file AttentionAlgorithm.cpp.

template<typename Message >
virtual std::vector<Signature*> cop::RemoteAttention< Message >::MessageToSignature ( boost::shared_ptr< Message const >  msg) [inline, virtual]

Definition at line 150 of file RemoteAttention.h.

template<typename Message >
virtual std::vector<Signature*> cop::RemoteAttention< Message >::Perform ( std::vector< Sensor * >  sensors,
RelPose pose,
Signature prototype,
int &  numOfObjects,
double &  qualityMeasure 
) [inline, virtual]

the function that is called to execute this current algorithm

Perform

Parameters:
sensorsempty
posePosition that can restict the search
prototypeDescription of the object to search for
numOfObjectsnumber of objects that should be found and on return that were found
qualityMeasureTakes threshold limiting results quality and receives resulting quality
Returns:
a list of objects which should be attended

Implements cop::AttentionAlgorithm.

Definition at line 46 of file RemoteAttention.h.

template<typename Message >
virtual XMLTag* cop::RemoteAttention< Message >::Save ( ) [inline, virtual]

saves the algorithms name and a parameter set

Save

Implements cop::AttentionAlgorithm.

Definition at line 105 of file RemoteAttention.h.

template<typename Message >
void cop::RemoteAttention< Message >::SaveRemoteProps ( XMLTag tag) [inline]

Definition at line 112 of file RemoteAttention.h.

template<typename Message >
virtual void cop::RemoteAttention< Message >::SetData ( XMLTag tag) [inline, virtual]

Reimplemented from cop::AttentionAlgorithm.

Definition at line 136 of file RemoteAttention.h.

template<typename Message >
void cop::RemoteAttention< Message >::SetObjectType ( ElemType_t  neededObjectType) [inline]

Definition at line 155 of file RemoteAttention.h.

template<typename Message >
void cop::RemoteAttention< Message >::Start ( ) [inline]

Definition at line 114 of file RemoteAttention.h.

template<typename Message >
virtual void cop::RemoteAttention< Message >::Stop ( ) [inline, virtual]

Definition at line 131 of file RemoteAttention.h.


Member Data Documentation

template<typename Message >
bool cop::RemoteAttention< Message >::m_bNew

Definition at line 160 of file RemoteAttention.h.

template<typename Message >
bool cop::RemoteAttention< Message >::m_bStarted

Definition at line 159 of file RemoteAttention.h.

template<typename Message >
std::vector<Signature*> cop::RemoteAttention< Message >::m_latestResult

Definition at line 158 of file RemoteAttention.h.

template<typename Message >
boost::mutex cop::RemoteAttention< Message >::m_mutexNewData

Definition at line 163 of file RemoteAttention.h.

template<typename Message >
ElemType_t cop::RemoteAttention< Message >::m_neededObjectType

Definition at line 164 of file RemoteAttention.h.

template<typename Message >
boost::condition cop::RemoteAttention< Message >::m_newDataArrived

Definition at line 162 of file RemoteAttention.h.

template<typename Message >
std::string cop::RemoteAttention< Message >::m_stTopic

Definition at line 157 of file RemoteAttention.h.

template<typename Message >
ros::Subscriber cop::RemoteAttention< Message >::m_subs

Definition at line 161 of file RemoteAttention.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


cognitive_perception
Author(s): Ulrich F Klank
autogenerated on Thu May 23 2013 07:38:35