Specialisation of AttentionAlgorithm that waits for external events. More...
#include <RemoteAttention.h>
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 XMLTag * | Save () |
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 |
Specialisation of AttentionAlgorithm that waits for external events.
class RemoteAttention
Definition at line 20 of file RemoteAttention.h.
typedef boost::mutex::scoped_lock cop::RemoteAttention< Message >::lock |
Definition at line 32 of file RemoteAttention.h.
cop::RemoteAttention< Message >::RemoteAttention | ( | ) | [inline] |
Constructor
Definition at line 27 of file RemoteAttention.h.
virtual cop::RemoteAttention< Message >::~RemoteAttention | ( | ) | [inline, virtual] |
Destructor
Definition at line 32 of file RemoteAttention.h.
void cop::RemoteAttention< Message >::CallbackToTopic | ( | boost::shared_ptr< Message const > | msg | ) | [inline] |
Definition at line 141 of file RemoteAttention.h.
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.
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.
virtual std::vector<Signature*> cop::RemoteAttention< Message >::MessageToSignature | ( | boost::shared_ptr< Message const > | msg | ) | [inline, virtual] |
Definition at line 150 of file RemoteAttention.h.
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
sensors | empty |
pose | Position that can restict the search |
prototype | Description of the object to search for |
numOfObjects | number of objects that should be found and on return that were found |
qualityMeasure | Takes threshold limiting results quality and receives resulting quality |
Implements cop::AttentionAlgorithm.
Definition at line 46 of file RemoteAttention.h.
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.
void cop::RemoteAttention< Message >::SaveRemoteProps | ( | XMLTag * | tag | ) | [inline] |
Definition at line 112 of file RemoteAttention.h.
virtual void cop::RemoteAttention< Message >::SetData | ( | XMLTag * | tag | ) | [inline, virtual] |
Reimplemented from cop::AttentionAlgorithm.
Definition at line 136 of file RemoteAttention.h.
void cop::RemoteAttention< Message >::SetObjectType | ( | ElemType_t | neededObjectType | ) | [inline] |
Definition at line 155 of file RemoteAttention.h.
void cop::RemoteAttention< Message >::Start | ( | ) | [inline] |
Definition at line 114 of file RemoteAttention.h.
virtual void cop::RemoteAttention< Message >::Stop | ( | ) | [inline, virtual] |
Definition at line 131 of file RemoteAttention.h.
bool cop::RemoteAttention< Message >::m_bNew |
Definition at line 160 of file RemoteAttention.h.
bool cop::RemoteAttention< Message >::m_bStarted |
Definition at line 159 of file RemoteAttention.h.
std::vector<Signature*> cop::RemoteAttention< Message >::m_latestResult |
Definition at line 158 of file RemoteAttention.h.
boost::mutex cop::RemoteAttention< Message >::m_mutexNewData |
Definition at line 163 of file RemoteAttention.h.
ElemType_t cop::RemoteAttention< Message >::m_neededObjectType |
Definition at line 164 of file RemoteAttention.h.
boost::condition cop::RemoteAttention< Message >::m_newDataArrived |
Definition at line 162 of file RemoteAttention.h.
std::string cop::RemoteAttention< Message >::m_stTopic |
Definition at line 157 of file RemoteAttention.h.
ros::Subscriber cop::RemoteAttention< Message >::m_subs |
Definition at line 161 of file RemoteAttention.h.