event/touch.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2015 Aldebaran
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 #include <iostream>
19 #include <vector>
20 
21 #include <boost/make_shared.hpp>
22 
23 #include <ros/ros.h>
24 
25 #include <qi/anyobject.hpp>
26 
29 
30 #include "touch.hpp"
31 
32 namespace naoqi
33 {
34 
35 template<class T>
37 {
38 }
39 
40 template<class T>
41 TouchEventRegister<T>::TouchEventRegister( const std::string& name, const std::vector<std::string> keys, const float& frequency, const qi::SessionPtr& session )
42  : serviceId(0),
43  p_memory_( session->service("ALMemory")),
44  session_(session),
45  isStarted_(false),
46  isPublishing_(false),
47  isRecording_(false),
48  isDumping_(false)
49 {
50  publisher_ = boost::make_shared<publisher::BasicPublisher<T> >( name );
51  //recorder_ = boost::make_shared<recorder::BasicEventRecorder<T> >( name );
52  converter_ = boost::make_shared<converter::TouchEventConverter<T> >( name, frequency, session );
53 
54  converter_->registerCallback( message_actions::PUBLISH, boost::bind(&publisher::BasicPublisher<T>::publish, publisher_, _1) );
55  //converter_->registerCallback( message_actions::RECORD, boost::bind(&recorder::BasicEventRecorder<T>::write, recorder_, _1) );
56  //converter_->registerCallback( message_actions::LOG, boost::bind(&recorder::BasicEventRecorder<T>::bufferize, recorder_, _1) );
57 
58  keys_.resize(keys.size());
59  size_t i = 0;
60  for(std::vector<std::string>::const_iterator it = keys.begin(); it != keys.end(); ++it, ++i)
61  keys_[i] = *it;
62 
63  name_ = name;
64 }
65 
66 template<class T>
68 {
69  stopProcess();
70 }
71 
72 template<class T>
74 {
75  publisher_->reset(nh);
76 }
77 
78 template<class T>
80 {
81  //recorder_->reset(gr, converter_->frequency());
82 }
83 
84 template<class T>
86 {
87  boost::mutex::scoped_lock start_lock(mutex_);
88  if (!isStarted_)
89  {
90  if(!serviceId)
91  {
92  //std::string serviceName = std::string("ROS-Driver-") + typeid(T).name();
93  std::string serviceName = std::string("ROS-Driver-") + keys_[0];
94  serviceId = session_->registerService(serviceName, this->shared_from_this());
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");
98  }
99  std::cout << serviceName << " : Start" << std::endl;
100  }
101  isStarted_ = true;
102  }
103 }
104 
105 template<class T>
107 {
108  boost::mutex::scoped_lock stop_lock(mutex_);
109  if (isStarted_)
110  {
111  //std::string serviceName = std::string("ROS-Driver-") + typeid(T).name();
112  std::string serviceName = std::string("ROS-Driver-") + keys_[0];
113  if(serviceId){
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);
116  }
117  session_->unregisterService(serviceId);
118  serviceId = 0;
119  }
120  std::cout << serviceName << " : Stop" << std::endl;
121  isStarted_ = false;
122  }
123 }
124 
125 template<class T>
127 {
128  if (isStarted_)
129  {
130  //recorder_->writeDump(time);
131  }
132 }
133 
134 template<class T>
136 {
137  //recorder_->setBufferDuration(duration);
138 }
139 
140 template<class T>
142 {
143  boost::mutex::scoped_lock rec_lock(mutex_);
144  isRecording_ = state;
145 }
146 
147 template<class T>
149 {
150  boost::mutex::scoped_lock pub_lock(mutex_);
151  isPublishing_ = state;
152 }
153 
154 template<class T>
156 {
157  boost::mutex::scoped_lock dump_lock(mutex_);
158  isDumping_ = state;
159 }
160 
161 template<class T>
163 {
164 }
165 
166 template<class T>
168 {
169 }
170 
171 template<class T>
172 void TouchEventRegister<T>::touchCallback(std::string &key, qi::AnyValue &value, qi::AnyValue &message)
173 {
174  T msg = T();
175 
176  bool state = value.toFloat() > 0.5f;
177 
178  //std::cerr << key << " " << state << std::endl;
179 
180  touchCallbackMessage(key, state, msg);
181 
182  std::vector<message_actions::MessageAction> actions;
183  boost::mutex::scoped_lock callback_lock(mutex_);
184  if (isStarted_) {
185  // CHECK FOR PUBLISH
186  if ( isPublishing_ && publisher_->isSubscribed() )
187  {
188  actions.push_back(message_actions::PUBLISH);
189  }
190  // CHECK FOR RECORD
191  if ( isRecording_ )
192  {
193  //actions.push_back(message_actions::RECORD);
194  }
195  if ( !isDumping_ )
196  {
197  //actions.push_back(message_actions::LOG);
198  }
199  if (actions.size() >0)
200  {
201  converter_->callAll( actions, msg );
202  }
203  }
204 }
205 
206 template<class T>
207 void TouchEventRegister<T>::touchCallbackMessage(std::string &key, bool &state, naoqi_bridge_msgs::Bumper &msg)
208 {
209  int i = 0;
210  for(std::vector<std::string>::const_iterator it = keys_.begin(); it != keys_.end(); ++it, ++i)
211  {
212  if ( key == it->c_str() ) {
213  msg.bumper = i;
214  msg.state = state?(naoqi_bridge_msgs::Bumper::statePressed):(naoqi_bridge_msgs::Bumper::stateReleased);
215  }
216  }
217 }
218 
219 template<class T>
220 void TouchEventRegister<T>::touchCallbackMessage(std::string &key, bool &state, naoqi_bridge_msgs::HandTouch &msg)
221 {
222  int i = 0;
223  for(std::vector<std::string>::const_iterator it = keys_.begin(); it != keys_.end(); ++it, ++i)
224  {
225  if ( key == it->c_str() ) {
226  msg.hand = i;
227  msg.state = state?(naoqi_bridge_msgs::HandTouch::statePressed):(naoqi_bridge_msgs::HandTouch::stateReleased);
228  }
229  }
230 }
231 
232 template<class T>
233 void TouchEventRegister<T>::touchCallbackMessage(std::string &key, bool &state, naoqi_bridge_msgs::HeadTouch &msg)
234 {
235  int i = 0;
236  for(std::vector<std::string>::const_iterator it = keys_.begin(); it != keys_.end(); ++it, ++i)
237  {
238  if ( key == it->c_str() ) {
239  msg.button = i;
240  msg.state = state?(naoqi_bridge_msgs::HeadTouch::statePressed):(naoqi_bridge_msgs::HeadTouch::stateReleased);
241  }
242  }
243 }
244 
245 // http://stackoverflow.com/questions/8752837/undefined-reference-to-template-class-constructor
249 
250 }//namespace
msg
void isDumping(bool state)
void isRecording(bool state)
void isPublishing(bool state)
TouchEventRegister()
Constructor for recorder interface.
Definition: event/touch.cpp:36
void resetPublisher(ros::NodeHandle &nh)
Definition: event/touch.cpp:73
void touchCallbackMessage(std::string &key, bool &state, naoqi_bridge_msgs::Bumper &msg)
boost::shared_ptr< converter::TouchEventConverter< T > > converter_
Definition: event/touch.hpp:93
void touchCallback(std::string &key, qi::AnyValue &value, qi::AnyValue &message)
boost::shared_ptr< publisher::BasicPublisher< T > > publisher_
Definition: event/touch.hpp:94
void resetRecorder(boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr)
Definition: event/touch.cpp:79
std::vector< std::string > keys_
void setBufferDuration(float duration)
void writeDump(const ros::Time &time)


naoqi_driver
Author(s): Karsten Knese
autogenerated on Sat Feb 15 2020 03:24:26