21 #include <boost/make_shared.hpp> 25 #include <qi/anyobject.hpp> 43 p_memory_( session->service(
"ALMemory")),
50 publisher_ = boost::make_shared<publisher::BasicPublisher<T> >( name );
52 converter_ = boost::make_shared<converter::TouchEventConverter<T> >( name, frequency, session );
58 keys_.resize(keys.size());
60 for(std::vector<std::string>::const_iterator it = keys.begin(); it != keys.end(); ++it, ++i)
87 boost::mutex::scoped_lock start_lock(
mutex_);
93 std::string serviceName = std::string(
"ROS-Driver-") +
keys_[0];
95 for(std::vector<std::string>::const_iterator it =
keys_.begin(); it !=
keys_.end(); ++it) {
96 std::cerr << *it << std::endl;
97 p_memory_.call<
void>(
"subscribeToEvent",it->c_str(), serviceName,
"touchCallback");
99 std::cout << serviceName <<
" : Start" << std::endl;
108 boost::mutex::scoped_lock stop_lock(
mutex_);
112 std::string serviceName = std::string(
"ROS-Driver-") +
keys_[0];
114 for(std::vector<std::string>::const_iterator it =
keys_.begin(); it !=
keys_.end(); ++it) {
115 p_memory_.call<
void>(
"unsubscribeToEvent",it->c_str(), serviceName);
120 std::cout << serviceName <<
" : Stop" << std::endl;
143 boost::mutex::scoped_lock rec_lock(
mutex_);
150 boost::mutex::scoped_lock pub_lock(
mutex_);
157 boost::mutex::scoped_lock dump_lock(
mutex_);
176 bool state = value.toFloat() > 0.5f;
182 std::vector<message_actions::MessageAction> actions;
183 boost::mutex::scoped_lock callback_lock(
mutex_);
199 if (actions.size() >0)
210 for(std::vector<std::string>::const_iterator it =
keys_.begin(); it !=
keys_.end(); ++it, ++i)
212 if ( key == it->c_str() ) {
214 msg.state = state?(naoqi_bridge_msgs::Bumper::statePressed):(naoqi_bridge_msgs::Bumper::stateReleased);
223 for(std::vector<std::string>::const_iterator it =
keys_.begin(); it !=
keys_.end(); ++it, ++i)
225 if ( key == it->c_str() ) {
227 msg.state = state?(naoqi_bridge_msgs::HandTouch::statePressed):(naoqi_bridge_msgs::HandTouch::stateReleased);
236 for(std::vector<std::string>::const_iterator it =
keys_.begin(); it !=
keys_.end(); ++it, ++i)
238 if ( key == it->c_str() ) {
240 msg.state = state?(naoqi_bridge_msgs::HeadTouch::statePressed):(naoqi_bridge_msgs::HeadTouch::stateReleased);
void isDumping(bool state)
void isRecording(bool state)
void isPublishing(bool state)
TouchEventRegister()
Constructor for recorder interface.
void unregisterCallback()
void resetPublisher(ros::NodeHandle &nh)
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)
boost::shared_ptr< publisher::BasicPublisher< T > > publisher_
void resetRecorder(boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr)
std::vector< std::string > keys_
void setBufferDuration(float duration)
void writeDump(const ros::Time &time)