Classes | Typedefs | Enumerations | Functions | Variables
novatel_oem7_driver Namespace Reference

Classes

class  ALIGNHandler
 
class  BESTPOSHandler
 
class  INSHandler
 
class  MessageHandler
 
class  NMEAHandler
 
class  Oem7ConfigNodelet
 
class  Oem7DebugFile
 
class  Oem7LogNodelet
 
class  Oem7MessageDecoder
 
class  Oem7MessageDecoderIf
 
class  Oem7MessageDecoderUserIf
 
class  Oem7MessageHandlerIf
 
class  Oem7MessageNodelet
 
class  Oem7Receiver
 
class  Oem7ReceiverFile
 
class  Oem7ReceiverIf
 
class  Oem7ReceiverNet
 
class  Oem7ReceiverPort
 
class  Oem7ReceiverTcp
 
class  Oem7ReceiverUdp
 
class  Oem7RosPublisher
 
class  RawMsgAdapter
 
class  ReceiverStatusHandler
 
class  TimeHandler
 

Typedefs

typedef int imu_rate_t
 IMU message output rate. Refer to INSCONFIG in the OEM7 manual.s. More...
 
typedef uint32_t oem7_bool_t
 
typedef char oem7_char_t
 
typedef uint32_t oem7_enum_t
 
typedef uint8_t oem7_hex_t
 
typedef std::vector< std::string > str_vector_t
 

Enumerations

enum  GPSReferenceTimeStatus { GPS_REFTIME_STATUS_UNKNOWN = 20 }
 
enum  oem7_imu_type_t {
  IMU_TYPE_UNKNOWN = 0, IMU_TYPE_HG1700_AG11 = 1, IMU_TYPE_HG1700_AG17 = 4, IMU_TYPE_HG1900_CA29 = 5,
  IMU_TYPE_LN200 = 8, IMU_TYPE_HG1700_AG58 = 11, IMU_TYPE_HG1700_AG62 = 12, IMU_TYPE_IMAR_FSAS = 13,
  IMU_TYPE_KVH_COTS = 16, IMU_TYPE_HG1930_AA99 = 20, IMU_TYPE_ISA100C = 26, IMU_TYPE_HG1900_CA50 = 27,
  IMU_TYPE_HG1930_CA50 = 28, IMU_TYPE_ADIS16488 = 31, IMU_TYPE_STIM300 = 32, IMU_TYPE_KVH_1750 = 33,
  IMU_TYPE_EPSON_G320 = 41, IMU_TYPE_LITEF_MICROIMU = 52, IMU_TYPE_STIM_300D = 56, IMU_TYPE_HG4930_AN01 = 58,
  IMU_TYPE_EPSON_G370 = 61, IMU_TYPE_EPSON_G320_200HZ = 62, IMU_TYPE_HG4930_AN04 = 68, IMU_TYPE_HG4930_AN04_400HZ = 69
}
 IMUs supported on OEM7 products; refer to INSCONFIG in the OEM7 manual. More...
 
enum  ValueRelation { REL_GT, REL_LT, REL_EQ }
 

Functions

struct __attribute__ ((packed)) Oem7MessageCommonHeaderMem
 
double arcsecondsToRadians (double arcsecs)
 
double computeHorizontalError (double lat_stdev, double lon_stdev)
 
double computeSphericalError (double lat_stdev, double lon_stdev, double hgt_stdev)
 
double computeVerticalError (double hgt_stdev)
 
double degreesToRadians (double degrees)
 
double feetToMeters (double feet)
 
double Get3DPositionError (double lat_stdev, double lon_stdev, double hgt_stdev)
 
size_t Get_INSCONFIG_NumRotations (const INSCONFIG_FixedMem *insconfig)
 
size_t Get_INSCONFIG_NumTranslations (const INSCONFIG_FixedMem *insconfig)
 
const INSCONFIG_RotationMem * Get_INSCONFIG_Rotation (const INSCONFIG_FixedMem *insconfig, size_t idx)
 
const INSCONFIG_TranslationMem * Get_INSCONFIG_Translation (const INSCONFIG_FixedMem *insconfig, size_t idx)
 
size_t Get_PSRDOP2_NumSystems (const PSRDOP2_FixedMem *psrdop2)
 
const PSRDOP2_SystemMem * Get_PSRDOP2_System (const PSRDOP2_FixedMem *psrdop2, size_t idx)
 
void get_status_info (uint32_t bitmask, const str_vector_t &str_map, str_vector_t &str_list, std::vector< uint8_t > &bit_list)
 
void GetDOPFromPSRDOP2 (const Oem7RawMessageIf::ConstPtr &msg, uint32_t system_to_use, double &gdop, double &pdop, double &hdop, double &vdop, double &tdop)
 
bool getImuRawScaleFactors (oem7_imu_type_t imu_type, imu_rate_t imu_rate, double &gyro_scale, double &acc_scale)
 
uint32_t GetNextMsgSequenceNumber ()
 
void getOem7Header (const Oem7RawMessageIf::ConstPtr &raw_msg, novatel_oem7_msgs::Oem7Header::Type &hdr)
 
int getOem7MessageId (const std::string &msg_name)
 
const std::string & getOem7MessageName (int msg_id)
 
ValueRelation GetOem7MessageTimeRelation (novatel_oem7_msgs::Oem7Header msg_hdr_1, novatel_oem7_msgs::Oem7Header msg_hdr_2)
 
void getOem7ShortHeader (const Oem7RawMessageIf::ConstPtr &raw_msg, novatel_oem7_msgs::Oem7Header::Type &hdr)
 
uint8_t GpsFixCovTypeToNavSatFixCovType (uint8_t covariance_type)
 
uint8_t GpsStatusToNavSatStatus (int16_t gps_status)
 
static int64_t GPSTimeToMsec (uint32_t gps_week_no, uint32_t week_msec)
 
static int64_t GPSTimeToMsec (const novatel_oem7_msgs::Oem7Header &hdr)
 
void initializeOem7MessageUtil (ros::NodeHandle &nh)
 
