Public Member Functions | Protected Attributes | Private Member Functions | Private Attributes
naoqi::TouchEventRegister< T > Class Template Reference

GlobalRecorder concept interface. More...

#include <touch.hpp>

Inheritance diagram for naoqi::TouchEventRegister< T >:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void isDumping (bool state)
void isPublishing (bool state)
void isRecording (bool state)
void resetPublisher (ros::NodeHandle &nh)
void resetRecorder (boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr)
void setBufferDuration (float duration)
void startProcess ()
void stopProcess ()
void touchCallback (std::string &key, qi::AnyValue &value, qi::AnyValue &message)
void touchCallbackMessage (std::string &key, bool &state, naoqi_bridge_msgs::Bumper &msg)
void touchCallbackMessage (std::string &key, bool &state, naoqi_bridge_msgs::HandTouch &msg)
void touchCallbackMessage (std::string &key, bool &state, naoqi_bridge_msgs::HeadTouch &msg)
 TouchEventRegister ()
 Constructor for recorder interface.
 TouchEventRegister (const std::string &name, const std::vector< std::string > keys, const float &frequency, const qi::SessionPtr &session)
void writeDump (const ros::Time &time)
 ~TouchEventRegister ()

Protected Attributes

std::vector< std::string > keys_

Private Member Functions

void onEvent ()
void registerCallback ()
void unregisterCallback ()

Private Attributes

boost::shared_ptr
< converter::TouchEventConverter
< T > > 
converter_
bool isDumping_
bool isPublishing_
bool isRecording_
bool isStarted_
boost::mutex mutex_
std::string name_
qi::AnyObject p_memory_
boost::shared_ptr
< publisher::BasicPublisher< T > > 
publisher_
unsigned int serviceId
qi::SessionPtr session_

Detailed Description

template<class T>
class naoqi::TouchEventRegister< T >

GlobalRecorder concept interface.

Note:
this defines an private concept struct, which each instance has to implement
a type erasure pattern in implemented here to avoid strict inheritance, thus each possible publisher instance has to implement the virtual functions mentioned in the concept

Definition at line 56 of file event/touch.hpp.


Constructor & Destructor Documentation

template<class T >
naoqi::TouchEventRegister< T >::TouchEventRegister ( )

Constructor for recorder interface.

Definition at line 36 of file event/touch.cpp.

template<class T >
naoqi::TouchEventRegister< T >::TouchEventRegister ( const std::string &  name,
const std::vector< std::string >  keys,
const float &  frequency,
const qi::SessionPtr &  session 
)

Definition at line 41 of file event/touch.cpp.

template<class T >
naoqi::TouchEventRegister< T >::~TouchEventRegister ( )

Definition at line 67 of file event/touch.cpp.


Member Function Documentation

template<class T >
void naoqi::TouchEventRegister< T >::isDumping ( bool  state)

Definition at line 155 of file event/touch.cpp.

template<class T >
void naoqi::TouchEventRegister< T >::isPublishing ( bool  state)

Definition at line 148 of file event/touch.cpp.

template<class T >
void naoqi::TouchEventRegister< T >::isRecording ( bool  state)

Definition at line 141 of file event/touch.cpp.

template<class T>
void naoqi::TouchEventRegister< T >::onEvent ( ) [private]
template<class T >
void naoqi::TouchEventRegister< T >::registerCallback ( ) [private]

Definition at line 162 of file event/touch.cpp.

template<class T >
void naoqi::TouchEventRegister< T >::resetPublisher ( ros::NodeHandle nh)

Definition at line 73 of file event/touch.cpp.

template<class T >
void naoqi::TouchEventRegister< T >::resetRecorder ( boost::shared_ptr< naoqi::recorder::GlobalRecorder gr)

Definition at line 79 of file event/touch.cpp.

template<class T >
void naoqi::TouchEventRegister< T >::setBufferDuration ( float  duration)

Definition at line 135 of file event/touch.cpp.

template<class T >
void naoqi::TouchEventRegister< T >::startProcess ( )

Definition at line 85 of file event/touch.cpp.

template<class T >
void naoqi::TouchEventRegister< T >::stopProcess ( )

Definition at line 106 of file event/touch.cpp.

template<class T >
void naoqi::TouchEventRegister< T >::touchCallback ( std::string &  key,
qi::AnyValue &  value,
qi::AnyValue &  message 
)

Definition at line 172 of file event/touch.cpp.

template<class T >
void naoqi::TouchEventRegister< T >::touchCallbackMessage ( std::string &  key,
bool &  state,
naoqi_bridge_msgs::Bumper &  msg 
)

Definition at line 207 of file event/touch.cpp.

template<class T >
void naoqi::TouchEventRegister< T >::touchCallbackMessage ( std::string &  key,
bool &  state,
naoqi_bridge_msgs::HandTouch &  msg 
)

Definition at line 220 of file event/touch.cpp.

template<class T >
void naoqi::TouchEventRegister< T >::touchCallbackMessage ( std::string &  key,
bool &  state,
naoqi_bridge_msgs::HeadTouch &  msg 
)

Definition at line 233 of file event/touch.cpp.

template<class T >
void naoqi::TouchEventRegister< T >::unregisterCallback ( ) [private]

Definition at line 167 of file event/touch.cpp.

template<class T >
void naoqi::TouchEventRegister< T >::writeDump ( const ros::Time time)

Definition at line 126 of file event/touch.cpp.


Member Data Documentation

template<class T>
boost::shared_ptr<converter::TouchEventConverter<T> > naoqi::TouchEventRegister< T >::converter_ [private]

Definition at line 93 of file event/touch.hpp.

template<class T>
bool naoqi::TouchEventRegister< T >::isDumping_ [private]

Definition at line 107 of file event/touch.hpp.

template<class T>
bool naoqi::TouchEventRegister< T >::isPublishing_ [private]

Definition at line 105 of file event/touch.hpp.

template<class T>
bool naoqi::TouchEventRegister< T >::isRecording_ [private]

Definition at line 106 of file event/touch.hpp.

template<class T>
bool naoqi::TouchEventRegister< T >::isStarted_ [private]

Definition at line 104 of file event/touch.hpp.

template<class T>
std::vector<std::string> naoqi::TouchEventRegister< T >::keys_ [protected]

Definition at line 110 of file event/touch.hpp.

template<class T>
boost::mutex naoqi::TouchEventRegister< T >::mutex_ [private]

Definition at line 102 of file event/touch.hpp.

template<class T>
std::string naoqi::TouchEventRegister< T >::name_ [private]

Definition at line 100 of file event/touch.hpp.

template<class T>
qi::AnyObject naoqi::TouchEventRegister< T >::p_memory_ [private]

Definition at line 98 of file event/touch.hpp.

template<class T>
boost::shared_ptr<publisher::BasicPublisher<T> > naoqi::TouchEventRegister< T >::publisher_ [private]

Definition at line 94 of file event/touch.hpp.

template<class T>
unsigned int naoqi::TouchEventRegister< T >::serviceId [private]

Definition at line 99 of file event/touch.hpp.

template<class T>
qi::SessionPtr naoqi::TouchEventRegister< T >::session_ [private]

Definition at line 97 of file event/touch.hpp.


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


naoqi_driver
Author(s): Karsten Knese
autogenerated on Tue Jul 9 2019 03:21:56