#include <inertial_sense_ros.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_ros::refLLAUpdate::Request &req, inertial_sense_ros::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_ros::FirmwareUpdate::Request &req, inertial_sense_ros::FirmwareUpdate::Response &res) | 
Definition at line 51 of file inertial_sense_ros.h.
| anonymous enum | 
| Enumerator | |
|---|---|
| NED | |
| ENU | |
Definition at line 108 of file inertial_sense_ros.h.
| Enumerator | |
|---|---|
| NMEA_GPGGA | |
| NMEA_GPGLL | |
| NMEA_GPGSA | |
| NMEA_GPRMC | |
| NMEA_SER0 | |
| NMEA_SER1 | |
Definition at line 54 of file inertial_sense_ros.h.
| Enumerator | |
|---|---|
| RTK_NONE | |
| RTK_ROVER | |
| RTK_BASE | |
| DUAL_GNSS | |
Definition at line 164 of file inertial_sense_ros.h.
| InertialSenseROS::InertialSenseROS | ( | ) | 
Start Up ROS service servers
Definition at line 9 of file inertial_sense_ros.cpp.
| void InertialSenseROS::baro_callback | ( | const barometer_t *const | msg | ) | 
Definition at line 605 of file inertial_sense_ros.cpp.
| void InertialSenseROS::callback | ( | p_data_t * | data | ) | 
| void InertialSenseROS::configure_ascii_output | ( | ) | 
Definition at line 144 of file inertial_sense_ros.cpp.
| void InertialSenseROS::configure_data_streams | ( | ) | 
Definition at line 39 of file inertial_sense_ros.cpp.
| void InertialSenseROS::configure_parameters | ( | ) | 
Definition at line 197 of file inertial_sense_ros.cpp.
| void InertialSenseROS::configure_rtk | ( | ) | 
Definition at line 211 of file inertial_sense_ros.cpp.
| void InertialSenseROS::connect | ( | ) | 
Connect to the uINS
Definition at line 160 of file inertial_sense_ros.cpp.
| void InertialSenseROS::diagnostics_callback | ( | const ros::TimerEvent & | event | ) | 
Definition at line 820 of file inertial_sense_ros.cpp.
| void InertialSenseROS::flash_config_callback | ( | const nvm_flash_cfg_t *const | msg | ) | 
| void InertialSenseROS::get_flash_config | ( | ) | 
| void InertialSenseROS::GPS_eph_callback | ( | const eph_t *const | msg | ) | 
Definition at line 746 of file inertial_sense_ros.cpp.
| void InertialSenseROS::GPS_geph_callback | ( | const geph_t *const | msg | ) | 
Definition at line 792 of file inertial_sense_ros.cpp.
| void InertialSenseROS::GPS_info_callback | ( | const gps_sat_t *const | msg | ) | 
Definition at line 574 of file inertial_sense_ros.cpp.
| void InertialSenseROS::GPS_obs_bundle_timer_callback | ( | const ros::TimerEvent & | e | ) | 
Definition at line 730 of file inertial_sense_ros.cpp.
| void InertialSenseROS::GPS_obs_callback | ( | const obsd_t *const | msg, | 
| int | nObs | ||
| ) | 
Definition at line 702 of file inertial_sense_ros.cpp.
| void InertialSenseROS::GPS_pos_callback | ( | const gps_pos_t *const | msg | ) | 
Definition at line 508 of file inertial_sense_ros.cpp.
| void InertialSenseROS::GPS_raw_callback | ( | const gps_raw_t *const | msg | ) | 
Definition at line 681 of file inertial_sense_ros.cpp.
| void InertialSenseROS::GPS_vel_callback | ( | const gps_vel_t *const | msg | ) | 
Definition at line 533 of file inertial_sense_ros.cpp.
| void InertialSenseROS::IMU_callback | ( | const dual_imu_t *const | msg | ) | 
Definition at line 481 of file inertial_sense_ros.cpp.
| void InertialSenseROS::INL2_states_callback | ( | const inl2_states_t *const | msg | ) | 
Definition at line 443 of file inertial_sense_ros.cpp.
| void InertialSenseROS::INS1_callback | ( | const ins_1_t *const | msg | ) | 
Definition at line 318 of file inertial_sense_ros.cpp.
| void InertialSenseROS::INS2_callback | ( | const ins_2_t *const | msg | ) | 
Definition at line 367 of file inertial_sense_ros.cpp.
| void InertialSenseROS::mag_callback | ( | const magnetometer_t *const | msg | ) | 
Definition at line 593 of file inertial_sense_ros.cpp.
| bool InertialSenseROS::perform_mag_cal_srv_callback | ( | std_srvs::Trigger::Request & | req, | 
| std_srvs::Trigger::Response & | res | ||
| ) | 
Definition at line 942 of file inertial_sense_ros.cpp.
| bool InertialSenseROS::perform_multi_mag_cal_srv_callback | ( | std_srvs::Trigger::Request & | req, | 
| std_srvs::Trigger::Response & | res | ||
| ) | 
Definition at line 971 of file inertial_sense_ros.cpp.
| void InertialSenseROS::preint_IMU_callback | ( | const preintegrated_imu_t *const | msg | ) | 
Definition at line 616 of file inertial_sense_ros.cpp.
| void InertialSenseROS::publishGPS | ( | ) | 
Definition at line 545 of file inertial_sense_ros.cpp.
| void InertialSenseROS::reset_device | ( | ) | 
Definition at line 1000 of file inertial_sense_ros.cpp.
| ros::Time InertialSenseROS::ros_time_from_gtime | ( | const uint64_t | sec, | 
| double | subsec | ||
| ) | 
Definition at line 1094 of file inertial_sense_ros.cpp.
| ros::Time InertialSenseROS::ros_time_from_start_time | ( | const double | time | ) | 
ros_time_from_start_time
| time | - Time since boot up in seconds - Convert to GPS time of week by adding gps.towOffset | 
Definition at line 1054 of file inertial_sense_ros.cpp.
| ros::Time InertialSenseROS::ros_time_from_tow | ( | const double | tow | ) | 
ros_time_from_tow Get equivalent ros time from tow and internal week counter
| tow | Time of Week (seconds) | 
Definition at line 1084 of file inertial_sense_ros.cpp.
| 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
| week | Weeks since January 6th, 1980 | 
| timeOfWeek | Time of week (since Sunday morning) in seconds, GMT | 
Definition at line 1025 of file inertial_sense_ros.cpp.
| void InertialSenseROS::RTK_Misc_callback | ( | const gps_rtk_misc_t *const | msg | ) | 
Definition at line 634 of file inertial_sense_ros.cpp.
| void InertialSenseROS::RTK_Rel_callback | ( | const gps_rtk_rel_t *const | msg | ) | 
Definition at line 659 of file inertial_sense_ros.cpp.
| bool InertialSenseROS::set_current_position_as_refLLA | ( | std_srvs::Trigger::Request & | req, | 
| std_srvs::Trigger::Response & | res | ||
| ) | 
Definition at line 876 of file inertial_sense_ros.cpp.
| void InertialSenseROS::set_flash_config | ( | std::string | param_name, | 
| uint32_t | offset, | ||
| T | def | ||
| ) | 
Definition at line 311 of file inertial_sense_ros.cpp.
| void InertialSenseROS::set_navigation_dt_ms | ( | ) | 
Definition at line 180 of file inertial_sense_ros.cpp.
| bool InertialSenseROS::set_refLLA_to_value | ( | inertial_sense_ros::refLLAUpdate::Request & | req, | 
| inertial_sense_ros::refLLAUpdate::Response & | res | ||
| ) | 
Definition at line 913 of file inertial_sense_ros.cpp.
| void InertialSenseROS::set_vector_flash_config | ( | std::string | param_name, | 
| uint32_t | size, | ||
| uint32_t | offset | ||
| ) | 
Definition at line 296 of file inertial_sense_ros.cpp.
| void InertialSenseROS::start_log | ( | ) | 
Definition at line 137 of file inertial_sense_ros.cpp.
| void InertialSenseROS::strobe_in_time_callback | ( | const strobe_in_time_t *const | msg | ) | 
Definition at line 559 of file inertial_sense_ros.cpp.
| double InertialSenseROS::tow_from_ros_time | ( | const ros::Time & | rt | ) | 
Definition at line 1089 of file inertial_sense_ros.cpp.
| void InertialSenseROS::update | ( | ) | 
Definition at line 554 of file inertial_sense_ros.cpp.
| bool InertialSenseROS::update_firmware_srv_callback | ( | inertial_sense_ros::FirmwareUpdate::Request & | req, | 
| inertial_sense_ros::FirmwareUpdate::Response & | res | ||
| ) | 
Definition at line 1010 of file inertial_sense_ros.cpp.
| ros_stream_t InertialSenseROS::baro_ | 
Definition at line 137 of file inertial_sense_ros.h.
| int InertialSenseROS::baudrate_ | 
Definition at line 83 of file inertial_sense_ros.h.
| tf::TransformBroadcaster InertialSenseROS::br | 
Definition at line 104 of file inertial_sense_ros.h.
| float InertialSenseROS::diagnostic_ar_ratio_ | 
Definition at line 149 of file inertial_sense_ros.h.
| float InertialSenseROS::diagnostic_differential_age_ | 
Definition at line 149 of file inertial_sense_ros.h.
| float InertialSenseROS::diagnostic_heading_base_to_rover_ | 
Definition at line 149 of file inertial_sense_ros.h.
| ros_stream_t InertialSenseROS::diagnostics_ | 
Definition at line 146 of file inertial_sense_ros.h.
| ros::Timer InertialSenseROS::diagnostics_timer_ | 
Definition at line 148 of file inertial_sense_ros.h.
| ros_stream_t InertialSenseROS::dt_vel_ | 
Definition at line 140 of file inertial_sense_ros.h.
| double InertialSenseROS::ecef_[3] | 
Definition at line 213 of file inertial_sense_ros.h.
| ros::ServiceServer InertialSenseROS::firmware_update_srv_ | 
Definition at line 153 of file inertial_sense_ros.h.
| std::string InertialSenseROS::frame_id_ | 
Definition at line 87 of file inertial_sense_ros.h.
Definition at line 209 of file inertial_sense_ros.h.
| ros_stream_t InertialSenseROS::GPS_ | 
Definition at line 117 of file inertial_sense_ros.h.
| ros_stream_t InertialSenseROS::GPS_eph_ | 
Definition at line 119 of file inertial_sense_ros.h.
| ros_stream_t InertialSenseROS::GPS_info_ | 
Definition at line 131 of file inertial_sense_ros.h.
| inertial_sense_ros::GPSInfo InertialSenseROS::gps_info_msg | 
Definition at line 218 of file inertial_sense_ros.h.
| inertial_sense_ros::GPS InertialSenseROS::gps_msg | 
Definition at line 216 of file inertial_sense_ros.h.
| ros_stream_t InertialSenseROS::GPS_obs_ | 
Definition at line 118 of file inertial_sense_ros.h.
| double InertialSenseROS::GPS_towOffset_ = 0 | 
Definition at line 204 of file inertial_sense_ros.h.
| geometry_msgs::Vector3Stamped InertialSenseROS::gps_velEcef | 
Definition at line 217 of file inertial_sense_ros.h.
| uint64_t InertialSenseROS::GPS_week_ = 0 | 
Definition at line 206 of file inertial_sense_ros.h.
| sensor_msgs::Imu InertialSenseROS::imu1_msg | 
Definition at line 214 of file inertial_sense_ros.h.
| sensor_msgs::Imu InertialSenseROS::imu2_msg | 
Definition at line 214 of file inertial_sense_ros.h.
| ros_stream_t InertialSenseROS::IMU_ | 
Definition at line 114 of file inertial_sense_ros.h.
| bool InertialSenseROS::initialized_ | 
Definition at line 84 of file inertial_sense_ros.h.
| ros_stream_t InertialSenseROS::INL2_states_ | 
Definition at line 102 of file inertial_sense_ros.h.
| inertial_sense_ros::INL2States InertialSenseROS::inl2_states_msg | 
Definition at line 219 of file inertial_sense_ros.h.
| ros_stream_t InertialSenseROS::INS_ | 
Definition at line 97 of file inertial_sense_ros.h.
| double InertialSenseROS::INS_local_offset_ = 0.0 | 
Definition at line 208 of file inertial_sense_ros.h.
| InertialSense InertialSenseROS::IS_ | 
Definition at line 225 of file inertial_sense_ros.h.
| ros::Time InertialSenseROS::last_obs_time_ | 
Definition at line 129 of file inertial_sense_ros.h.
| double InertialSenseROS::lla_[3] | 
Definition at line 212 of file inertial_sense_ros.h.
| bool InertialSenseROS::log_enabled_ | 
Definition at line 85 of file inertial_sense_ros.h.
| int InertialSenseROS::LTCF | 
Definition at line 107 of file inertial_sense_ros.h.
| enum { ... } InertialSenseROS::ltcf | 
| ros_stream_t InertialSenseROS::mag_ | 
Definition at line 134 of file inertial_sense_ros.h.
| ros::ServiceServer InertialSenseROS::mag_cal_srv_ | 
Definition at line 151 of file inertial_sense_ros.h.
| ros::ServiceServer InertialSenseROS::multi_mag_cal_srv_ | 
Definition at line 152 of file inertial_sense_ros.h.
| ros::NodeHandle InertialSenseROS::nh_ | 
Definition at line 221 of file inertial_sense_ros.h.
| ros::NodeHandle InertialSenseROS::nh_private_ | 
Definition at line 222 of file inertial_sense_ros.h.
| ros::Timer InertialSenseROS::obs_bundle_timer_ | 
Definition at line 128 of file inertial_sense_ros.h.
| inertial_sense_ros::GNSSObsVec InertialSenseROS::obs_Vec_ | 
Definition at line 127 of file inertial_sense_ros.h.
| nav_msgs::Odometry InertialSenseROS::odom_msg | 
Definition at line 215 of file inertial_sense_ros.h.
| std::string InertialSenseROS::port_ | 
Definition at line 82 of file inertial_sense_ros.h.
| bool InertialSenseROS::publishTf | 
Definition at line 105 of file inertial_sense_ros.h.
| ros::ServiceServer InertialSenseROS::refLLA_set_current_srv_ | 
Definition at line 154 of file inertial_sense_ros.h.
| ros::ServiceServer InertialSenseROS::refLLA_set_value_srv_ | 
Definition at line 155 of file inertial_sense_ros.h.
| ros_stream_t InertialSenseROS::RTK_ | 
Definition at line 172 of file inertial_sense_ros.h.
| rtk_state_t InertialSenseROS::RTK_state_ = RTK_NONE | 
Definition at line 171 of file inertial_sense_ros.h.
| ros::Publisher InertialSenseROS::strobe_pub_ | 
Definition at line 143 of file inertial_sense_ros.h.
| tf::Transform InertialSenseROS::transform | 
Definition at line 106 of file inertial_sense_ros.h.