bool IsINSSolutionAvailable (const novatel_oem7_msgs::InertialSolutionStatus &status)
 
bool isNMEAMessage (const Oem7RawMessageIf::ConstPtr &raw_msg)
 
double MakeGpsTime_Seconds (uint16_t gps_week, uint32_t gps_milliseconds)
 
template<class T >
void MakeROSMessage (const Oem7RawMessageIf::ConstPtr &msg, boost::shared_ptr< T > &rosmsg)
 
template void MakeROSMessage (const Oem7RawMessageIf::ConstPtr &, boost::shared_ptr< novatel_oem7_msgs::BESTGNSSPOS > &)
 
template void MakeROSMessage (const Oem7RawMessageIf::ConstPtr &, boost::shared_ptr< novatel_oem7_msgs::BESTPOS > &)
 
template void MakeROSMessage (const Oem7RawMessageIf::ConstPtr &, boost::shared_ptr< novatel_oem7_msgs::BESTVEL > &)
 
template void MakeROSMessage (const Oem7RawMessageIf::ConstPtr &, boost::shared_ptr< novatel_oem7_msgs::BESTUTM > &)
 
template void MakeROSMessage (const Oem7RawMessageIf::ConstPtr &, boost::shared_ptr< novatel_oem7_msgs::PPPPOS > &)
 
template void MakeROSMessage (const Oem7RawMessageIf::ConstPtr &, boost::shared_ptr< novatel_oem7_msgs::TERRASTARINFO > &)
 
template void MakeROSMessage (const Oem7RawMessageIf::ConstPtr &, boost::shared_ptr< novatel_oem7_msgs::TERRASTARSTATUS > &)
 
template void MakeROSMessage (const Oem7RawMessageIf::ConstPtr &, boost::shared_ptr< novatel_oem7_msgs::INSPVA > &)
 
template void MakeROSMessage (const Oem7RawMessageIf::ConstPtr &, boost::shared_ptr< novatel_oem7_msgs::INSPVAX > &)
 
template void MakeROSMessage (const Oem7RawMessageIf::ConstPtr &, boost::shared_ptr< novatel_oem7_msgs::INSCONFIG > &)
 
template void MakeROSMessage (const Oem7RawMessageIf::ConstPtr &, boost::shared_ptr< novatel_oem7_msgs::INSSTDEV > &)
 
template void MakeROSMessage (const Oem7RawMessageIf::ConstPtr &, boost::shared_ptr< novatel_oem7_msgs::CORRIMU > &)
 
template void MakeROSMessage (const Oem7RawMessageIf::ConstPtr &, boost::shared_ptr< novatel_oem7_msgs::TIME > &)
 
template void MakeROSMessage (const Oem7RawMessageIf::ConstPtr &, boost::shared_ptr< novatel_oem7_msgs::RXSTATUS > &)
 
template<>
void MakeROSMessage< novatel_oem7_msgs::BESTGNSSPOS > (const Oem7RawMessageIf::ConstPtr &msg, boost::shared_ptr< novatel_oem7_msgs::BESTGNSSPOS > &bestgnsspos)
 
template<>
void MakeROSMessage< novatel_oem7_msgs::BESTPOS > (const Oem7RawMessageIf::ConstPtr &msg, boost::shared_ptr< novatel_oem7_msgs::BESTPOS > &bestpos)
 
template<>
void MakeROSMessage< novatel_oem7_msgs::BESTUTM > (const Oem7RawMessageIf::ConstPtr &msg, boost::shared_ptr< novatel_oem7_msgs::BESTUTM > &bestutm)
 
template<>
void MakeROSMessage< novatel_oem7_msgs::BESTVEL > (const Oem7RawMessageIf::ConstPtr &msg, boost::shared_ptr< novatel_oem7_msgs::BESTVEL > &bestvel)
 
template<>
void MakeROSMessage< novatel_oem7_msgs::CORRIMU > (const Oem7RawMessageIf::ConstPtr &msg, boost::shared_ptr< novatel_oem7_msgs::CORRIMU > &corrimu)
 
template<>
void MakeROSMessage< novatel_oem7_msgs::HEADING2 > (const Oem7RawMessageIf::ConstPtr &msg, boost::shared_ptr< novatel_oem7_msgs::HEADING2 > &heading2)
 
template<>
void MakeROSMessage< novatel_oem7_msgs::INSCONFIG > (const Oem7RawMessageIf::ConstPtr &msg, boost::shared_ptr< novatel_oem7_msgs::INSCONFIG > &insconfig)
 
template<>
void MakeROSMessage< novatel_oem7_msgs::INSPVA > (const Oem7RawMessageIf::ConstPtr &msg, boost::shared_ptr< novatel_oem7_msgs::INSPVA > &pva)
 
template<>
void MakeROSMessage< novatel_oem7_msgs::INSPVAX > (const Oem7RawMessageIf::ConstPtr &msg, boost::shared_ptr< novatel_oem7_msgs::INSPVAX > &inspvax)
 
template<>
void MakeROSMessage< novatel_oem7_msgs::INSSTDEV > (const Oem7RawMessageIf::ConstPtr &msg, boost::shared_ptr< novatel_oem7_msgs::INSSTDEV > &insstdev)
 
template<>
void MakeROSMessage< novatel_oem7_msgs::PPPPOS > (const Oem7RawMessageIf::ConstPtr &msg, boost::shared_ptr< novatel_oem7_msgs::PPPPOS > &ppppos)
 
template<>
void MakeROSMessage< novatel_oem7_msgs::RXSTATUS > (const Oem7RawMessageIf::ConstPtr &msg, boost::shared_ptr< novatel_oem7_msgs::RXSTATUS > &rxstatus)
 
template<>
void MakeROSMessage< novatel_oem7_msgs::TERRASTARINFO > (const Oem7RawMessageIf::ConstPtr &msg, boost::shared_ptr< novatel_oem7_msgs::TERRASTARINFO > &terrastarinfo)
 
