30 #include "novatel_oem7_msgs/Oem7RawMsg.h" 33 #include <boost/scoped_ptr.hpp> 44 const novatel_oem7_msgs::Oem7RawMsg::ConstPtr
msg_;
54 return Oem7RawMessageIf::OEM7MSGTYPE_UNKNOWN;
60 return Oem7RawMessageIf::OEM7MSGFMT_UNKNOWN;
65 const Oem7MessageCommonHeaderMem* mem =
66 reinterpret_cast<const Oem7MessageCommonHeaderMem*
>(
getMessageData(0));
67 return mem->message_id;
72 return const_cast<uint8_t*
>(msg_->message_data.data());
77 return msg_->message_data.size();
112 msg_handler_->handleMessage(raw_msg);
Oem7MessageType getMessageType() const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
PLUGINLIB_EXPORT_CLASS(novatel_oem7_driver::Oem7LogNodelet, nodelet::Nodelet)
const novatel_oem7_msgs::Oem7RawMsg::ConstPtr msg_
const uint8_t * getMessageData(size_t offset) const
size_t getMessageDataLength() const
RawMsgAdapter(const novatel_oem7_msgs::Oem7RawMsg::ConstPtr &msg)
Oem7MessageFormat getMessageFormat() const
ros::Subscriber oem7_raw_msg_sub_
boost::scoped_ptr< MessageHandler > msg_handler_
void oem7RawMsgCb(const novatel_oem7_msgs::Oem7RawMsg::ConstPtr &msg)