MRPT
1.9.9
|
GNSS (GPS) data structures, mainly for use within mrpt::obs::CObservationGPS.
Namespaces | |
nv_oem6_ins_status_type | |
nv_oem6_position_type | |
nv_oem6_solution_status | |
Classes | |
struct | gnss_message |
Pure virtual base for all message types. More... | |
struct | gnss_message_ptr |
A smart pointer to a GNSS message. More... | |
struct | Message_NMEA_GGA |
NMEA datum: GGA. More... | |
struct | Message_NMEA_GLL |
NMEA datum: GLL. More... | |
struct | Message_NMEA_RMC |
NMEA datum: RMC. More... | |
struct | Message_NMEA_VTG |
NMEA datum: VTG. More... | |
struct | Message_NMEA_ZDA |
NMEA datum: ZDA. More... | |
struct | Message_NV_OEM6_GENERIC_FRAME |
Novatel generic frame (to store frames without a parser at the present time). More... | |
struct | Message_NV_OEM6_GENERIC_SHORT_FRAME |
Novatel generic short-header frame (to store frames without a parser at the present time). More... | |
struct | Message_NV_OEM6_RANGECMP |
Novatel frame: NV_OEM6_RANGECMP. More... | |
struct | Message_NV_OEM6_VERSION |
Novatel frame: NV_OEM6_VERSION. More... | |
struct | Message_TOPCON_PZS |
GPS datum for TopCon's mmGPS devices: PZS. More... | |
struct | Message_TOPCON_SATS |
TopCon mmGPS devices: SATS, a generic structure for statistics about tracked satelites and their positions. More... | |
struct | nv_oem6_header_t |
Novatel OEM6 regular header structure. More... | |
struct | nv_oem6_short_header_t |
Novatel OEM6 short header structure. More... | |
struct | UTC_time |
UTC (Coordinated Universal Time) time-stamp structure for GPS messages. More... | |
Enumerations | |
enum | gnss_message_type_t { NMEA_GGA = 10, NMEA_GLL, NMEA_GSA, NMEA_GSV, NMEA_MSS, NMEA_RMC, NMEA_VTG, NMEA_ZDA, TOPCON_PZS = 30, TOPCON_SATS, NV_OEM6_MSG2ENUM = 1000, NV_OEM6_GENERIC_FRAME = 3000 + NV_OEM6_MSG2ENUM, NV_OEM6_GENERIC_SHORT_FRAME, NV_OEM6_ALIGNBSLNENU = 1315 + NV_OEM6_MSG2ENUM, NV_OEM6_ALIGNBSLNXYZ = 1314 + NV_OEM6_MSG2ENUM, NV_OEM6_ALIGNDOP = 1332 + NV_OEM6_MSG2ENUM, NV_OEM6_BESTPOS = 42 + NV_OEM6_MSG2ENUM, NV_OEM6_BESTSATS = 1194 + NV_OEM6_MSG2ENUM, NV_OEM6_BESTUTM = 726 + NV_OEM6_MSG2ENUM, NV_OEM6_BESTVEL = 99 + NV_OEM6_MSG2ENUM, NV_OEM6_BESTXYZ = 241 + NV_OEM6_MSG2ENUM, NV_OEM6_CLOCKSTEERING = 26 + NV_OEM6_MSG2ENUM, NV_OEM6_GPGLL = 219 + NV_OEM6_MSG2ENUM, NV_OEM6_GPGGA = 218 + NV_OEM6_MSG2ENUM, NV_OEM6_GPGGARTK, NV_OEM6_GPGSA = 221 + NV_OEM6_MSG2ENUM, NV_OEM6_GPGSV = 223 + NV_OEM6_MSG2ENUM, NV_OEM6_GPHDT = 1045 + NV_OEM6_MSG2ENUM, NV_OEM6_GPRMC = 225 + NV_OEM6_MSG2ENUM, NV_OEM6_GPVTG = 226 + NV_OEM6_MSG2ENUM, NV_OEM6_GPZDA = 227 + NV_OEM6_MSG2ENUM, NV_OEM6_IONUTC = 8 + NV_OEM6_MSG2ENUM, NV_OEM6_MARKPOS = 181 + NV_OEM6_MSG2ENUM, NV_OEM6_MARK2POS = 615 + NV_OEM6_MSG2ENUM, NV_OEM6_MARKTIME = 231 + NV_OEM6_MSG2ENUM, NV_OEM6_MARK2TIME = 616 + NV_OEM6_MSG2ENUM, NV_OEM6_PPPPOS = 1538 + NV_OEM6_MSG2ENUM, NV_OEM6_RANGECMP = 140 + NV_OEM6_MSG2ENUM, NV_OEM6_RAWEPHEM = 41 + NV_OEM6_MSG2ENUM, NV_OEM6_RXSTATUS = 93 + NV_OEM6_MSG2ENUM, NV_OEM6_VERSION = 37 + NV_OEM6_MSG2ENUM, NV_OEM6_INSPVAS = 508 + NV_OEM6_MSG2ENUM, NV_OEM6_INSATTS = 319 + NV_OEM6_MSG2ENUM, NV_OEM6_INSCOVS = 320 + NV_OEM6_MSG2ENUM, NV_OEM6_INSVELS = 324 + NV_OEM6_MSG2ENUM, NV_OEM6_RAWIMUS = 325 + NV_OEM6_MSG2ENUM } |
List of all known GNSS message types. More... | |
Functions | |
template<class TGEODETICCOORDS > | |
GNSS_BINARY_MSG_DEFINITION_MID TGEODETICCOORDS | getAsStruct () const |
Return the geodetic coords as a mrpt::topography::TGeodeticCoords structure (requires linking against mrpt-topography) Call as: getAsStruct<TGeodeticCoords>();. More... | |
bool | getAllFieldDescriptions (std::ostream &o) const override |
bool | getAllFieldValues (std::ostream &o) const override |
List of all known GNSS message types.
Normally, each type here has a corresponding class, derived from mrpt::obs::gnss::gnss_message, that stores the message data, but some classes may be still in the "TO-DO" list or just not needed in practice. On the other hand, all message classes must be associated with one and only one value from this list.
Definition at line 22 of file gnss_messages_type_list.h.
|
override |
|
override |
|
inline |
Return the geodetic coords as a mrpt::topography::TGeodeticCoords structure (requires linking against mrpt-topography) Call as: getAsStruct<TGeodeticCoords>();.
Definition at line 244 of file gnss_messages_novatel.h.
double mrpt::obs::gnss::a0 |
Definition at line 450 of file gnss_messages_novatel.h.
double mrpt::obs::gnss::A0 |
UTC constant and 1st order terms.
Definition at line 457 of file gnss_messages_novatel.h.
double mrpt::obs::gnss::a1 |
Definition at line 450 of file gnss_messages_novatel.h.
Referenced by mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::generatePWConsistenciesMatrix(), mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::generatePWConsistencyElement(), mrpt::topography::GeodeticToUTM(), mrpt::maps::CPointsMap::internal_insertObservation(), mrAugmentBestRun(), mrFindQuadNeighbors2(), and mrpt::math::solve_poly5().
double mrpt::obs::gnss::A1 |
Definition at line 457 of file gnss_messages_novatel.h.
Referenced by mrpt::vision::pnp::epnp::epnp(), mrpt::topography::geodeticToUTM(), mrpt::vision::pnp::rpnp::getp3p(), mrpt::vision::pnp::epnp::qr_solve(), mrpt::vision::pnp::upnp::qr_solve(), mrpt::vision::pnp::upnp::upnp(), mrpt::topography::UTMToGeodetic(), mrpt::vision::pnp::epnp::~epnp(), and mrpt::vision::pnp::upnp::~upnp().
double mrpt::obs::gnss::a2 |
Definition at line 450 of file gnss_messages_novatel.h.
Referenced by mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::generatePWConsistenciesMatrix(), mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::generatePWConsistencyElement(), mrpt::topography::GeodeticToUTM(), mrpt::maps::CPointsMap::internal_insertObservation(), mrAugmentBestRun(), mrFindQuadNeighbors2(), mrpt::vision::pnp::p3p::solve_for_lengths(), mrpt::math::solve_poly3(), and mrpt::topography::UTMToGeodetic().
double mrpt::obs::gnss::a3 |
Definition at line 450 of file gnss_messages_novatel.h.
Referenced by mrAugmentBestRun(), and mrFindQuadNeighbors2().
int32_t mrpt::obs::gnss::accel_x |
Definition at line 378 of file gnss_messages_novatel.h.
int32_t mrpt::obs::gnss::accel_y_neg |
Definition at line 378 of file gnss_messages_novatel.h.
int32_t mrpt::obs::gnss::accel_z |
Definition at line 378 of file gnss_messages_novatel.h.
double mrpt::obs::gnss::att_cov[9] |
Attitude covariance matrix of the SPAN frame to the local level frame.
(deg sq) xx,xy,xz,yx,yy,yz,zx,zy,zz
Definition at line 287 of file gnss_messages_novatel.h.
uint32_t mrpt::obs::gnss::aux1stat |
Definition at line 328 of file gnss_messages_novatel.h.
uint32_t mrpt::obs::gnss::aux1stat_clear |
Definition at line 328 of file gnss_messages_novatel.h.
uint32_t mrpt::obs::gnss::aux1stat_pri |
Definition at line 328 of file gnss_messages_novatel.h.
uint32_t mrpt::obs::gnss::aux1stat_set |
Definition at line 328 of file gnss_messages_novatel.h.
uint32_t mrpt::obs::gnss::aux2stat |
Definition at line 329 of file gnss_messages_novatel.h.
uint32_t mrpt::obs::gnss::aux2stat_clear |
Definition at line 329 of file gnss_messages_novatel.h.
uint32_t mrpt::obs::gnss::aux2stat_pri |
Definition at line 329 of file gnss_messages_novatel.h.
uint32_t mrpt::obs::gnss::aux2stat_set |
Definition at line 329 of file gnss_messages_novatel.h.
uint32_t mrpt::obs::gnss::aux3stat |
Definition at line 330 of file gnss_messages_novatel.h.
uint32_t mrpt::obs::gnss::aux3stat_clear |
Definition at line 330 of file gnss_messages_novatel.h.
uint32_t mrpt::obs::gnss::aux3stat_pri |
Definition at line 330 of file gnss_messages_novatel.h.
uint32_t mrpt::obs::gnss::aux3stat_set |
Definition at line 330 of file gnss_messages_novatel.h.
double mrpt::obs::gnss::azimuth |
Definition at line 260 of file gnss_messages_novatel.h.
Referenced by mrpt::obs::CObservationVelodyneScan::TPointCloud::clear(), mrpt::obs::CObservationVelodyneScan::TPointCloud::clear_deep(), mrpt::obs::CObservationVelodyneScan::generatePointCloud(), mrpt::obs::CObservationVelodyneScan::generatePointCloudAlongSE3Trajectory(), and mrpt::obs::CObservationVelodyneScan::TPointCloud::reserve().
double mrpt::obs::gnss::b0 |
Definition at line 450 of file gnss_messages_novatel.h.
Referenced by mrpt::vision::pnp::p3p::solve_for_lengths().
double mrpt::obs::gnss::b1 |
Definition at line 450 of file gnss_messages_novatel.h.
Referenced by mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::generatePWConsistenciesMatrix(), mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::generatePWConsistencyElement(), mrAugmentBestRun(), mrFindQuadNeighbors2(), mrpt::math::noncentralChi2PDF_CDF(), mrpt::vision::pnp::p3p::solve_for_lengths(), mrpt::math::solve_poly4(), mrpt::math::solve_poly5(), and mrpt::math::spline().
double mrpt::obs::gnss::b2 |
Definition at line 450 of file gnss_messages_novatel.h.
Referenced by mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::generatePWConsistenciesMatrix(), mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::generatePWConsistencyElement(), mrAugmentBestRun(), mrFindQuadNeighbors2(), XMLNode::parseFile(), mrpt::vision::pnp::dls::run_kernel(), solve_deg4(), mrpt::vision::pnp::p3p::solve_for_lengths(), mrpt::math::spline(), and mrpt::topography::UTMToGeodetic().
double mrpt::obs::gnss::b3 |
Definition at line 450 of file gnss_messages_novatel.h.
Referenced by mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), mrpt::vision::pnp::epnp::find_betas_approx_2(), mrAugmentBestRun(), mrFindQuadNeighbors2(), and solve_deg4().
char mrpt::obs::gnss::base_station_id |
Definition at line 231 of file gnss_messages_novatel.h.
double mrpt::obs::gnss::clock_offset |
Definition at line 422 of file gnss_messages_novatel.h.
double mrpt::obs::gnss::clock_offset_std |
Definition at line 422 of file gnss_messages_novatel.h.
uint32_t mrpt::obs::gnss::clock_status |
Definition at line 424 of file gnss_messages_novatel.h.
uint32_t mrpt::obs::gnss::crc |
Definition at line 238 of file gnss_messages_novatel.h.
Referenced by mrpt::hwdrivers::CSickLaserSerial::SendCommandToSICK(), and TEST().
uint32_t mrpt::obs::gnss::datum_id |
Definition at line 228 of file gnss_messages_novatel.h.
uint32_t mrpt::obs::gnss::deltat_ls |
Delta time due to leap seconds.
Definition at line 463 of file gnss_messages_novatel.h.
uint32_t mrpt::obs::gnss::deltat_lsf |
Delta time due to leap seconds (future)
Definition at line 465 of file gnss_messages_novatel.h.
float mrpt::obs::gnss::diff_age |
Definition at line 232 of file gnss_messages_novatel.h.
uint32_t mrpt::obs::gnss::dn |
Day number (1=sunday, 7=saturday)
Definition at line 461 of file gnss_messages_novatel.h.
uint32_t mrpt::obs::gnss::error |
Definition at line 326 of file gnss_messages_novatel.h.
Referenced by mrpt::hwdrivers::CRovio::getEncoders(), mrpt::hwdrivers::CPhidgetInterfaceKitProximitySensors::getObservation(), mrpt::hwdrivers::CImageGrabber_FlyCapture2::getObservation(), mrpt::hwdrivers::CRovio::getRovioState(), mrpt::hwdrivers::CImageGrabber_FlyCapture2::open(), XMLNode::parseString(), mrpt::hwdrivers::CRovio::pathGetList(), mrpt::hwdrivers::CImageGrabber_FlyCapture2::startCapture(), mrpt::hwdrivers::CImageGrabber_FlyCapture2::startSyncCapture(), and mrpt::hwdrivers::CImageGrabber_FlyCapture2::stopCapture().
uint8_t mrpt::obs::gnss::ext_sol_stat |
Definition at line 235 of file gnss_messages_novatel.h.
uint8_t mrpt::obs::gnss::galileo_beidou_mask |
Definition at line 236 of file gnss_messages_novatel.h.
uint8_t mrpt::obs::gnss::gps_glonass_mask |
Definition at line 237 of file gnss_messages_novatel.h.
int32_t mrpt::obs::gnss::gyro_x |
Definition at line 379 of file gnss_messages_novatel.h.
int32_t mrpt::obs::gnss::gyro_y_neg |
Definition at line 379 of file gnss_messages_novatel.h.
int32_t mrpt::obs::gnss::gyro_z |
Definition at line 379 of file gnss_messages_novatel.h.
GNSS_BINARY_MSG_DEFINITION_MID_END nv_oem6_header_t mrpt::obs::gnss::header |
Novatel frame: NV_OEM6_BESTPOS.
Novatel frame: NV_OEM6_IONUTC.
Novatel frame: NV_OEM6_MARK2TIME.
Novatel frame: NV_OEM6_MARKTIME.
Novatel frame: NV_OEM6_MARKPOS.
Novatel frame: NV_OEM6_RAWIMUS.
Novatel frame: NV_OEM6_RAWEPHEM.
Novatel frame: NV_OEM6_RXSTATUS.
Novatel frame: NV_OEM6_INSCOVS.
Novatel frame: NV_OEM6_INSPVAS.
Definition at line 222 of file gnss_messages_novatel.h.
Referenced by rp::standalone::rplidar::RPlidarDriverSerialImpl::_sendCommand(), rp::standalone::rplidar::RPlidarDriverSerialImpl::_waitResponseHeader(), mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::dumpToStream(), mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::dumpToStream(), mrpt::hwdrivers::CVelodyneScanner::internal_read_PCAP_packet(), mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::internal_readFromStream(), mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::internal_readFromStream(), mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::internal_readFromStream(), mrpt::obs::gnss::Message_NV_OEM6_VERSION::internal_readFromStream(), mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::internal_writeToStream(), mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::internal_writeToStream(), mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::internal_writeToStream(), mrpt::obs::gnss::Message_NV_OEM6_VERSION::internal_writeToStream(), mrpt::maps::loadLASFile(), mrpt::hwdrivers::CVelodyneScanner::receivePackets(), and mrpt::maps::saveLASFile().
double mrpt::obs::gnss::hgt |
Definition at line 226 of file gnss_messages_novatel.h.
float mrpt::obs::gnss::hgt_sigma |
Definition at line 230 of file gnss_messages_novatel.h.
uint32_t mrpt::obs::gnss::imu_status |
Definition at line 377 of file gnss_messages_novatel.h.
nv_oem6_ins_status_type::nv_ins_status_type_t mrpt::obs::gnss::ins_status |
Definition at line 261 of file gnss_messages_novatel.h.
double mrpt::obs::gnss::lat |
[deg], [deg], hgt over sea level[m]
Definition at line 226 of file gnss_messages_novatel.h.
Referenced by mrpt::topography::geodeticToGeocentric(), mrpt::topography::geodeticToGeocentric_WGS84(), mrpt::topography::GeodeticToUTM(), mrpt::topography::geodeticToUTM(), and mrpt::hwdrivers::CGPSInterface::parse_NMEA().
float mrpt::obs::gnss::lat_sigma |
Uncertainties (all in [m])
Definition at line 230 of file gnss_messages_novatel.h.
double mrpt::obs::gnss::lon |
Definition at line 226 of file gnss_messages_novatel.h.
Referenced by mrpt::comms::CClientTCPSocket::connect(), mrpt::topography::geodeticToGeocentric(), mrpt::topography::geodeticToGeocentric_WGS84(), mrpt::topography::GeodeticToUTM(), and mrpt::topography::geodeticToUTM().
float mrpt::obs::gnss::lon_sigma |
Definition at line 230 of file gnss_messages_novatel.h.
uint8_t mrpt::obs::gnss::num_sats_sol |
Definition at line 233 of file gnss_messages_novatel.h.
uint8_t mrpt::obs::gnss::num_sats_sol_L1 |
Definition at line 233 of file gnss_messages_novatel.h.
uint8_t mrpt::obs::gnss::num_sats_sol_multi |
Definition at line 233 of file gnss_messages_novatel.h.
uint8_t mrpt::obs::gnss::num_sats_tracked |
Definition at line 233 of file gnss_messages_novatel.h.
uint32_t mrpt::obs::gnss::num_stats |
Definition at line 326 of file gnss_messages_novatel.h.
double mrpt::obs::gnss::pitch |
Definition at line 260 of file gnss_messages_novatel.h.
Referenced by mrpt::poses::CPose3DPDFGaussian::copyFrom(), mrpt::obs::CObservationBearingRange::debugPrintOut(), generate_points(), Pose3DPDFGaussTests::generateRandomPose3DPDF(), Pose3DQuatPDFGaussTests::generateRandomPose3DPDF(), Pose3DQuatPDFGaussTests::generateRandomPoseQuat3DPDF(), mrpt::poses::CPose3DGridTemplate< double >::getAsMatrix(), mrpt::poses::CPose3DGridTemplate< double >::getByPos(), mrpt::poses::internal::getPoseFromString(), mrpt::poses::CPoseInterpolatorBase< 3 >::impl_interpolation(), IMPLEMENTS_SERIALIZABLE(), mrpt::poses::CPose3DPDF::jacobiansPoseComposition(), mrpt::hwdrivers::CPhidgetInterfaceKitProximitySensors::loadConfig_sensorSpecific(), mrpt::opengl::CAngularObservationMesh::FTrace2D< T >::operator()(), mrpt::poses::CPose3DGridTemplate< double >::pitch2idx(), mrpt::opengl::CRenderizable::readFromStreamRender(), mrpt::math::CQuaternion< T >::rpy(), mrpt::math::CQuaternion< T >::rpy_and_jacobian(), mrpt::opengl::CArrow::setArrowYawPitchRoll(), mrpt::maps::CLandmarksMap::simulateRangeBearingReadings(), Pose3DQuatTests::test_invComposePoint_vs_CPose3D(), Pose3DQuatPDFGaussTests::test_toFromYPRGauss(), Pose3DPDFGaussTests::testAllPoseOperators(), Pose3DQuatPDFGaussTests::testChangeCoordsRef(), Pose3DPDFGaussTests::testChangeCoordsRef(), Pose3DPDFGaussTests::testCompositionJacobian(), Pose3DQuatPDFGaussTests::testCompositionJacobian(), Pose3DQuatPDFGaussTests::testInverse(), Pose3DPDFGaussTests::testPoseComposition(), Pose3DQuatPDFGaussTests::testPoseComposition(), Pose3DPDFGaussTests::testPoseInverse(), Pose3DPDFGaussTests::testPoseInverseComposition(), Pose3DQuatPDFGaussTests::testPoseInverseComposition(), and Pose3DPDFGaussTests::testToQuatPDFAndBack().
double mrpt::obs::gnss::pos_cov[9] |
Position covariance matrix in local level frame (metres squared) xx,xy,xz,yx,yy,yz,zx,zy,zz.
Definition at line 284 of file gnss_messages_novatel.h.
nv_oem6_position_type::nv_position_type_t mrpt::obs::gnss::position_type |
Definition at line 224 of file gnss_messages_novatel.h.
uint32_t mrpt::obs::gnss::ref_secs |
Definition at line 338 of file gnss_messages_novatel.h.
uint32_t mrpt::obs::gnss::ref_week |
Definition at line 338 of file gnss_messages_novatel.h.
uint32_t mrpt::obs::gnss::reserved |
Definition at line 234 of file gnss_messages_novatel.h.
double mrpt::obs::gnss::roll |
Definition at line 260 of file gnss_messages_novatel.h.
Referenced by mrpt::poses::CPose3DPDFGaussian::copyFrom(), generate_points(), Pose3DPDFGaussTests::generateRandomPose3DPDF(), Pose3DQuatPDFGaussTests::generateRandomPose3DPDF(), Pose3DQuatPDFGaussTests::generateRandomPoseQuat3DPDF(), mrpt::poses::CPose3DGridTemplate< double >::getAsMatrix(), mrpt::poses::CPose3DGridTemplate< double >::getByPos(), mrpt::poses::internal::getPoseFromString(), mrpt::poses::CPoseInterpolatorBase< 3 >::impl_interpolation(), mrpt::poses::CPose3DPDF::jacobiansPoseComposition(), mrpt::hwdrivers::CPhidgetInterfaceKitProximitySensors::loadConfig_sensorSpecific(), mrpt::opengl::CRenderizable::readFromStreamRender(), mrpt::poses::CPose3DGridTemplate< double >::roll2idx(), mrpt::math::CQuaternion< T >::rpy(), mrpt::math::CQuaternion< T >::rpy_and_jacobian(), mrpt::opengl::CArrow::setArrowYawPitchRoll(), Pose3DQuatPDFGaussTests::test_toFromYPRGauss(), Pose3DPDFGaussTests::testAllPoseOperators(), Pose3DQuatPDFGaussTests::testChangeCoordsRef(), Pose3DPDFGaussTests::testChangeCoordsRef(), Pose3DPDFGaussTests::testCompositionJacobian(), Pose3DQuatPDFGaussTests::testCompositionJacobian(), Pose3DQuatPDFGaussTests::testInverse(), Pose3DPDFGaussTests::testPoseComposition(), Pose3DQuatPDFGaussTests::testPoseComposition(), Pose3DPDFGaussTests::testPoseInverse(), Pose3DPDFGaussTests::testPoseInverseComposition(), Pose3DQuatPDFGaussTests::testPoseInverseComposition(), and Pose3DPDFGaussTests::testToQuatPDFAndBack().
uint32_t mrpt::obs::gnss::rxstat |
Definition at line 327 of file gnss_messages_novatel.h.
uint32_t mrpt::obs::gnss::rxstat_clear |
Definition at line 327 of file gnss_messages_novatel.h.
uint32_t mrpt::obs::gnss::rxstat_pri |
Definition at line 327 of file gnss_messages_novatel.h.
uint32_t mrpt::obs::gnss::rxstat_set |
Definition at line 327 of file gnss_messages_novatel.h.
uint32_t mrpt::obs::gnss::sat_prn |
Definition at line 338 of file gnss_messages_novatel.h.
double mrpt::obs::gnss::seconds_in_week |
Definition at line 257 of file gnss_messages_novatel.h.
float mrpt::obs::gnss::sol_age |
Definition at line 232 of file gnss_messages_novatel.h.
nv_oem6_solution_status::nv_solution_status_t mrpt::obs::gnss::solution_stat |
Definition at line 223 of file gnss_messages_novatel.h.
uint8_t mrpt::obs::gnss::subframe1[30] |
Definition at line 339 of file gnss_messages_novatel.h.
uint8_t mrpt::obs::gnss::subframe2[30] |
Definition at line 339 of file gnss_messages_novatel.h.
uint8_t mrpt::obs::gnss::subframe3[30] |
Definition at line 339 of file gnss_messages_novatel.h.
uint32_t mrpt::obs::gnss::tot |
Reference time of UTC params.
Definition at line 455 of file gnss_messages_novatel.h.
float mrpt::obs::gnss::undulation |
Definition at line 227 of file gnss_messages_novatel.h.
double mrpt::obs::gnss::utc_offset |
Definition at line 423 of file gnss_messages_novatel.h.
Referenced by TIMECONV_GetJulianDateFromGPSTime().
uint32_t mrpt::obs::gnss::utc_wn |
UTC reference week number.
Definition at line 453 of file gnss_messages_novatel.h.
double mrpt::obs::gnss::vel_cov[9] |
Velocity covariance matrix in local level frame.
(metres/second squared) xx,xy,xz,yx,yy,yz,zx,zy,zz
Definition at line 290 of file gnss_messages_novatel.h.
double mrpt::obs::gnss::vel_east |
Definition at line 259 of file gnss_messages_novatel.h.
double mrpt::obs::gnss::vel_north |
Definition at line 259 of file gnss_messages_novatel.h.
double mrpt::obs::gnss::vel_up |
Definition at line 259 of file gnss_messages_novatel.h.
uint32_t mrpt::obs::gnss::week |
Definition at line 256 of file gnss_messages_novatel.h.
double mrpt::obs::gnss::week_seconds |
Definition at line 376 of file gnss_messages_novatel.h.
uint32_t mrpt::obs::gnss::wn_lsf |
Future week number.
Definition at line 459 of file gnss_messages_novatel.h.
Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 8fe78517f Sun Jul 14 19:43:28 2019 +0200 at lun oct 28 02:10:00 CET 2019 |