template<>
void MakeROSMessage< novatel_oem7_msgs::TERRASTARSTATUS > (const Oem7RawMessageIf::ConstPtr &msg, boost::shared_ptr< novatel_oem7_msgs::TERRASTARSTATUS > &terrastarstatus)
 
template<>
void MakeROSMessage< novatel_oem7_msgs::TIME > (const Oem7RawMessageIf::ConstPtr &msg, boost::shared_ptr< novatel_oem7_msgs::TIME > &time)
 
uint16_t NavSatStatusService (novatel_oem7_msgs::BESTPOS::Ptr bestpos)
 
static const std::vector< int > OEM7_NMEA_MSGIDS ({ GLMLA_OEM7_MSGID, GPALM_OEM7_MSGID, GPGGA_OEM7_MSGID, GPGGALONG_OEM7_MSGID, GPGLL_OEM7_MSGID, GPGRS_OEM7_MSGID, GPGSA_OEM7_MSGID, GPGST_OEM7_MSGID, GPGSV_OEM7_MSGID, GPHDT_OEM7_MSGID, GPHDTDUALANTENNA_MSGID, GPRMB_OEM7_MSGID, GPRMC_OEM7_MSGID, GPVTG_OEM7_MSGID, GPZDA_OEM7_MSGID })
 
double radiansToDegrees (double radians)
 
void SetOem7Header (const Oem7RawMessageIf::ConstPtr &msg, const std::string &name, novatel_oem7_msgs::Oem7Header::Type &oem7_hdr)
 
void SetOem7ShortHeader (const Oem7RawMessageIf::ConstPtr &msg, const std::string &name, novatel_oem7_msgs::Oem7Header::Type &oem7_hdr)
 
template<typename T >
void SetROSHeader (const std::string &frame_id, boost::shared_ptr< T > &msg)
 
int16_t ToROSGPSStatus (const novatel_oem7_msgs::BESTPOS::Ptr bestpos)
 
void UTMPointFromGnss (geometry_msgs::Point &pt, double lat, double lon, double hgt)
 

Variables

const str_vector_t AUX1_STATUS_STRS
 
const str_vector_t AUX2_STATUS_STRS
 
const str_vector_t AUX3_STATUS_STRS
 
const str_vector_t AUX4_STATUS_STRS
 
const int BESTGNSSPOS_OEM7_MSGID = 1429
 
const int BESTPOS_OEM7_MSGID = 42
 
const int BESTUTM_OEM7_MSGID = 726
 
const int BESTVEL_OEM7_MSGID = 99
 
const int CORRIMUS_OEM7_MSGID = 2264
 
const double DATA_NOT_AVAILABLE = -1.0
 Used to initialized unpopulated fields. More...
 
const int GLMLA_OEM7_MSGID = 859
 
const int GPALM_OEM7_MSGID = 217
 
const int GPGGA_OEM7_MSGID = 218
 
const int GPGGALONG_OEM7_MSGID = 521
 
const int GPGLL_OEM7_MSGID = 219
 
const int GPGRS_OEM7_MSGID = 220
 
const int GPGSA_OEM7_MSGID = 221
 
const int GPGST_OEM7_MSGID = 222
 
const int GPGSV_OEM7_MSGID = 223
 
const int GPHDT_OEM7_MSGID = 1045
 
const int GPHDTDUALANTENNA_MSGID = 2045
 
const int GPRMB_OEM7_MSGID = 224
 
const int GPRMC_OEM7_MSGID = 225
 
const int GPVTG_OEM7_MSGID = 226
 
const int GPZDA_OEM7_MSGID = 227
 
const int HEADING2_OEM7_MSGID = 1335
 
const int IMURATECORRIMUS_OEM7_MSGID = 1362
 
const int INSCONFIG_OEM7_MSGID = 1945
 
const int INSPVAS_OEM7_MSGID = 508
 
const int INSPVAX_OEM7_MSGID = 1465
 
const int INSSTDEV_OEM7_MSGID = 2051
 
const std::size_t OEM7_BINARY_MSG_HDR_LEN = sizeof(Oem7MessageHeaderMem)
 
const std::size_t OEM7_BINARY_MSG_SHORT_HDR_LEN = sizeof(Oem7MessgeShortHeaderMem)
 
const double ONE_G = 9.80665
 
const int PPPPOS_OEM7_MSGID = 1538
 
const int PSRDOP2_OEM7_MSGID = 1163
 
const int RAWIMUSX_OEM7_MSGID = 1462
 
const str_vector_t RECEIVER_ERROR_STRS
 
const str_vector_t RECEIVER_STATUS_STRS
 
const int RXSTATUS_OEM7_MSGID = 93
 
const int TERRASTARINFO_OEM7_MSGID = 1719
 
const int TERRASTARSTATUS_OEM7_MSGID = 1729
 
const int TIME_OEM7_MSGID = 101
 

Typedef Documentation

◆ imu_rate_t

IMU message output rate. Refer to INSCONFIG in the OEM7 manual.s.

Definition at line 59 of file oem7_imu.hpp.

◆ oem7_bool_t

Definition at line 43 of file oem7_messages.h.

◆ oem7_char_t

Definition at line 45 of file oem7_messages.h.

◆ oem7_enum_t

Definition at line 42 of file oem7_messages.h.

◆ oem7_hex_t

Definition at line 44 of file oem7_messages.h.

◆ str_vector_t

typedef std::vector<std::string> novatel_oem7_driver::str_vector_t

Definition at line 40 of file receiverstatus_handler.cpp.

Enumeration Type Documentation

◆ GPSReferenceTimeStatus

Enumerator
GPS_REFTIME_STATUS_UNKNOWN 

Definition at line 42 of file oem7_message_util.cpp.

◆ oem7_imu_type_t

IMUs supported on OEM7 products; refer to INSCONFIG in the OEM7 manual.

