Go to the documentation of this file.
30 #include <condition_variable>
33 #include <boost/asio.hpp>
35 #include "novatel_oem7_msgs/Oem7AbasciiCmd.h"
36 #include "novatel_oem7_msgs/Oem7RawMsg.h"
113 catch(std::exception
const& ex)
127 << __DATE__ <<
" " << __TIME__);
146 std::string oem7_if_name;
152 std::string msg_decoder_name;
161 std::vector<std::string> oem7_raw_msgs;
163 for(
const auto& msg : oem7_raw_msgs)
201 bool serviceOem7AbasciiCb(novatel_oem7_msgs::Oem7AbasciiCmd::Request& req, novatel_oem7_msgs::Oem7AbasciiCmd::Response& rsp)
215 recvr_->write(boost::asio::buffer(req.cmd));
216 static const std::string NEWLINE(
"\n");
217 recvr_->write(boost::asio::buffer(NEWLINE));
221 std::chrono::steady_clock::now() + std::chrono::seconds(3)
222 ) == std::cv_status::no_timeout)
252 for(log_count_map_t::iterator itr =
log_counts_.begin();
257 long count = itr->second;
285 novatel_oem7_msgs::Oem7RawMsg::Ptr oem7_raw_msg(
new novatel_oem7_msgs::Oem7RawMsg);
286 oem7_raw_msg->message_data.insert(
287 oem7_raw_msg->message_data.end(),
288 raw_msg->getMessageData(0),
289 raw_msg->getMessageData(raw_msg->getMessageDataLength()));
291 assert(oem7_raw_msg->message_data.size() == raw_msg->getMessageDataLength());
303 <<
" type= " << raw_msg->getMessageType());
306 if(raw_msg->getMessageFormat() == Oem7RawMessageIf::OEM7MSGFMT_UNKNOWN)
310 "Type: " << raw_msg->getMessageType() <<
311 "Fmt: " << raw_msg->getMessageFormat() <<
312 "Len: " << raw_msg->getMessageDataLength() <<
325 if(raw_msg->getMessageFormat() == Oem7RawMessageIf::OEM7MSGFMT_ASCII ||
326 raw_msg->getMessageFormat() == Oem7RawMessageIf::OEM7MSGFMT_ABASCII)
328 std::string msg(raw_msg->getMessageData(0), raw_msg->getMessageData(raw_msg->getMessageDataLength()));
332 <<
"<---------------------------");
335 if(raw_msg->getMessageType() == Oem7RawMessageIf::OEM7MSGTYPE_RSP)
337 std::string rsp(raw_msg->getMessageData(0), raw_msg->getMessageData(raw_msg->getMessageDataLength()));
338 if(rsp.find_first_not_of(
" /t/r/n") != std::string::npos &&
339 std::all_of(rsp.begin(), rsp.end(), [](
char c){return std::isprint(c);}))
354 if( raw_msg->getMessageFormat() == Oem7RawMessageIf::OEM7MSGFMT_BINARY ||
355 raw_msg->getMessageFormat() == Oem7RawMessageIf::OEM7MSGFMT_SHORTBINARY ||
356 (raw_msg->getMessageFormat() == Oem7RawMessageIf::OEM7MSGFMT_ASCII &&
isNMEAMessage(raw_msg)))
387 NODELET_WARN(
"No more input from Decoder; Oem7MessageNodelet finished.");
393 recvr_loader_(
"novatel_oem7_driver",
"novatel_oem7_driver::Oem7ReceiverIf"),
void setup(const std::string &name, ros::NodeHandle &nh)
double publish_delay_sec_
Delay after publishing each message; used to throttle output with static data sources.
boost::shared_ptr< MessageHandler > msg_handler_
Dispatches individual messages for handling.
ros::NodeHandle & getNodeHandle() const
std::set< int > raw_msg_pub_
Set of raw messages to publish.
void publishOem7RawMsg(Oem7RawMessageIf::ConstPtr raw_msg)
bool getParam(const std::string &key, bool &b) const
void serviceLoopCb(const ros::TimerEvent &event)
long discarded_msg_num_
Number of messages received and discarded by the driver.
ros::CallbackQueue queue_
#define NODELET_WARN(...)
ROSCPP_DECL void shutdown()
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
std::mutex nodelet_mtx_
Protects nodelet internal state.
long total_log_count_
Total number of logs received.
#define NODELET_WARN_STREAM(...)
std::mutex rsp_ready_mtx_
Response condition guard.
ros::NodeHandle & getPrivateNodeHandle() const
const std::string & getOem7MessageName(int msg_id)
boost::shared_ptr< novatel_oem7_driver::Oem7MessageDecoderIf > msg_decoder
Message Decoder plugin.
std::string rsp_
The latest response from Oem7 receiver.
boost::shared_ptr< novatel_oem7_driver::Oem7ReceiverIf > recvr_
Oem7 Receiver Interface plugin.
#define NODELET_ERROR_STREAM(...)
PLUGINLIB_EXPORT_CLASS(novatel_oem7_driver::Oem7ConfigNodelet, nodelet::Nodelet)
bool serviceOem7AbasciiCb(novatel_oem7_msgs::Oem7AbasciiCmd::Request &req, novatel_oem7_msgs::Oem7AbasciiCmd::Response &rsp)
void onNewMessage(Oem7RawMessageIf::ConstPtr raw_msg)
void publish(boost::shared_ptr< M > &msg)
ros::ServiceServer oem7_cmd_srv_
Oem7 command service.
ros::CallbackQueue timer_queue_
Dedicated queue for command requests.
void initializeOem7MessageUtil(ros::NodeHandle &nh)
long unknown_msg_num_
number of messages received that could not be identified.
pluginlib::ClassLoader< novatel_oem7_driver::Oem7MessageDecoderIf > oem7_msg_decoder_loader
void setCallbackQueue(CallbackQueueInterface *queue)
#define NODELET_INFO(...)
int getOem7MessageId(const std::string &msg_name)
boost::shared_ptr< T > createInstance(const std::string &lookup_name)
std::condition_variable rsp_ready_cond_
Response ready, signaled from response handler to Oem7 Cmd Handler.
void outputLogStatistics()
boost::shared_ptr< ros::AsyncSpinner > aspinner_
1 thread servicing the command queue.
#define NODELET_FATAL_STREAM(...)
#define NODELET_DEBUG_STREAM(...)
void updateLogStatistics(const Oem7RawMessageIf::ConstPtr &raw_msg)
const std::string & getName() const
boost::shared_ptr< ros::AsyncSpinner > timer_spinner_
1 thread servicing the command queue.
ros::Timer timer_
One time service callback.
Oem7RosPublisher oem7rawmsg_pub_
Publishes raw Oem7 messages.
#define NODELET_INFO_STREAM(...)
bool isNMEAMessage(const Oem7RawMessageIf::ConstPtr &raw_msg)
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
bool publish_unknown_oem7raw_
Publish all unknown messages to 'Oem7Raw'.
std::map< int, long > log_count_map_t
#define NODELET_DEBUG(...)
pluginlib::ClassLoader< novatel_oem7_driver::Oem7ReceiverIf > recvr_loader_
log_count_map_t log_counts_
Indidividual log counts.