29 #ifndef UBLOX_GPS_CALLBACK_H 30 #define UBLOX_GPS_CALLBACK_H 33 #include <ublox/serialization/ublox_msgs.h> 34 #include <boost/format.hpp> 35 #include <boost/function.hpp> 36 #include <boost/thread.hpp> 53 bool wait(
const boost::posix_time::time_duration& timeout) {
54 boost::mutex::scoped_lock lock(
mutex_);
70 typedef boost::function<void(const T&)>
Callback;
81 virtual const T&
get() {
return message_; }
88 boost::mutex::scoped_lock lock(
mutex_);
90 if (!reader.
read<T>(message_)) {
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()),
99 }
catch (std::runtime_error& e) {
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()),
109 if (func_) func_(message_);
128 template <
typename T>
130 boost::mutex::scoped_lock lock(callback_mutex_);
133 std::make_pair(std::make_pair(T::CLASS_ID, T::MESSAGE_ID),
145 template <
typename T>
148 unsigned int message_id) {
149 boost::mutex::scoped_lock lock(callback_mutex_);
152 std::make_pair(std::make_pair(T::CLASS_ID, message_id),
162 boost::mutex::scoped_lock lock(callback_mutex_);
163 Callbacks::key_type key =
165 for (Callbacks::iterator callback = callbacks_.lower_bound(key);
166 callback != callbacks_.upper_bound(key); ++callback)
167 callback->second->handle(reader);
175 template <
typename T>
176 bool read(T& message,
const boost::posix_time::time_duration& timeout) {
179 callback_mutex_.lock();
181 Callbacks::iterator callback = callbacks_.insert(
182 (std::make_pair(std::make_pair(T::CLASS_ID, T::MESSAGE_ID),
184 callback_mutex_.unlock();
187 if (handler->
wait(timeout)) {
188 message = handler->
get();
193 callback_mutex_.lock();
194 callbacks_.erase(callback);
195 callback_mutex_.unlock();
211 std::ostringstream oss;
213 it != reader.
pos() + reader.
length() + 8; ++it)
214 oss << boost::format(
"%02x") %
static_cast<unsigned int>(*it) <<
" ";
223 std::copy(reader.
pos(), reader.
end(), data);
224 size -= reader.
pos() - data;
228 typedef std::multimap<std::pair<uint8_t, uint8_t>,
238 #endif // UBLOX_GPS_CALLBACK_H int debug
Used to determine which debug messages to display.
T message_
The last received message.
void handle(ublox::Reader &reader)
Decode the U-Blox message & call the callback function if it exists.
void insert(typename CallbackHandler_< T >::Callback callback, unsigned int message_id)
void handle(ublox::Reader &reader)
Calls the callback handler for the message in the reader.
CallbackHandler_(const Callback &func=Callback())
Initialize the Callback Handler with a callback function.
virtual void handle(ublox::Reader &reader)=0
Decode the u-blox message.
virtual const T & get()
Get the last received message.
void insert(typename CallbackHandler_< T >::Callback callback)
Callback handlers for incoming u-blox messages.
boost::condition_variable condition_
Condition for the handler lock.
boost::mutex mutex_
Lock for the handler.
A callback handler for a u-blox message.
boost::function< void(const T &)> Callback
A callback function.
bool read(T &message, const boost::posix_time::time_duration &timeout)
Read a u-blox message of the given type.
void readCallback(unsigned char *data, std::size_t &size)
Processes u-blox messages in the given buffer & clears the read messages from the buffer...
Callback func_
the callback function to handle the message
boost::mutex callback_mutex_
#define ROS_DEBUG_COND(cond,...)
bool wait(const boost::posix_time::time_duration &timeout)
Wait for on the condition.
std::multimap< std::pair< uint8_t, uint8_t >, boost::shared_ptr< CallbackHandler > > Callbacks
bool read(typename boost::call_traits< T >::reference message, bool search=false)