Enumerator
IMU_TYPE_UNKNOWN 
IMU_TYPE_HG1700_AG11 
IMU_TYPE_HG1700_AG17 
IMU_TYPE_HG1900_CA29 
IMU_TYPE_LN200 
IMU_TYPE_HG1700_AG58 
IMU_TYPE_HG1700_AG62 
IMU_TYPE_IMAR_FSAS 
IMU_TYPE_KVH_COTS 
IMU_TYPE_HG1930_AA99 
IMU_TYPE_ISA100C 
IMU_TYPE_HG1900_CA50 
IMU_TYPE_HG1930_CA50 
IMU_TYPE_ADIS16488 
IMU_TYPE_STIM300 
IMU_TYPE_KVH_1750 
IMU_TYPE_EPSON_G320 
IMU_TYPE_LITEF_MICROIMU 
IMU_TYPE_STIM_300D 
IMU_TYPE_HG4930_AN01 
IMU_TYPE_EPSON_G370 
IMU_TYPE_EPSON_G320_200HZ 
IMU_TYPE_HG4930_AN04 
IMU_TYPE_HG4930_AN04_400HZ 

Definition at line 29 of file oem7_imu.hpp.

◆ ValueRelation

Enumerator
REL_GT 
REL_LT 
REL_EQ 

Definition at line 209 of file bestpos_handler.cpp.

Function Documentation

◆ __attribute__()

struct novatel_oem7_driver::__attribute__ ( (packed)  )

Definition at line 51 of file oem7_messages.h.

◆ arcsecondsToRadians()

double novatel_oem7_driver::arcsecondsToRadians ( double  arcsecs)
inline
Returns
arcseconds

Definition at line 38 of file oem7_imu.cpp.

◆ computeHorizontalError()

double novatel_oem7_driver::computeHorizontalError ( double  lat_stdev,
double  lon_stdev 
)

Definition at line 108 of file bestpos_handler.cpp.

◆ computeSphericalError()

double novatel_oem7_driver::computeSphericalError ( double  lat_stdev,
double  lon_stdev,
double  hgt_stdev 
)

Definition at line 129 of file bestpos_handler.cpp.

◆ computeVerticalError()

double novatel_oem7_driver::computeVerticalError ( double  hgt_stdev)

Definition at line 120 of file bestpos_handler.cpp.

◆ degreesToRadians()

double novatel_oem7_driver::degreesToRadians ( double  degrees)
inline
Returns
degrees

Definition at line 84 of file bestpos_handler.cpp.

◆ feetToMeters()

double novatel_oem7_driver::feetToMeters ( double  feet)
inline
Returns
meters

Definition at line 54 of file oem7_imu.cpp.

◆ Get3DPositionError()

double novatel_oem7_driver::Get3DPositionError ( double  lat_stdev,
double  lon_stdev,
double  hgt_stdev 
)

Compute a single 3D standard deviation from individual deviations. This can be used as a '3D error'.

Definition at line 94 of file bestpos_handler.cpp.

◆ Get_INSCONFIG_NumRotations()

size_t novatel_oem7_driver::Get_INSCONFIG_NumRotations ( const INSCONFIG_FixedMem *  insconfig)

Definition at line 135 of file oem7_message_util.cpp.

◆ Get_INSCONFIG_NumTranslations()

size_t novatel_oem7_driver::Get_INSCONFIG_NumTranslations ( const INSCONFIG_FixedMem *  insconfig)

Definition at line 119 of file oem7_message_util.cpp.

◆ Get_INSCONFIG_Rotation()

const INSCONFIG_RotationMem * novatel_oem7_driver::Get_INSCONFIG_Rotation ( const INSCONFIG_FixedMem *  insconfig,
size_t  idx 
)

Definition at line 146 of file oem7_message_util.cpp.

◆ Get_INSCONFIG_Translation()

const INSCONFIG_TranslationMem * novatel_oem7_driver::Get_INSCONFIG_Translation ( const INSCONFIG_FixedMem *  insconfig,
size_t  idx 
)

Definition at line 125 of file oem7_message_util.cpp.

◆ Get_PSRDOP2_NumSystems()

size_t novatel_oem7_driver::Get_PSRDOP2_NumSystems ( const PSRDOP2_FixedMem *  psrdop2)

Definition at line 159 of file oem7_message_util.cpp.

◆ Get_PSRDOP2_System()

const PSRDOP2_SystemMem * novatel_oem7_driver::Get_PSRDOP2_System ( const PSRDOP2_FixedMem *  psrdop2,
size_t  idx 
)

Definition at line 165 of file oem7_message_util.cpp.

◆ get_status_info()

void novatel_oem7_driver::get_status_info ( uint32_t  bitmask,
const str_vector_t str_map,
str_vector_t str_list,
std::vector< uint8_t > &  bit_list 
)

Definition at line 266 of file receiverstatus_handler.cpp.

◆ GetDOPFromPSRDOP2()

void novatel_oem7_driver::GetDOPFromPSRDOP2 ( const Oem7RawMessageIf::ConstPtr &  msg,
uint32_t  system_to_use,
double &  gdop,
double &  pdop,
double &  hdop,
double &  vdop,
double &  tdop 
)

Definition at line 705 of file oem7_ros_messages.cpp.

◆ getImuRawScaleFactors()

bool novatel_oem7_driver::getImuRawScaleFactors ( oem7_imu_type_t  imu_type,
imu_rate_t  imu_rate,
double &  gyro_scale,
double &  acc_scale 
)

Obtain scaling factors for raw IMU output (as reported by RAWIMUS etc). Refer to RAWIMUSX documentation.

Returns
false if the IMU is not supported. This means that the code was not updated to reflect new OEM7 product release.
Parameters
imu_typeIMU type.
imu_rateIMU rate; needed because some IMUs report instantaneous rate.
gyro_scaleGyroscope scale factor
acc_scaleAccelerometer scale factor

Definition at line 61 of file oem7_imu.cpp.

◆ GetNextMsgSequenceNumber()

uint32_t novatel_oem7_driver::GetNextMsgSequenceNumber ( )

Generate ROS message sequence number

Returns
sequence number

Definition at line 63 of file oem7_ros_messages.cpp.

◆ getOem7Header()

void novatel_oem7_driver::getOem7Header ( const Oem7RawMessageIf::ConstPtr &  raw_msg,
novatel_oem7_msgs::Oem7Header::Type &  hdr 
)

