callback.h
Go to the documentation of this file.
1 //==============================================================================
2 // Copyright (c) 2012, Johannes Meyer, TU Darmstadt
3 // All rights reserved.
4 
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 // * Redistributions of source code must retain the above copyright
8 // notice, this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of the Flight Systems and Automatic Control group,
13 // TU Darmstadt, nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without
15 // specific prior written permission.
16 
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //==============================================================================
28 
29 #ifndef UBLOX_GPS_CALLBACK_H
30 #define UBLOX_GPS_CALLBACK_H
31 
32 #include <ros/console.h>
33 #include <ublox/serialization/ublox_msgs.h>
34 #include <boost/format.hpp>
35 #include <boost/function.hpp>
36 #include <boost/thread.hpp>
37 
38 namespace ublox_gps {
39 
44  public:
48  virtual void handle(ublox::Reader& reader) = 0;
49 
53  bool wait(const boost::posix_time::time_duration& timeout) {
54  boost::mutex::scoped_lock lock(mutex_);
55  return condition_.timed_wait(lock, timeout);
56  }
57 
58  protected:
59  boost::mutex mutex_;
60  boost::condition_variable condition_;
61 };
62 
67 template <typename T>
69  public:
70  typedef boost::function<void(const T&)> Callback;
71 
76  CallbackHandler_(const Callback& func = Callback()) : func_(func) {}
77 
81  virtual const T& get() { return message_; }
82 
87  void handle(ublox::Reader& reader) {
88  boost::mutex::scoped_lock lock(mutex_);
89  try {
90  if (!reader.read<T>(message_)) {
91  ROS_DEBUG_COND(debug >= 2,
92  "U-Blox Decoder error for 0x%02x / 0x%02x (%d bytes)",
93  static_cast<unsigned int>(reader.classId()),
94  static_cast<unsigned int>(reader.messageId()),
95  reader.length());
96  condition_.notify_all();
97  return;
98  }
99  } catch (std::runtime_error& e) {
100  ROS_DEBUG_COND(debug >= 2,
101  "U-Blox Decoder error for 0x%02x / 0x%02x (%d bytes)",
102  static_cast<unsigned int>(reader.classId()),
103  static_cast<unsigned int>(reader.messageId()),
104  reader.length());
105  condition_.notify_all();
106  return;
107  }
108 
109  if (func_) func_(message_);
110  condition_.notify_all();
111  }
112 
113  private:
114  Callback func_;
116 };
117 
122  public:
128  template <typename T>
129  void insert(typename CallbackHandler_<T>::Callback callback) {
130  boost::mutex::scoped_lock lock(callback_mutex_);
131  CallbackHandler_<T>* handler = new CallbackHandler_<T>(callback);
132  callbacks_.insert(
133  std::make_pair(std::make_pair(T::CLASS_ID, T::MESSAGE_ID),
135  }
136 
145  template <typename T>
146  void insert(
147  typename CallbackHandler_<T>::Callback callback,
148  unsigned int message_id) {
149  boost::mutex::scoped_lock lock(callback_mutex_);
150  CallbackHandler_<T>* handler = new CallbackHandler_<T>(callback);
151  callbacks_.insert(
152  std::make_pair(std::make_pair(T::CLASS_ID, message_id),
154  }
155 
160  void handle(ublox::Reader& reader) {
161  // Find the callback handlers for the message & decode it
162  boost::mutex::scoped_lock lock(callback_mutex_);
163  Callbacks::key_type key =
164  std::make_pair(reader.classId(), reader.messageId());
165  for (Callbacks::iterator callback = callbacks_.lower_bound(key);
166  callback != callbacks_.upper_bound(key); ++callback)
167  callback->second->handle(reader);
168  }
169 
175  template <typename T>
176  bool read(T& message, const boost::posix_time::time_duration& timeout) {
177  bool result = false;
178  // Create a callback handler for this message
179  callback_mutex_.lock();
180  CallbackHandler_<T>* handler = new CallbackHandler_<T>();
181  Callbacks::iterator callback = callbacks_.insert(
182  (std::make_pair(std::make_pair(T::CLASS_ID, T::MESSAGE_ID),
184  callback_mutex_.unlock();
185 
186  // Wait for the message
187  if (handler->wait(timeout)) {
188  message = handler->get();
189  result = true;
190  }
191 
192  // Remove the callback handler
193  callback_mutex_.lock();
194  callbacks_.erase(callback);
195  callback_mutex_.unlock();
196  return result;
197  }
198 
205  void readCallback(unsigned char* data, std::size_t& size) {
206  ublox::Reader reader(data, size);
207  // Read all U-Blox messages in buffer
208  while (reader.search() != reader.end() && reader.found()) {
209  if (debug >= 3) {
210  // Print the received bytes
211  std::ostringstream oss;
212  for (ublox::Reader::iterator it = reader.pos();
213  it != reader.pos() + reader.length() + 8; ++it)
214  oss << boost::format("%02x") % static_cast<unsigned int>(*it) << " ";
215  ROS_DEBUG("U-blox: reading %d bytes\n%s", reader.length() + 8,
216  oss.str().c_str());
217  }
218 
219  handle(reader);
220  }
221 
222  // delete read bytes from ASIO input buffer
223  std::copy(reader.pos(), reader.end(), data);
224  size -= reader.pos() - data;
225  }
226 
227  private:
228  typedef std::multimap<std::pair<uint8_t, uint8_t>,
230 
231  // Call back handlers for u-blox messages
232  Callbacks callbacks_;
233  boost::mutex callback_mutex_;
234 };
235 
236 } // namespace ublox_gps
237 
238 #endif // UBLOX_GPS_CALLBACK_H
int debug
Used to determine which debug messages to display.
Definition: async_worker.h:45
uint8_t classId()
T message_
The last received message.
Definition: callback.h:115
iterator end()
iterator search()
void handle(ublox::Reader &reader)
Decode the U-Blox message & call the callback function if it exists.
Definition: callback.h:87
uint32_t length()
void insert(typename CallbackHandler_< T >::Callback callback, unsigned int message_id)
Definition: callback.h:146
void handle(ublox::Reader &reader)
Calls the callback handler for the message in the reader.
Definition: callback.h:160
CallbackHandler_(const Callback &func=Callback())
Initialize the Callback Handler with a callback function.
Definition: callback.h:76
virtual void handle(ublox::Reader &reader)=0
Decode the u-blox message.
virtual const T & get()
Get the last received message.
Definition: callback.h:81
void insert(typename CallbackHandler_< T >::Callback callback)
Definition: callback.h:129
Callback handlers for incoming u-blox messages.
Definition: callback.h:121
boost::condition_variable condition_
Condition for the handler lock.
Definition: callback.h:60
boost::mutex mutex_
Lock for the handler.
Definition: callback.h:59
A callback handler for a u-blox message.
Definition: callback.h:43
boost::function< void(const T &)> Callback
A callback function.
Definition: callback.h:70
bool read(T &message, const boost::posix_time::time_duration &timeout)
Read a u-blox message of the given type.
Definition: callback.h:176
void readCallback(unsigned char *data, std::size_t &size)
Processes u-blox messages in the given buffer & clears the read messages from the buffer...
Definition: callback.h:205
Callback func_
the callback function to handle the message
Definition: callback.h:114
boost::mutex callback_mutex_
Definition: callback.h:233
#define ROS_DEBUG_COND(cond,...)
bool wait(const boost::posix_time::time_duration &timeout)
Wait for on the condition.
Definition: callback.h:53
std::multimap< std::pair< uint8_t, uint8_t >, boost::shared_ptr< CallbackHandler > > Callbacks
Definition: callback.h:229
iterator pos()
uint8_t messageId()
const uint8_t * iterator
bool read(typename boost::call_traits< T >::reference message, bool search=false)
#define ROS_DEBUG(...)


ublox_gps
Author(s): Johannes Meyer
autogenerated on Thu Jan 28 2021 03:13:52