59 #ifndef CALLBACK_HANDLERS_HPP 60 #define CALLBACK_HANDLERS_HPP 63 #include <boost/foreach.hpp> 66 #include <boost/function.hpp> 72 #include <boost/thread.hpp> 77 #include <boost/thread/condition.hpp> 78 #include <boost/tokenizer.hpp> 81 #include <boost/algorithm/string/join.hpp> 84 #include <boost/date_time/posix_time/posix_time.hpp> 87 #include <boost/asio.hpp> 90 #include <boost/asio/serial_port.hpp> 91 #include <boost/bind.hpp> 92 #include <boost/format.hpp> 93 #include <boost/thread/mutex.hpp> 123 virtual void handle(
RxMessage& rx_message, std::string message_key) = 0;
125 bool Wait(
const boost::posix_time::time_duration& timeout)
127 boost::mutex::scoped_lock lock(
mutex_);
140 template <
typename T>
144 virtual const T&
Get() {
return message_; }
148 boost::mutex::scoped_lock lock(
mutex_);
151 if (!rx_message.
read(message_key))
153 std::ostringstream ss;
154 ss <<
"Rx decoder error for message with ID (empty field if non-determinable)" 155 << rx_message.
messageID() <<
". Reason unknown.";
156 throw std::runtime_error(ss.str());
159 }
catch (std::runtime_error& e)
161 std::ostringstream ss;
162 ss <<
"Rx decoder error for message with ID " 165 throw std::runtime_error(ss.str());
187 typedef std::multimap<std::string,
193 rx_message_(node, settings),
208 template <
typename T>
211 boost::mutex::scoped_lock lock(callback_mutex_);
214 callbackmap_.insert(std::make_pair(
216 CallbackMap::key_type key = message_key;
217 node_->log(
LogLevel::DEBUG,
"Key " + message_key +
" successfully inserted into multimap: " +
218 (((
unsigned int)callbackmap_.count(key)) ?
"true" :
"false"));
235 void readCallback(
Timestamp recvTimestamp,
const uint8_t* data, std::size_t& size);
304 typedef std::unordered_map<std::string, uint32_t>
GPSFixMap;
336 typedef std::unordered_map<std::string, uint32_t>
ImuMap;
static std::string do_imu_
bool read(std::string message_key, bool search=false)
Performs the CRC check (if SBF) and publishes ROS messages.
CallbackHandlers(ROSaicNodeBase *node, Settings *settings)
std::unordered_map< std::string, uint32_t > PoseWithCovarianceStampedMap
RxMessage rx_message_
RxMessage parser.
std::multimap< std::string, boost::shared_ptr< AbstractCallbackHandler > > CallbackMap
Represents ensemble of (to be constructed) ROS messages, to be handled at once by this class...
bool Wait(const boost::posix_time::time_duration &timeout)
static std::string do_insnavsatfix_
static std::string do_gpsfix_
static LocalizationMap localization_map
static std::string do_diagnostics_
boost::mutex g_response_mutex
Mutex to control changes of global variable "g_response_received".
Abstract class representing a generic callback handler, includes high-level functionality such as wai...
Defines a class that reads messages handed over from the circular buffer.
static boost::mutex callback_mutex_
static std::string do_inslocalization_
bool g_response_received
Determines whether a command reply was received from the Rx.
static std::string do_insgpsfix_
std::unordered_map< std::string, uint32_t > LocalizationMap
static NavSatFixMap navsatfix_map
boost::mutex g_cd_mutex
Mutex to control changes of global variable "g_cd_received".
CallbackMap insert(std::string message_key)
Adds a pair to the multimap "callbackmap_", with the message_key being the key.
std::string g_rx_tcp_port
Rx TCP port, e.g. IP10 or IP11, to which ROSaic is connected to.
ROSaicNodeBase * node_
Pointer to Node.
virtual void handle(RxMessage &rx_message, std::string message_key)=0
bool g_cd_received
Determines whether the connection descriptor was received from the Rx.
static DiagnosticArrayMap diagnosticarray_map
static std::string do_inspose_
boost::condition_variable g_cd_condition
Condition variable complementing "g_cd_mutex".
boost::condition_variable condition_
std::unordered_map< std::string, uint32_t > ImuMap
boost::condition_variable g_response_condition
Condition variable complementing "g_response_mutex".
std::unordered_map< std::string, uint32_t > GPSFixMap
static GPSFixMap gpsfix_map
std::unordered_map< std::string, uint32_t > NavSatFixMap
This class is the base class for abstraction.
Can search buffer for messages, read/parse them, and so on.
void handle(RxMessage &rx_message, std::string message_key)
std::unordered_map< std::string, uint32_t > DiagnosticArrayMap
static PoseWithCovarianceStampedMap pose_map
Settings * settings_
Settings.
static std::string do_navsatfix_
static std::string do_pose_