Populates Oem7 Binary message header from raw message

Gets Oem7 Binary message header from raw message

Parameters
[in]raw_msgRaw binary message
[out]hdrOem7 Message Header

Definition at line 78 of file oem7_message_util.cpp.

◆ getOem7MessageId()

int novatel_oem7_driver::getOem7MessageId ( const std::string &  msg_name)

Definition at line 63 of file oem7_message_util.cpp.

◆ getOem7MessageName()

const std::string & novatel_oem7_driver::getOem7MessageName ( int  msg_id)

Definition at line 68 of file oem7_message_util.cpp.

◆ GetOem7MessageTimeRelation()

ValueRelation novatel_oem7_driver::GetOem7MessageTimeRelation ( novatel_oem7_msgs::Oem7Header  msg_hdr_1,
novatel_oem7_msgs::Oem7Header  msg_hdr_2 
)

Definition at line 221 of file bestpos_handler.cpp.

◆ getOem7ShortHeader()

void novatel_oem7_driver::getOem7ShortHeader ( const Oem7RawMessageIf::ConstPtr &  raw_msg,
novatel_oem7_msgs::Oem7Header::Type &  hdr 
)

Populates Oem7 Binary message header from 'short' raw message

Parameters
[in]raw_msgRaw binary message
[out]hdrOem7 Message Header

Definition at line 93 of file oem7_message_util.cpp.

◆ GpsFixCovTypeToNavSatFixCovType()

uint8_t novatel_oem7_driver::GpsFixCovTypeToNavSatFixCovType ( uint8_t  covariance_type)

Definition at line 246 of file bestpos_handler.cpp.

◆ GpsStatusToNavSatStatus()

uint8_t novatel_oem7_driver::GpsStatusToNavSatStatus ( int16_t  gps_status)

Definition at line 268 of file bestpos_handler.cpp.

◆ GPSTimeToMsec() [1/2]

static int64_t novatel_oem7_driver::GPSTimeToMsec ( uint32_t  gps_week_no,
uint32_t  week_msec 
)
inlinestatic

Definition at line 34 of file oem7_driver_util.hpp.

◆ GPSTimeToMsec() [2/2]

static int64_t novatel_oem7_driver::GPSTimeToMsec ( const novatel_oem7_msgs::Oem7Header &  hdr)
inlinestatic

Definition at line 44 of file oem7_driver_util.hpp.

◆ initializeOem7MessageUtil()

void novatel_oem7_driver::initializeOem7MessageUtil ( ros::NodeHandle nh)

Definition at line 47 of file oem7_message_util.cpp.

◆ IsINSSolutionAvailable()

bool novatel_oem7_driver::IsINSSolutionAvailable ( const novatel_oem7_msgs::InertialSolutionStatus &  status)

Returns true if INS Solution is available

Definition at line 340 of file bestpos_handler.cpp.

◆ isNMEAMessage()

bool novatel_oem7_driver::isNMEAMessage ( const Oem7RawMessageIf::ConstPtr &  raw_msg)

Determines if this is NMEA0183 Oem7 message

Definition at line 112 of file oem7_message_util.cpp.

◆ MakeGpsTime_Seconds()

double novatel_oem7_driver::MakeGpsTime_Seconds ( uint16_t  gps_week,
uint32_t  gps_milliseconds 
)

Definition at line 196 of file bestpos_handler.cpp.

◆ MakeROSMessage() [1/15]

template<class T >
void novatel_oem7_driver::MakeROSMessage ( const Oem7RawMessageIf::ConstPtr &  msg,
boost::shared_ptr< T > &  rosmsg 
)

◆ MakeROSMessage() [2/15]

template void novatel_oem7_driver::MakeROSMessage ( const Oem7RawMessageIf::ConstPtr &  ,
boost::shared_ptr< novatel_oem7_msgs::BESTGNSSPOS > &   
)

◆ MakeROSMessage() [3/15]

template void novatel_oem7_driver::MakeROSMessage ( const Oem7RawMessageIf::ConstPtr &  ,
boost::shared_ptr< novatel_oem7_msgs::BESTPOS > &   
)

◆ MakeROSMessage() [4/15]

template void novatel_oem7_driver::MakeROSMessage ( const Oem7RawMessageIf::ConstPtr &  ,
boost::shared_ptr< novatel_oem7_msgs::BESTVEL > &   
)

◆ MakeROSMessage() [5/15]

template void novatel_oem7_driver::MakeROSMessage ( const Oem7RawMessageIf::ConstPtr &  ,
boost::shared_ptr< novatel_oem7_msgs::BESTUTM > &   
)

◆ MakeROSMessage() [6/15]

template void novatel_oem7_driver::MakeROSMessage ( const Oem7RawMessageIf::ConstPtr &  ,
boost::shared_ptr< novatel_oem7_msgs::PPPPOS > &   
)

◆ MakeROSMessage() [7/15]

template void novatel_oem7_driver::MakeROSMessage ( const Oem7RawMessageIf::ConstPtr &  ,
boost::shared_ptr< novatel_oem7_msgs::TERRASTARINFO > &   
)

◆ MakeROSMessage() [8/15]

template void novatel_oem7_driver::MakeROSMessage ( const Oem7RawMessageIf::ConstPtr &  ,
boost::shared_ptr< novatel_oem7_msgs::TERRASTARSTATUS > &   
)

◆ MakeROSMessage() [9/15]

template void novatel_oem7_driver::MakeROSMessage ( const Oem7RawMessageIf::ConstPtr &  ,
boost::shared_ptr< novatel_oem7_msgs::INSPVA > &   
)

◆ MakeROSMessage() [10/15]

template void novatel_oem7_driver::MakeROSMessage ( const Oem7RawMessageIf::ConstPtr &  ,
boost::shared_ptr< novatel_oem7_msgs::INSPVAX > &   
)

◆ MakeROSMessage() [11/15]

template void novatel_oem7_driver::MakeROSMessage ( const Oem7RawMessageIf::ConstPtr &  ,
boost::shared_ptr< novatel_oem7_msgs::INSCONFIG > &   
)

