Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 #ifndef TOUCH_EVENT_CONVERTER_HPP
00019 #define TOUCH_EVENT_CONVERTER_HPP
00020
00021
00022
00023
00024 #include "converter_base.hpp"
00025 #include <naoqi_driver/message_actions.h>
00026
00027
00028
00029
00030 #include <naoqi_bridge_msgs/Bumper.h>
00031 #include <naoqi_bridge_msgs/HandTouch.h>
00032 #include <naoqi_bridge_msgs/HeadTouch.h>
00033
00034
00035
00036
00037 #include <qi/anymodule.hpp>
00038
00039 namespace naoqi{
00040
00041 namespace converter{
00042
00043 template <class T>
00044 class TouchEventConverter : public BaseConverter<TouchEventConverter<T> >
00045 {
00046
00047 typedef boost::function<void(T&) > Callback_t;
00048
00049 public:
00050 TouchEventConverter(const std::string& name, const float& frequency, const qi::SessionPtr& session);
00051
00052 ~TouchEventConverter();
00053
00054 virtual void reset();
00055
00056 void registerCallback( const message_actions::MessageAction action, Callback_t cb );
00057
00058 void callAll(const std::vector<message_actions::MessageAction>& actions, T& msg);
00059
00060 private:
00062 std::map<message_actions::MessageAction, Callback_t> callbacks_;
00063 T msg_;
00064 };
00065
00066 }
00067
00068 }
00069
00070 #endif // TOUCH_CONVERTER_HPP