18 #ifndef TOUCH_EVENT_REGISTER_HPP 19 #define TOUCH_EVENT_REGISTER_HPP 23 #include <boost/make_shared.hpp> 24 #include <boost/shared_ptr.hpp> 25 #include <boost/thread/mutex.hpp> 26 #include <boost/enable_shared_from_this.hpp> 28 #include <qi/session.hpp> 31 #include <naoqi_bridge_msgs/Bumper.h> 32 #include <naoqi_bridge_msgs/HandTouch.h> 33 #include <naoqi_bridge_msgs/HeadTouch.h> 39 #include "../src/converters/touch.hpp" 41 #include "../src/publishers/basic.hpp" 43 #include "../recorder/basic_event.hpp" 65 TouchEventRegister(
const std::string& name,
const std::vector<std::string> keys,
const float& frequency,
const qi::SessionPtr& session );
81 void touchCallback(std::string &key, qi::AnyValue &value, qi::AnyValue &message);
117 BumperEventRegister(
const std::string& name,
const std::vector<std::string> keys,
const float& frequency,
const qi::SessionPtr& session ) :
TouchEventRegister<naoqi_bridge_msgs::Bumper>(name, keys, frequency, session) {}
123 HeadTouchEventRegister(
const std::string& name,
const std::vector<std::string> keys,
const float& frequency,
const qi::SessionPtr& session ) :
TouchEventRegister<naoqi_bridge_msgs::HeadTouch>(name, keys, frequency, session) {}
129 HandTouchEventRegister(
const std::string& name,
const std::vector<std::string> keys,
const float& frequency,
const qi::SessionPtr& session ) :
TouchEventRegister<naoqi_bridge_msgs::HandTouch>(name, keys, frequency, session) {}
136 ::qi::ObjectTypeBuilder<TouchEventRegister<naoqi_bridge_msgs::Bumper> > b;
144 ::qi::ObjectTypeBuilder<TouchEventRegister<naoqi_bridge_msgs::HandTouch> > b;
152 ::qi::ObjectTypeBuilder<TouchEventRegister<naoqi_bridge_msgs::HeadTouch> > b;
void isDumping(bool state)
void isRecording(bool state)
void isPublishing(bool state)
TouchEventRegister()
Constructor for recorder interface.
HandTouchEventRegister(const std::string &name, const std::vector< std::string > keys, const float &frequency, const qi::SessionPtr &session)
HeadTouchEventRegister(const std::string &name, const std::vector< std::string > keys, const float &frequency, const qi::SessionPtr &session)
void unregisterCallback()
void resetPublisher(ros::NodeHandle &nh)
GlobalRecorder concept interface.
static bool _qiregisterTouchEventRegisterBumper()
BumperEventRegister(const std::string &name, const std::vector< std::string > keys, const float &frequency, const qi::SessionPtr &session)
void touchCallbackMessage(std::string &key, bool &state, naoqi_bridge_msgs::Bumper &msg)
boost::shared_ptr< converter::TouchEventConverter< T > > converter_
void touchCallback(std::string &key, qi::AnyValue &value, qi::AnyValue &message)
static bool BOOST_PP_CAT(__qi_registration, __LINE__)
boost::shared_ptr< publisher::BasicPublisher< T > > publisher_
void resetRecorder(boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr)
std::vector< std::string > keys_
static bool _qiregisterTouchEventRegisterHeadTouch()
static bool _qiregisterTouchEventRegisterHandTouch()
void setBufferDuration(float duration)
void writeDump(const ros::Time &time)