◆ MakeROSMessage() [12/15]

template void novatel_oem7_driver::MakeROSMessage ( const Oem7RawMessageIf::ConstPtr &  ,
boost::shared_ptr< novatel_oem7_msgs::INSSTDEV > &   
)

◆ MakeROSMessage() [13/15]

template void novatel_oem7_driver::MakeROSMessage ( const Oem7RawMessageIf::ConstPtr &  ,
boost::shared_ptr< novatel_oem7_msgs::CORRIMU > &   
)

◆ MakeROSMessage() [14/15]

template void novatel_oem7_driver::MakeROSMessage ( const Oem7RawMessageIf::ConstPtr &  ,
boost::shared_ptr< novatel_oem7_msgs::TIME > &   
)

◆ MakeROSMessage() [15/15]

template void novatel_oem7_driver::MakeROSMessage ( const Oem7RawMessageIf::ConstPtr &  ,
boost::shared_ptr< novatel_oem7_msgs::RXSTATUS > &   
)

◆ MakeROSMessage< novatel_oem7_msgs::BESTGNSSPOS >()

template<>
void novatel_oem7_driver::MakeROSMessage< novatel_oem7_msgs::BESTGNSSPOS > ( const Oem7RawMessageIf::ConstPtr &  msg,
boost::shared_ptr< novatel_oem7_msgs::BESTGNSSPOS > &  bestgnsspos 
)

Definition at line 136 of file oem7_ros_messages.cpp.

◆ MakeROSMessage< novatel_oem7_msgs::BESTPOS >()

template<>
void novatel_oem7_driver::MakeROSMessage< novatel_oem7_msgs::BESTPOS > ( const Oem7RawMessageIf::ConstPtr &  msg,
boost::shared_ptr< novatel_oem7_msgs::BESTPOS > &  bestpos 
)

Definition at line 173 of file oem7_ros_messages.cpp.

◆ MakeROSMessage< novatel_oem7_msgs::BESTUTM >()

template<>
void novatel_oem7_driver::MakeROSMessage< novatel_oem7_msgs::BESTUTM > ( const Oem7RawMessageIf::ConstPtr &  msg,
boost::shared_ptr< novatel_oem7_msgs::BESTUTM > &  bestutm 
)

Definition at line 234 of file oem7_ros_messages.cpp.

◆ MakeROSMessage< novatel_oem7_msgs::BESTVEL >()

template<>
void novatel_oem7_driver::MakeROSMessage< novatel_oem7_msgs::BESTVEL > ( const Oem7RawMessageIf::ConstPtr &  msg,
boost::shared_ptr< novatel_oem7_msgs::BESTVEL > &  bestvel 
)

Definition at line 210 of file oem7_ros_messages.cpp.

◆ MakeROSMessage< novatel_oem7_msgs::CORRIMU >()

template<>
void novatel_oem7_driver::MakeROSMessage< novatel_oem7_msgs::CORRIMU > ( const Oem7RawMessageIf::ConstPtr &  msg,
boost::shared_ptr< novatel_oem7_msgs::CORRIMU > &  corrimu 
)

Definition at line 537 of file oem7_ros_messages.cpp.

◆ MakeROSMessage< novatel_oem7_msgs::HEADING2 >()

template<>
void novatel_oem7_driver::MakeROSMessage< novatel_oem7_msgs::HEADING2 > ( const Oem7RawMessageIf::ConstPtr &  msg,
boost::shared_ptr< novatel_oem7_msgs::HEADING2 > &  heading2 
)

Definition at line 102 of file oem7_ros_messages.cpp.

◆ MakeROSMessage< novatel_oem7_msgs::INSCONFIG >()

template<>
void novatel_oem7_driver::MakeROSMessage< novatel_oem7_msgs::INSCONFIG > ( const Oem7RawMessageIf::ConstPtr &  msg,
boost::shared_ptr< novatel_oem7_msgs::INSCONFIG > &  insconfig 
)

Definition at line 383 of file oem7_ros_messages.cpp.

◆ MakeROSMessage< novatel_oem7_msgs::INSPVA >()

template<>
void novatel_oem7_driver::MakeROSMessage< novatel_oem7_msgs::INSPVA > ( const Oem7RawMessageIf::ConstPtr &  msg,
boost::shared_ptr< novatel_oem7_msgs::INSPVA > &  pva 
)

Definition at line 356 of file oem7_ros_messages.cpp.

◆ MakeROSMessage< novatel_oem7_msgs::INSPVAX >()

template<>
void novatel_oem7_driver::MakeROSMessage< novatel_oem7_msgs::INSPVAX > ( const Oem7RawMessageIf::ConstPtr &  msg,
boost::shared_ptr< novatel_oem7_msgs::INSPVAX > &  inspvax 
)

Definition at line 467 of file oem7_ros_messages.cpp.

◆ MakeROSMessage< novatel_oem7_msgs::INSSTDEV >()

template<>
void novatel_oem7_driver::MakeROSMessage< novatel_oem7_msgs::INSSTDEV > ( const Oem7RawMessageIf::ConstPtr &  msg,
boost::shared_ptr< novatel_oem7_msgs::INSSTDEV > &  insstdev 
)

Definition at line 507 of file oem7_ros_messages.cpp.

◆ MakeROSMessage< novatel_oem7_msgs::PPPPOS >()

template<>
void novatel_oem7_driver::MakeROSMessage< novatel_oem7_msgs::PPPPOS > ( const Oem7RawMessageIf::ConstPtr &  msg,
boost::shared_ptr< novatel_oem7_msgs::PPPPOS > &  ppppos 
)

Definition at line 272 of file oem7_ros_messages.cpp.

◆ MakeROSMessage< novatel_oem7_msgs::RXSTATUS >()

template<>
void novatel_oem7_driver::MakeROSMessage< novatel_oem7_msgs::RXSTATUS > ( const Oem7RawMessageIf::ConstPtr &  msg,
boost::shared_ptr< novatel_oem7_msgs::RXSTATUS > &  rxstatus 
)

