#include <stdio.h>
#include <iostream>
#include <algorithm>
#include <string>
#include <cstdlib>
#include "InertialSense.h"
#include "ros/ros.h"
#include "ros/timer.h"
#include "sensor_msgs/Imu.h"
#include "sensor_msgs/MagneticField.h"
#include "sensor_msgs/FluidPressure.h"
#include "sensor_msgs/JointState.h"
#include "inertial_sense/GPS.h"
#include "inertial_sense/GPSInfo.h"
#include "inertial_sense/PreIntIMU.h"
#include "inertial_sense/FirmwareUpdate.h"
#include "inertial_sense/refLLAUpdate.h"
#include "inertial_sense/RTKRel.h"
#include "inertial_sense/RTKInfo.h"
#include "inertial_sense/GNSSEphemeris.h"
#include "inertial_sense/GlonassEphemeris.h"
#include "inertial_sense/GNSSObservation.h"
#include "inertial_sense/GNSSObsVec.h"
#include "inertial_sense/INL2States.h"
#include "nav_msgs/Odometry.h"
#include "std_srvs/Trigger.h"
#include "std_msgs/Header.h"
#include "geometry_msgs/Vector3Stamped.h"
#include "geometry_msgs/PoseWithCovarianceStamped.h"
#include "diagnostic_msgs/DiagnosticArray.h"
#include <tf/transform_broadcaster.h>
Go to the source code of this file.
◆ GPS_UNIX_OFFSET
#define GPS_UNIX_OFFSET 315964800 |
◆ LEAP_SECONDS
◆ SET_CALLBACK
#define SET_CALLBACK |
( |
|
DID, |
|
|
|
__type, |
|
|
|
__cb_fun, |
|
|
|
__periodmultiple |
|
) |
| |
Value:IS_.BroadcastBinaryData(DID, __periodmultiple, \
{ \
\
this->__cb_fun(reinterpret_cast<__type*>(data->
buf));\
})
USBInterfaceDescriptor data
uint8_t buf[MAX_DATASET_SIZE]
Definition at line 42 of file inertial_sense.h.
◆ UNIX_TO_GPS_OFFSET