Classes | Public Types | Public Member Functions | Public Attributes | List of all members
InertialSenseROS Class Reference

#include <inertial_sense.h>

Classes

struct  ros_stream_t
 

Public Types

enum  { NED, ENU }
 
enum  NMEA_message_config_t {
  NMEA_GPGGA = 0x01, NMEA_GPGLL = 0x02, NMEA_GPGSA = 0x04, NMEA_GPRMC = 0x08,
  NMEA_SER0 = 0x01, NMEA_SER1 = 0x02
}
 
enum  rtk_state_t { RTK_NONE, RTK_ROVER, RTK_BASE, DUAL_GNSS }
 

Public Member Functions

void baro_callback (const barometer_t *const msg)
 
void callback (p_data_t *data)
 
void configure_ascii_output ()
 
void configure_data_streams ()
 
void configure_parameters ()
 
void configure_rtk ()
 
void connect ()
 
void diagnostics_callback (const ros::TimerEvent &event)
 
void flash_config_callback (const nvm_flash_cfg_t *const msg)
 
void get_flash_config ()
 
void GPS_eph_callback (const eph_t *const msg)
 
void GPS_geph_callback (const geph_t *const msg)
 
void GPS_info_callback (const gps_sat_t *const msg)
 
void GPS_obs_bundle_timer_callback (const ros::TimerEvent &e)
 
void GPS_obs_callback (const obsd_t *const msg, int nObs)
 
void GPS_pos_callback (const gps_pos_t *const msg)
 
void GPS_raw_callback (const gps_raw_t *const msg)
 
void GPS_vel_callback (const gps_vel_t *const msg)
 
void IMU_callback (const dual_imu_t *const msg)
 
 InertialSenseROS ()
 
void INL2_states_callback (const inl2_states_t *const msg)
 
void INS1_callback (const ins_1_t *const msg)
 
void INS2_callback (const ins_2_t *const msg)
 
void mag_callback (const magnetometer_t *const msg)
 