Definition at line 604 of file oem7_ros_messages.cpp.

◆ MakeROSMessage< novatel_oem7_msgs::TERRASTARINFO >()

template<>
void novatel_oem7_driver::MakeROSMessage< novatel_oem7_msgs::TERRASTARINFO > ( const Oem7RawMessageIf::ConstPtr &  msg,
boost::shared_ptr< novatel_oem7_msgs::TERRASTARINFO > &  terrastarinfo 
)

Definition at line 309 of file oem7_ros_messages.cpp.

◆ MakeROSMessage< novatel_oem7_msgs::TERRASTARSTATUS >()

template<>
void novatel_oem7_driver::MakeROSMessage< novatel_oem7_msgs::TERRASTARSTATUS > ( const Oem7RawMessageIf::ConstPtr &  msg,
boost::shared_ptr< novatel_oem7_msgs::TERRASTARSTATUS > &  terrastarstatus 
)

Definition at line 335 of file oem7_ros_messages.cpp.

◆ MakeROSMessage< novatel_oem7_msgs::TIME >()

template<>
void novatel_oem7_driver::MakeROSMessage< novatel_oem7_msgs::TIME > ( const Oem7RawMessageIf::ConstPtr &  msg,
boost::shared_ptr< novatel_oem7_msgs::TIME > &  time 
)

Definition at line 577 of file oem7_ros_messages.cpp.

◆ NavSatStatusService()

uint16_t novatel_oem7_driver::NavSatStatusService ( novatel_oem7_msgs::BESTPOS::Ptr  bestpos)

Definition at line 295 of file bestpos_handler.cpp.

◆ OEM7_NMEA_MSGIDS()

◆ radiansToDegrees()

double novatel_oem7_driver::radiansToDegrees ( double  radians)
inline

Definition at line 74 of file bestpos_handler.cpp.

◆ SetOem7Header()

void novatel_oem7_driver::SetOem7Header ( const Oem7RawMessageIf::ConstPtr &  msg,
const std::string &  name,
novatel_oem7_msgs::Oem7Header::Type &  oem7_hdr 
)
Parameters
msgin: raw message
namemessage name
oem7_hdrheader to populate

Definition at line 74 of file oem7_ros_messages.cpp.

◆ SetOem7ShortHeader()

void novatel_oem7_driver::SetOem7ShortHeader ( const Oem7RawMessageIf::ConstPtr &  msg,
const std::string &  name,
novatel_oem7_msgs::Oem7Header::Type &  oem7_hdr 
)
Parameters
msgin: short raw message
namemessage name
oem7_hdrheader to populate

Definition at line 88 of file oem7_ros_messages.cpp.

◆ SetROSHeader()

template<typename T >
void novatel_oem7_driver::SetROSHeader ( const std::string &  frame_id,
boost::shared_ptr< T > &  msg 
)

Definition at line 38 of file ros_messages.hpp.

◆ ToROSGPSStatus()

int16_t novatel_oem7_driver::ToROSGPSStatus ( const novatel_oem7_msgs::BESTPOS::Ptr  bestpos)

Definition at line 139 of file bestpos_handler.cpp.

◆ UTMPointFromGnss()

void novatel_oem7_driver::UTMPointFromGnss ( geometry_msgs::Point &  pt,
double  lat,
double  lon,
double  hgt 
)

Get Geometry (UTM) point from GNSS position, assuming zero origin.

Definition at line 325 of file bestpos_handler.cpp.

Variable Documentation

◆ AUX1_STATUS_STRS

const str_vector_t novatel_oem7_driver::AUX1_STATUS_STRS

Auxiliary 1 Status strings - refer to Oem7 manual.

Definition at line 119 of file receiverstatus_handler.cpp.

◆ AUX2_STATUS_STRS

const str_vector_t novatel_oem7_driver::AUX2_STATUS_STRS

Auxiliary 2 Status strings - refer to Oem7 manual.

Definition at line 156 of file receiverstatus_handler.cpp.

◆ AUX3_STATUS_STRS

const str_vector_t novatel_oem7_driver::AUX3_STATUS_STRS

Auxiliary 3 Status strings - refer to Oem7 manual.

Definition at line 193 of file receiverstatus_handler.cpp.

◆ AUX4_STATUS_STRS

const str_vector_t novatel_oem7_driver::AUX4_STATUS_STRS

Definition at line 229 of file receiverstatus_handler.cpp.

◆ BESTGNSSPOS_OEM7_MSGID

const int novatel_oem7_driver::BESTGNSSPOS_OEM7_MSGID = 1429

Definition at line 35 of file oem7_message_ids.h.

◆ BESTPOS_OEM7_MSGID

const int novatel_oem7_driver::BESTPOS_OEM7_MSGID = 42

Definition at line 36 of file oem7_message_ids.h.

◆ BESTUTM_OEM7_MSGID

const int novatel_oem7_driver::BESTUTM_OEM7_MSGID = 726

Definition at line 37 of file oem7_message_ids.h.

◆ BESTVEL_OEM7_MSGID

const int novatel_oem7_driver::BESTVEL_OEM7_MSGID = 99

Definition at line 38 of file oem7_message_ids.h.

◆ CORRIMUS_OEM7_MSGID

const int novatel_oem7_driver::CORRIMUS_OEM7_MSGID = 2264

Definition at line 42 of file oem7_message_ids.h.

◆ DATA_NOT_AVAILABLE

const double novatel_oem7_driver::DATA_NOT_AVAILABLE = -1.0

Used to initialized unpopulated fields.

Definition at line 64 of file ins_handler.cpp.

◆ GLMLA_OEM7_MSGID

const int novatel_oem7_driver::GLMLA_OEM7_MSGID = 859

Definition at line 55 of file oem7_message_ids.h.

◆ GPALM_OEM7_MSGID

const int novatel_oem7_driver::GPALM_OEM7_MSGID = 217

Definition at line 56 of file oem7_message_ids.h.

◆ GPGGA_OEM7_MSGID

const int novatel_oem7_driver::GPGGA_OEM7_MSGID = 218

