3 #include <ixblue_ins_msgs/Ins.h> 9 #include <sensor_msgs/Imu.h> 10 #include <sensor_msgs/NavSatFix.h> 11 #include <sensor_msgs/TimeReference.h> 23 static sensor_msgs::ImuPtr
26 static sensor_msgs::NavSatFixPtr
28 static sensor_msgs::TimeReferencePtr
32 static ixblue_ins_msgs::InsPtr
void onNewStdBinData(const ixblue_stdbin_decoder::Data::BinaryNav &navData, const ixblue_stdbin_decoder::Data::NavHeader &headerData)
ros::Publisher stdInsPublisher
static sensor_msgs::NavSatFixPtr toNavSatFixMsg(const ixblue_stdbin_decoder::Data::BinaryNav &navData)
ros::Publisher stdNavSatFixPublisher
DiagnosticsPublisher diagPub
static sensor_msgs::ImuPtr toImuMsg(const ixblue_stdbin_decoder::Data::BinaryNav &navData, bool use_compensated_acceleration)
std_msgs::Header getHeader(const ixblue_stdbin_decoder::Data::NavHeader &headerData, const ixblue_stdbin_decoder::Data::BinaryNav &navData)
bool useInsAsTimeReference
ros::Publisher stdTimeReferencePublisher
ros::Publisher stdImuPublisher
static sensor_msgs::TimeReferencePtr toTimeReference(const ixblue_stdbin_decoder::Data::NavHeader &headerData)
static ixblue_ins_msgs::InsPtr toiXInsMsg(const ixblue_stdbin_decoder::Data::BinaryNav &navData)
bool use_compensated_acceleration