Go to the documentation of this file.
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>
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,
208 template <
typename T>
216 CallbackMap::key_type key = message_key;
218 (((
unsigned int)
callbackmap_.count(key)) ?
"true" :
"false"));
304 typedef std::unordered_map<std::string, uint32_t>
GPSFixMap;
336 typedef std::unordered_map<std::string, uint32_t>
ImuMap;
std::string g_rx_tcp_port
Rx TCP port, e.g. IP10 or IP11, to which ROSaic is connected to.
CallbackHandlers(ROSaicNodeBase *node, Settings *settings)
std::unordered_map< std::string, uint32_t > LocalizationMap
std::multimap< std::string, boost::shared_ptr< AbstractCallbackHandler > > CallbackMap
static NavSatFixMap navsatfix_map
void readCallback(Timestamp recvTimestamp, const uint8_t *data, std::size_t &size)
Searches for Rx messages that could potentially be decoded/parsed/published.
std::unordered_map< std::string, uint32_t > ImuMap
static DiagnosticArrayMap diagnosticarray_map
std::unordered_map< std::string, uint32_t > GPSFixMap
std::unordered_map< std::string, uint32_t > DiagnosticArrayMap
Defines a class that reads messages handed over from the circular buffer.
static std::string do_inspose_
static boost::mutex callback_mutex_
This class is the base class for abstraction.
boost::condition_variable g_cd_condition
Condition variable complementing "g_cd_mutex".
static LocalizationMap localization_map
bool g_cd_received
Determines whether the connection descriptor was received from the Rx.
static std::string do_diagnostics_
static std::string do_imu_
static GPSFixMap gpsfix_map
Settings * settings_
Settings.
static std::string do_insgpsfix_
static std::string do_pose_
void handle()
Called every time rx_message is found to contain some potentially useful message.
static std::string do_navsatfix_
RxMessage rx_message_
RxMessage parser.
virtual void handle(RxMessage &rx_message, std::string message_key)=0
std::unordered_map< std::string, uint32_t > PoseWithCovarianceStampedMap
Represents ensemble of (to be constructed) ROS messages, to be handled at once by this class.
Abstract class representing a generic callback handler, includes high-level functionality such as wai...
CallbackMap insert(std::string message_key)
Adds a pair to the multimap "callbackmap_", with the message_key being the key.
bool g_response_received
Determines whether a command reply was received from the Rx.
static std::string do_insnavsatfix_
static PoseWithCovarianceStampedMap pose_map
bool read(std::string message_key, bool search=false)
Performs the CRC check (if SBF) and publishes ROS messages.
bool Wait(const boost::posix_time::time_duration &timeout)
void log(LogLevel logLevel, const std::string &s)
Log function to provide abstraction of ROS loggers.
static std::string do_gpsfix_
std::unordered_map< std::string, uint32_t > NavSatFixMap
boost::mutex g_cd_mutex
Mutex to control changes of global variable "g_cd_received".
boost::condition_variable condition_
static std::string do_inslocalization_
boost::condition_variable g_response_condition
Condition variable complementing "g_response_mutex".
boost::mutex g_response_mutex
Mutex to control changes of global variable "g_response_received".
Can search buffer for messages, read/parse them, and so on.
ROSaicNodeBase * node_
Pointer to Node.
void handle(RxMessage &rx_message, std::string message_key)