Definition at line 57 of file oem7_message_ids.h.

◆ GPGGALONG_OEM7_MSGID

const int novatel_oem7_driver::GPGGALONG_OEM7_MSGID = 521

Definition at line 58 of file oem7_message_ids.h.

◆ GPGLL_OEM7_MSGID

const int novatel_oem7_driver::GPGLL_OEM7_MSGID = 219

Definition at line 59 of file oem7_message_ids.h.

◆ GPGRS_OEM7_MSGID

const int novatel_oem7_driver::GPGRS_OEM7_MSGID = 220

Definition at line 60 of file oem7_message_ids.h.

◆ GPGSA_OEM7_MSGID

const int novatel_oem7_driver::GPGSA_OEM7_MSGID = 221

Definition at line 61 of file oem7_message_ids.h.

◆ GPGST_OEM7_MSGID

const int novatel_oem7_driver::GPGST_OEM7_MSGID = 222

Definition at line 62 of file oem7_message_ids.h.

◆ GPGSV_OEM7_MSGID

const int novatel_oem7_driver::GPGSV_OEM7_MSGID = 223

Definition at line 63 of file oem7_message_ids.h.

◆ GPHDT_OEM7_MSGID

const int novatel_oem7_driver::GPHDT_OEM7_MSGID = 1045

Definition at line 64 of file oem7_message_ids.h.

◆ GPHDTDUALANTENNA_MSGID

const int novatel_oem7_driver::GPHDTDUALANTENNA_MSGID = 2045

Definition at line 65 of file oem7_message_ids.h.

◆ GPRMB_OEM7_MSGID

const int novatel_oem7_driver::GPRMB_OEM7_MSGID = 224

Definition at line 66 of file oem7_message_ids.h.

◆ GPRMC_OEM7_MSGID

const int novatel_oem7_driver::GPRMC_OEM7_MSGID = 225

Definition at line 67 of file oem7_message_ids.h.

◆ GPVTG_OEM7_MSGID

const int novatel_oem7_driver::GPVTG_OEM7_MSGID = 226

Definition at line 68 of file oem7_message_ids.h.

◆ GPZDA_OEM7_MSGID

const int novatel_oem7_driver::GPZDA_OEM7_MSGID = 227

Definition at line 69 of file oem7_message_ids.h.

◆ HEADING2_OEM7_MSGID

const int novatel_oem7_driver::HEADING2_OEM7_MSGID = 1335

Definition at line 43 of file oem7_message_ids.h.

◆ IMURATECORRIMUS_OEM7_MSGID

const int novatel_oem7_driver::IMURATECORRIMUS_OEM7_MSGID = 1362

Definition at line 44 of file oem7_message_ids.h.

◆ INSCONFIG_OEM7_MSGID

const int novatel_oem7_driver::INSCONFIG_OEM7_MSGID = 1945

Definition at line 45 of file oem7_message_ids.h.

◆ INSPVAS_OEM7_MSGID

const int novatel_oem7_driver::INSPVAS_OEM7_MSGID = 508

Definition at line 46 of file oem7_message_ids.h.

◆ INSPVAX_OEM7_MSGID

const int novatel_oem7_driver::INSPVAX_OEM7_MSGID = 1465

Definition at line 47 of file oem7_message_ids.h.

◆ INSSTDEV_OEM7_MSGID

const int novatel_oem7_driver::INSSTDEV_OEM7_MSGID = 2051

Definition at line 48 of file oem7_message_ids.h.

◆ OEM7_BINARY_MSG_HDR_LEN

const std::size_t novatel_oem7_driver::OEM7_BINARY_MSG_HDR_LEN = sizeof(Oem7MessageHeaderMem)

Definition at line 512 of file oem7_messages.h.

◆ OEM7_BINARY_MSG_SHORT_HDR_LEN

const std::size_t novatel_oem7_driver::OEM7_BINARY_MSG_SHORT_HDR_LEN = sizeof(Oem7MessgeShortHeaderMem)

Definition at line 513 of file oem7_messages.h.

◆ ONE_G

const double novatel_oem7_driver::ONE_G = 9.80665

Definition at line 33 of file oem7_imu.cpp.

◆ PPPPOS_OEM7_MSGID

const int novatel_oem7_driver::PPPPOS_OEM7_MSGID = 1538

Definition at line 39 of file oem7_message_ids.h.

◆ PSRDOP2_OEM7_MSGID

const int novatel_oem7_driver::PSRDOP2_OEM7_MSGID = 1163

Definition at line 49 of file oem7_message_ids.h.

◆ RAWIMUSX_OEM7_MSGID

const int novatel_oem7_driver::RAWIMUSX_OEM7_MSGID = 1462

Definition at line 52 of file oem7_message_ids.h.

◆ RECEIVER_ERROR_STRS

const str_vector_t novatel_oem7_driver::RECEIVER_ERROR_STRS

Definition at line 45 of file receiverstatus_handler.cpp.

◆ RECEIVER_STATUS_STRS

const str_vector_t novatel_oem7_driver::RECEIVER_STATUS_STRS

Oem7 receiver status strings - refer to Oem7 manual

Definition at line 82 of file receiverstatus_handler.cpp.

◆ RXSTATUS_OEM7_MSGID

const int novatel_oem7_driver::RXSTATUS_OEM7_MSGID = 93

Definition at line 50 of file oem7_message_ids.h.

◆ TERRASTARINFO_OEM7_MSGID

const int novatel_oem7_driver::TERRASTARINFO_OEM7_MSGID = 1719

Definition at line 40 of file oem7_message_ids.h.

◆ TERRASTARSTATUS_OEM7_MSGID

const int novatel_oem7_driver::TERRASTARSTATUS_OEM7_MSGID = 1729

Definition at line 41 of file oem7_message_ids.h.

◆ TIME_OEM7_MSGID

const int novatel_oem7_driver::TIME_OEM7_MSGID = 101

Definition at line 51 of file oem7_message_ids.h.



novatel_oem7_driver
Author(s):
autogenerated on Sun Mar 19 2023 02:17:37