13 #include "sensor_msgs/Imu.h" 14 #include "sensor_msgs/MagneticField.h" 15 #include "sensor_msgs/FluidPressure.h" 16 #include "sensor_msgs/JointState.h" 17 #include "inertial_sense_ros/GPS.h" 18 #include "inertial_sense_ros/GPSInfo.h" 19 #include "inertial_sense_ros/PreIntIMU.h" 20 #include "inertial_sense_ros/FirmwareUpdate.h" 21 #include "inertial_sense_ros/refLLAUpdate.h" 22 #include "inertial_sense_ros/RTKRel.h" 23 #include "inertial_sense_ros/RTKInfo.h" 24 #include "inertial_sense_ros/GNSSEphemeris.h" 25 #include "inertial_sense_ros/GlonassEphemeris.h" 26 #include "inertial_sense_ros/GNSSObservation.h" 27 #include "inertial_sense_ros/GNSSObsVec.h" 28 #include "inertial_sense_ros/INL2States.h" 29 #include "nav_msgs/Odometry.h" 30 #include "std_srvs/Trigger.h" 31 #include "std_msgs/Header.h" 32 #include "geometry_msgs/Vector3Stamped.h" 33 #include "geometry_msgs/PoseWithCovarianceStamped.h" 34 #include "diagnostic_msgs/DiagnosticArray.h" 38 # define GPS_UNIX_OFFSET 315964800 // GPS time started on 6/1/1980 while UNIX time started 1/1/1970 this is the difference between those in seconds 39 # define LEAP_SECONDS 18 // GPS time does not have leap seconds, UNIX does (as of 1/1/2017 - next one is probably in 2020 sometime unless there is some crazy earthquake or nuclear blast) 40 # define UNIX_TO_GPS_OFFSET (GPS_UNIX_OFFSET - LEAP_SECONDS) 42 #define SET_CALLBACK(DID, __type, __cb_fun, __periodmultiple) \ 43 IS_.BroadcastBinaryData(DID, __periodmultiple, \ 44 [this](InertialSense*i, p_data_t* data, int pHandle)\ 47 this->__cb_fun(reinterpret_cast<__type*>(data->buf));\ 157 bool set_refLLA_to_value(inertial_sense_ros::refLLAUpdate::Request &req, inertial_sense_ros::refLLAUpdate::Response &res);
160 bool update_firmware_srv_callback(inertial_sense_ros::FirmwareUpdate::Request & req, inertial_sense_ros::FirmwareUpdate::Response & res);
tf::TransformBroadcaster br
inertial_sense_ros::GPSInfo gps_info_msg
inertial_sense_ros::GPS gps_msg
ros::Publisher strobe_pub_
ros::NodeHandle nh_private_
ros::Time ros_time_from_gtime(const uint64_t sec, double subsec)
enum InertialSenseROS::@0 ltcf
void RTK_Rel_callback(const gps_rtk_rel_t *const msg)
bool update_firmware_srv_callback(inertial_sense_ros::FirmwareUpdate::Request &req, inertial_sense_ros::FirmwareUpdate::Response &res)
void mag_callback(const magnetometer_t *const msg)
void GPS_raw_callback(const gps_raw_t *const msg)
void preint_IMU_callback(const preintegrated_imu_t *const msg)
geometry_msgs::Vector3Stamped gps_velEcef
void GPS_info_callback(const gps_sat_t *const msg)
float diagnostic_heading_base_to_rover_
float diagnostic_differential_age_
void GPS_pos_callback(const gps_pos_t *const msg)
void INS1_callback(const ins_1_t *const msg)
void RTK_Misc_callback(const gps_rtk_misc_t *const msg)
ros::Timer obs_bundle_timer_
void diagnostics_callback(const ros::TimerEvent &event)
inertial_sense_ros::INL2States inl2_states_msg
nav_msgs::Odometry odom_msg
ros::ServiceServer firmware_update_srv_
double tow_from_ros_time(const ros::Time &rt)
void GPS_vel_callback(const gps_vel_t *const msg)
void strobe_in_time_callback(const strobe_in_time_t *const msg)
void INS2_callback(const ins_2_t *const msg)
ros::ServiceServer mag_cal_srv_
float diagnostic_ar_ratio_
sensor_msgs::Imu imu2_msg
ros::Timer diagnostics_timer_
ros::Time ros_time_from_start_time(const double time)
ros_time_from_start_time
void set_flash_config(std::string param_name, uint32_t offset, T def) __attribute__((optimize(0)))
void configure_ascii_output()
void set_vector_flash_config(std::string param_name, uint32_t size, uint32_t offset)
typedef __attribute__
USB Device LPM Descriptor structure.
void GPS_obs_callback(const obsd_t *const msg, int nObs)
ros::ServiceServer multi_mag_cal_srv_
USBInterfaceDescriptor data
ros::Time ros_time_from_tow(const double tow)
ros_time_from_tow Get equivalent ros time from tow and internal week counter
void GPS_geph_callback(const geph_t *const msg)
ros_stream_t INL2_states_
ros::ServiceServer refLLA_set_current_srv_
void configure_parameters()
bool perform_mag_cal_srv_callback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
bool set_refLLA_to_value(inertial_sense_ros::refLLAUpdate::Request &req, inertial_sense_ros::refLLAUpdate::Response &res)
sensor_msgs::Imu imu1_msg
void GPS_eph_callback(const eph_t *const msg)
void configure_data_streams()
ros::Time ros_time_from_week_and_tow(const uint32_t week, const double timeOfWeek)
ros_time_from_week_and_tow Get current ROS time from week and tow
void GPS_obs_bundle_timer_callback(const ros::TimerEvent &e)
bool set_current_position_as_refLLA(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
ros::ServiceServer refLLA_set_value_srv_
void set_navigation_dt_ms()
void IMU_callback(const dual_imu_t *const msg)
void baro_callback(const barometer_t *const msg)
void callback(p_data_t *data)
inertial_sense_ros::GNSSObsVec obs_Vec_
bool perform_multi_mag_cal_srv_callback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
void flash_config_callback(const nvm_flash_cfg_t *const msg)
ros_stream_t diagnostics_
void INL2_states_callback(const inl2_states_t *const msg)