bool perform_mag_cal_srv_callback (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
 
bool perform_multi_mag_cal_srv_callback (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
 
void preint_IMU_callback (const preintegrated_imu_t *const msg)
 
void publishGPS ()
 
void reset_device ()
 
ros::Time ros_time_from_gtime (const uint64_t sec, double subsec)
 
ros::Time ros_time_from_start_time (const double time)
 ros_time_from_start_time More...
 
ros::Time ros_time_from_tow (const double tow)
 ros_time_from_tow Get equivalent ros time from tow and internal week counter More...
 
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 More...
 
void RTK_Misc_callback (const gps_rtk_misc_t *const msg)
 
void RTK_Rel_callback (const gps_rtk_rel_t *const msg)
 
bool set_current_position_as_refLLA (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
 
template<typename T >
void set_flash_config (std::string param_name, uint32_t offset, T def) __attribute__((optimize(0)))
 
void set_navigation_dt_ms ()
 
bool set_refLLA_to_value (inertial_sense::refLLAUpdate::Request &req, inertial_sense::refLLAUpdate::Response &res)
 
template<typename T >
void set_vector_flash_config (std::string param_name, uint32_t size, uint32_t offset)
 
void start_log ()
 
void strobe_in_time_callback (const strobe_in_time_t *const msg)
 
double tow_from_ros_time (const ros::Time &rt)
 
void update ()
 
bool update_firmware_srv_callback (inertial_sense::FirmwareUpdate::Request &req, inertial_sense::FirmwareUpdate::Response &res)
 

Public Attributes

ros_stream_t baro_
 
int baudrate_
 
tf::TransformBroadcaster br
 
float diagnostic_ar_ratio_
 
float diagnostic_differential_age_
 
float diagnostic_heading_base_to_rover_
 
ros_stream_t diagnostics_
 
ros::Timer diagnostics_timer_
 
ros_stream_t dt_vel_
 
double ecef_ [3]
 
ros::ServiceServer firmware_update_srv_
 
std::string frame_id_
 
bool got_first_message_ = false
 
ros_stream_t GPS_
 
ros_stream_t GPS_eph_
 
ros_stream_t GPS_info_
 
inertial_sense::GPSInfo gps_info_msg
 
inertial_sense::GPS gps_msg
 
ros_stream_t GPS_obs_
 
double GPS_towOffset_ = 0
 
geometry_msgs::Vector3Stamped gps_velEcef
 
uint64_t GPS_week_ = 0
 
sensor_msgs::Imu imu1_msg
 
sensor_msgs::Imu imu2_msg
 
ros_stream_t IMU_
 
bool initialized_
 
ros_stream_t INL2_states_
 
inertial_sense::INL2States inl2_states_msg
 
ros_stream_t INS_
 
double INS_local_offset_ = 0.0
 
InertialSense IS_
 
ros::Time last_obs_time_
 
double lla_ [3]
 
bool log_enabled_
 
int LTCF
 
enum InertialSenseROS:: { ... }  ltcf
 
ros_stream_t mag_
 
ros::ServiceServer mag_cal_srv_
 
ros::ServiceServer multi_mag_cal_srv_
 
ros::NodeHandle nh_
 
ros::NodeHandle nh_private_
 
ros::Timer obs_bundle_timer_
 
inertial_sense::GNSSObsVec obs_Vec_
 
nav_msgs::Odometry odom_msg
 
std::string port_
 
bool publishTf
 
ros::ServiceServer refLLA_set_current_srv_
 
ros::ServiceServer refLLA_set_value_srv_
 
ros_stream_t RTK_
 
rtk_state_t RTK_state_ = RTK_NONE
 
ros::Publisher strobe_pub_
 
tf::Transform transform
 

Detailed Description

Definition at line 51 of file inertial_sense.h.

Member Enumeration Documentation

◆ anonymous enum

anonymous enum
Enumerator
NED 
ENU 

Definition at line 108 of file inertial_sense.h.

◆ NMEA_message_config_t

Enumerator
NMEA_GPGGA 
NMEA_GPGLL 
NMEA_GPGSA 
NMEA_GPRMC 
NMEA_SER0 
NMEA_SER1 

Definition at line 54 of file inertial_sense.h.

◆ rtk_state_t

Enumerator
RTK_NONE 
RTK_ROVER 
RTK_BASE 
DUAL_GNSS 

Definition at line 164 of file inertial_sense.h.

Constructor & Destructor Documentation

◆ InertialSenseROS()

InertialSenseROS::InertialSenseROS ( )

Start Up ROS service servers

Definition at line 8 of file inertial_sense.cpp.

Member Function Documentation

◆ baro_callback()

void InertialSenseROS::baro_callback ( const barometer_t *const  msg)

Definition at line 588 of file inertial_sense.cpp.

◆ callback()

void InertialSenseROS::callback ( p_data_t data)

◆ configure_ascii_output()

void InertialSenseROS::configure_ascii_output ( )

Definition at line 143 of file inertial_sense.cpp.

◆ configure_data_streams()

void InertialSenseROS::configure_data_streams ( )

Definition at line 38 of file inertial_sense.cpp.

◆ configure_parameters()

void InertialSenseROS::configure_parameters ( )

Definition at line 196 of file inertial_sense.cpp.

◆ configure_rtk()

void InertialSenseROS::configure_rtk ( )

Definition at line 210 of file inertial_sense.cpp.

◆ connect()

void InertialSenseROS::connect ( )

Connect to the uINS

Definition at line 159 of file inertial_sense.cpp.

◆ diagnostics_callback()

void InertialSenseROS::diagnostics_callback ( const ros::TimerEvent event)

Definition at line 803 of file inertial_sense.cpp.

◆ flash_config_callback()

void InertialSenseROS::flash_config_callback ( const nvm_flash_cfg_t *const  msg)

◆ get_flash_config()

void InertialSenseROS::get_flash_config ( )

◆ GPS_eph_callback()

void InertialSenseROS::GPS_eph_callback ( const eph_t *const  msg)

Definition at line 729 of file inertial_sense.cpp.

◆ GPS_geph_callback()

void InertialSenseROS::GPS_geph_callback ( const geph_t *const  msg)

Definition at line 775 of file inertial_sense.cpp.

◆ GPS_info_callback()

void InertialSenseROS::GPS_info_callback ( const gps_sat_t *const  msg)

Definition at line 557 of file inertial_sense.cpp.

◆ GPS_obs_bundle_timer_callback()

void InertialSenseROS::GPS_obs_bundle_timer_callback ( const ros::TimerEvent e)

Definition at line 713 of file inertial_sense.cpp.

◆ GPS_obs_callback()

void InertialSenseROS::GPS_obs_callback ( const obsd_t *const  msg,
int  nObs 
)

Definition at line 685 of file inertial_sense.cpp.

◆ GPS_pos_callback()

void InertialSenseROS::GPS_pos_callback ( const gps_pos_t *const  msg)

Definition at line 491 of file inertial_sense.cpp.

◆ GPS_raw_callback()

void InertialSenseROS::GPS_raw_callback ( const gps_raw_t *const  msg)

Definition at line 664 of file inertial_sense.cpp.

◆ GPS_vel_callback()

void InertialSenseROS::GPS_vel_callback ( const gps_vel_t *const  msg)

Definition at line 516 of file inertial_sense.cpp.

◆ IMU_callback()

void InertialSenseROS::IMU_callback ( const dual_imu_t *const  msg)

Definition at line 464 of file inertial_sense.cpp.

◆ INL2_states_callback()

void InertialSenseROS::INL2_states_callback ( const inl2_states_t *const  msg)

Definition at line 426 of file inertial_sense.cpp.

◆ INS1_callback()

void InertialSenseROS::INS1_callback ( const ins_1_t *const  msg)

Definition at line 317 of file inertial_sense.cpp.

◆ INS2_callback()

void InertialSenseROS::INS2_callback ( const ins_2_t *const  msg)

Definition at line 366 of file inertial_sense.cpp.

◆ mag_callback()

void InertialSenseROS::mag_callback ( const magnetometer_t *const  msg)

Definition at line 576 of file inertial_sense.cpp.

◆ perform_mag_cal_srv_callback()

bool InertialSenseROS::perform_mag_cal_srv_callback ( std_srvs::Trigger::Request &  req,
std_srvs::Trigger::Response &  res 
)

Definition at line 925 of file inertial_sense.cpp.

◆ perform_multi_mag_cal_srv_callback()

bool InertialSenseROS::perform_multi_mag_cal_srv_callback ( std_srvs::Trigger::Request &  req,
std_srvs::Trigger::Response &  res 
)

Definition at line 954 of file inertial_sense.cpp.

◆ preint_IMU_callback()

void InertialSenseROS::preint_IMU_callback ( const preintegrated_imu_t *const  msg)

Definition at line 599 of file inertial_sense.cpp.

◆ publishGPS()

void InertialSenseROS::publishGPS ( )

Definition at line 528 of file inertial_sense.cpp.

◆ reset_device()

void InertialSenseROS::reset_device ( )

Definition at line 983 of file inertial_sense.cpp.

◆ ros_time_from_gtime()

ros::Time InertialSenseROS::ros_time_from_gtime ( const uint64_t  sec,
double  subsec 
)

Definition at line 1077 of file inertial_sense.cpp.

◆ ros_time_from_start_time()

ros::Time InertialSenseROS::ros_time_from_start_time ( const double  time)

ros_time_from_start_time

Parameters
time- Time since boot up in seconds - Convert to GPS time of week by adding gps.towOffset
Returns
equivalent ros::Time

Definition at line 1037 of file inertial_sense.cpp.

◆ ros_time_from_tow()

ros::Time InertialSenseROS::ros_time_from_tow ( const double  tow)

ros_time_from_tow Get equivalent ros time from tow and internal week counter

Parameters
towTime of Week (seconds)
Returns
equivalent ros::Time

Definition at line 1067 of file inertial_sense.cpp.

◆ ros_time_from_week_and_tow()

ros::Time InertialSenseROS::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

Parameters
weekWeeks since January 6th, 1980
timeOfWeekTime of week (since Sunday morning) in seconds, GMT
Returns
equivalent ros::Time

Definition at line 1008 of file inertial_sense.cpp.

◆ RTK_Misc_callback()

void InertialSenseROS::RTK_Misc_callback ( const gps_rtk_misc_t *const  msg)

Definition at line 617 of file inertial_sense.cpp.

◆ RTK_Rel_callback()

void InertialSenseROS::RTK_Rel_callback ( const gps_rtk_rel_t *const  msg)

Definition at line 642 of file inertial_sense.cpp.

◆ set_current_position_as_refLLA()

bool InertialSenseROS::set_current_position_as_refLLA ( std_srvs::Trigger::Request &  req,
std_srvs::Trigger::Response &  res 
)

Definition at line 859 of file inertial_sense.cpp.

◆ set_flash_config()

template<typename T >
void InertialSenseROS::set_flash_config ( std::string  param_name,
uint32_t  offset,
def 
)

Definition at line 310 of file inertial_sense.cpp.

◆ set_navigation_dt_ms()

void InertialSenseROS::set_navigation_dt_ms ( )

Definition at line 179 of file inertial_sense.cpp.

◆ set_refLLA_to_value()

bool InertialSenseROS::set_refLLA_to_value ( inertial_sense::refLLAUpdate::Request &  req,
inertial_sense::refLLAUpdate::Response &  res 
)

Definition at line 896 of file inertial_sense.cpp.

◆ set_vector_flash_config()

template<typename T >
void InertialSenseROS::set_vector_flash_config ( std::string  param_name,
uint32_t  size,
uint32_t  offset 
)

Definition at line 295 of file inertial_sense.cpp.

◆ start_log()

void InertialSenseROS::start_log ( )

Definition at line 136 of file inertial_sense.cpp.

◆ strobe_in_time_callback()

void InertialSenseROS::strobe_in_time_callback ( const strobe_in_time_t *const  msg)

Definition at line 542 of file inertial_sense.cpp.

◆ tow_from_ros_time()

double InertialSenseROS::tow_from_ros_time ( const ros::Time rt)

Definition at line 1072 of file inertial_sense.cpp.

◆ update()

void InertialSenseROS::update ( )

Definition at line 537 of file inertial_sense.cpp.

◆ update_firmware_srv_callback()

bool InertialSenseROS::update_firmware_srv_callback ( inertial_sense::FirmwareUpdate::Request &  req,
inertial_sense::FirmwareUpdate::Response &  res 
)

Definition at line 993 of file inertial_sense.cpp.

Member Data Documentation

◆ baro_

ros_stream_t InertialSenseROS::baro_

Definition at line 137 of file inertial_sense.h.

◆ baudrate_

int InertialSenseROS::baudrate_

Definition at line 83 of file inertial_sense.h.

◆ br

tf::TransformBroadcaster InertialSenseROS::br

Definition at line 104 of file inertial_sense.h.

◆ diagnostic_ar_ratio_

float InertialSenseROS::diagnostic_ar_ratio_

Definition at line 149 of file inertial_sense.h.

◆ diagnostic_differential_age_

float InertialSenseROS::diagnostic_differential_age_

Definition at line 149 of file inertial_sense.h.

◆ diagnostic_heading_base_to_rover_

float InertialSenseROS::diagnostic_heading_base_to_rover_

Definition at line 149 of file inertial_sense.h.

◆ diagnostics_

ros_stream_t InertialSenseROS::diagnostics_

Definition at line 146 of file inertial_sense.h.

◆ diagnostics_timer_

ros::Timer InertialSenseROS::diagnostics_timer_

Definition at line 148 of file inertial_sense.h.

◆ dt_vel_

ros_stream_t InertialSenseROS::dt_vel_

Definition at line 140 of file inertial_sense.h.

◆ ecef_

double InertialSenseROS::ecef_[3]

Definition at line 213 of file inertial_sense.h.

◆ firmware_update_srv_

ros::ServiceServer InertialSenseROS::firmware_update_srv_

Definition at line 153 of file inertial_sense.h.

◆ frame_id_

std::string InertialSenseROS::frame_id_

Definition at line 87 of file inertial_sense.h.

◆ got_first_message_

bool InertialSenseROS::got_first_message_ = false

Definition at line 209 of file inertial_sense.h.

◆ GPS_

ros_stream_t InertialSenseROS::GPS_

Definition at line 117 of file inertial_sense.h.

◆ GPS_eph_

ros_stream_t InertialSenseROS::GPS_eph_

Definition at line 119 of file inertial_sense.h.

◆ GPS_info_

ros_stream_t InertialSenseROS::GPS_info_

Definition at line 131 of file inertial_sense.h.

◆ gps_info_msg

inertial_sense::GPSInfo InertialSenseROS::gps_info_msg

Definition at line 218 of file inertial_sense.h.

◆ gps_msg

inertial_sense::GPS InertialSenseROS::gps_msg

Definition at line 216 of file inertial_sense.h.

◆ GPS_obs_

ros_stream_t InertialSenseROS::GPS_obs_

Definition at line 118 of file inertial_sense.h.

◆ GPS_towOffset_

double InertialSenseROS::GPS_towOffset_ = 0

Definition at line 204 of file inertial_sense.h.

◆ gps_velEcef

geometry_msgs::Vector3Stamped InertialSenseROS::gps_velEcef

Definition at line 217 of file inertial_sense.h.

◆ GPS_week_

uint64_t InertialSenseROS::GPS_week_ = 0

Definition at line 206 of file inertial_sense.h.

◆ imu1_msg

sensor_msgs::Imu InertialSenseROS::imu1_msg

Definition at line 214 of file inertial_sense.h.

◆ imu2_msg

sensor_msgs::Imu InertialSenseROS::imu2_msg

Definition at line 214 of file inertial_sense.h.

◆ IMU_

ros_stream_t InertialSenseROS::IMU_

Definition at line 114 of file inertial_sense.h.

◆ initialized_

bool InertialSenseROS::initialized_

Definition at line 84 of file inertial_sense.h.

◆ INL2_states_

ros_stream_t InertialSenseROS::INL2_states_

Definition at line 102 of file inertial_sense.h.

◆ inl2_states_msg

inertial_sense::INL2States InertialSenseROS::inl2_states_msg

Definition at line 219 of file inertial_sense.h.

◆ INS_

ros_stream_t InertialSenseROS::INS_

Definition at line 97 of file inertial_sense.h.

◆ INS_local_offset_

double InertialSenseROS::INS_local_offset_ = 0.0

Definition at line 208 of file inertial_sense.h.

◆ IS_

InertialSense InertialSenseROS::IS_

Definition at line 225 of file inertial_sense.h.

◆ last_obs_time_

ros::Time InertialSenseROS::last_obs_time_

Definition at line 129 of file inertial_sense.h.

◆ lla_

double InertialSenseROS::lla_[3]

Definition at line 212 of file inertial_sense.h.

◆ log_enabled_

bool InertialSenseROS::log_enabled_

Definition at line 85 of file inertial_sense.h.

◆ LTCF

int InertialSenseROS::LTCF

Definition at line 107 of file inertial_sense.h.

◆ ltcf

enum { ... } InertialSenseROS::ltcf

◆ mag_

ros_stream_t InertialSenseROS::mag_

Definition at line 134 of file inertial_sense.h.

◆ mag_cal_srv_

ros::ServiceServer InertialSenseROS::mag_cal_srv_

Definition at line 151 of file inertial_sense.h.

◆ multi_mag_cal_srv_

ros::ServiceServer InertialSenseROS::multi_mag_cal_srv_

Definition at line 152 of file inertial_sense.h.

◆ nh_

ros::NodeHandle InertialSenseROS::nh_

Definition at line 221 of file inertial_sense.h.

◆ nh_private_

ros::NodeHandle InertialSenseROS::nh_private_

Definition at line 222 of file inertial_sense.h.

◆ obs_bundle_timer_

ros::Timer InertialSenseROS::obs_bundle_timer_

Definition at line 128 of file inertial_sense.h.

◆ obs_Vec_

inertial_sense::GNSSObsVec InertialSenseROS::obs_Vec_

Definition at line 127 of file inertial_sense.h.

◆ odom_msg

nav_msgs::Odometry InertialSenseROS::odom_msg

Definition at line 215 of file inertial_sense.h.

◆ port_

std::string InertialSenseROS::port_

Definition at line 82 of file inertial_sense.h.

◆ publishTf

bool InertialSenseROS::publishTf

Definition at line 105 of file inertial_sense.h.

◆ refLLA_set_current_srv_

ros::ServiceServer InertialSenseROS::refLLA_set_current_srv_

Definition at line 154 of file inertial_sense.h.

◆ refLLA_set_value_srv_

ros::ServiceServer InertialSenseROS::refLLA_set_value_srv_

Definition at line 155 of file inertial_sense.h.

◆ RTK_

ros_stream_t InertialSenseROS::RTK_

Definition at line 172 of file inertial_sense.h.

◆ RTK_state_

rtk_state_t InertialSenseROS::RTK_state_ = RTK_NONE

Definition at line 171 of file inertial_sense.h.

◆ strobe_pub_

ros::Publisher InertialSenseROS::strobe_pub_

Definition at line 143 of file inertial_sense.h.

◆ transform

tf::Transform InertialSenseROS::transform

Definition at line 106 of file inertial_sense.h.


The documentation for this class was generated from the following files:


inertial_sense_ros
Author(s):
autogenerated on Sat Sep 19 2020 03:19:09