PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <common.h>
Public Attributes | |
uint64_t | time_usec |
int32_t | lat |
Latitude in 1E-7 degrees. More... | |
int32_t | lon |
Longitude in 1E-7 degrees. More... | |
int32_t | alt |
Altitude in 1E-3 meters (millimeters) above MSL. More... | |
float | yaw |
yaw angle. NaN if not set (used for dual antenna GPS), (rad, [-PI, PI]) More... | |
float | yaw_offset |
Heading/Yaw offset for dual antenna GPS - refer to description for GPS_YAW_OFFSET. More... | |
uint8_t | fix_type |
0-1: no fix, 2: 2D fix, 3: 3D fix, 4: RTCM code differential, 5: Real-Time Kinematic More... | |
float | eph |
GPS horizontal position accuracy in m. More... | |
float | epv |
GPS vertical position accuracy in m. More... | |
float | sacc |
GPS speed accuracy in m/s. More... | |
float | vel_m_s |
GPS ground speed (m/sec) More... | |
float | vel_ned [3] |
GPS ground speed NED. More... | |
bool | vel_ned_valid |
GPS ground speed is valid. More... | |
uint8_t | nsats |
number of satellites used More... | |
float | pdop |
position dilution of precision More... | |
int32_t estimator::gps_message::alt |
Altitude in 1E-3 meters (millimeters) above MSL.
Definition at line 61 of file common.h.
Referenced by Ekf2::apply_gps_offsets(), Ekf2::calc_gps_blend_output(), Ekf::collect_gps(), Ekf2::fillGpsMsgWithVehicleGpsPosData(), Ekf::gps_is_good(), Ekf2::Run(), EstimatorInterface::setGpsData(), EkfInitializationTest::SetUp(), Ekf2::update_gps_blend_states(), and Ekf2::update_gps_offsets().
float estimator::gps_message::eph |
GPS horizontal position accuracy in m.
Definition at line 65 of file common.h.
Referenced by Ekf2::apply_gps_offsets(), Ekf2::blend_gps_data(), Ekf2::calc_gps_blend_output(), Ekf::collect_gps(), Ekf2::fillGpsMsgWithVehicleGpsPosData(), Ekf::gps_is_good(), Ekf2::Run(), EstimatorInterface::setGpsData(), EkfInitializationTest::SetUp(), and Ekf2::update_gps_blend_states().
float estimator::gps_message::epv |
GPS vertical position accuracy in m.
Definition at line 66 of file common.h.
Referenced by Ekf2::apply_gps_offsets(), Ekf2::blend_gps_data(), Ekf2::calc_gps_blend_output(), Ekf::collect_gps(), Ekf2::fillGpsMsgWithVehicleGpsPosData(), Ekf::gps_is_good(), Ekf2::Run(), EstimatorInterface::setGpsData(), EkfInitializationTest::SetUp(), and Ekf2::update_gps_blend_states().
uint8_t estimator::gps_message::fix_type |
0-1: no fix, 2: 2D fix, 3: 3D fix, 4: RTCM code differential, 5: Real-Time Kinematic
Definition at line 64 of file common.h.
Referenced by Ekf2::apply_gps_offsets(), Ekf2::calc_gps_blend_output(), Ekf::collect_gps(), Ekf2::fillGpsMsgWithVehicleGpsPosData(), Ekf::gps_is_good(), Ekf2::Run(), EstimatorInterface::setGpsData(), EkfInitializationTest::SetUp(), and Ekf2::update_gps_blend_states().
int32_t estimator::gps_message::lat |
Latitude in 1E-7 degrees.
Definition at line 59 of file common.h.
Referenced by Ekf2::apply_gps_offsets(), Ekf2::calc_gps_blend_output(), Ekf::collect_gps(), Ekf2::fillGpsMsgWithVehicleGpsPosData(), Ekf::gps_is_good(), Ekf2::Run(), EstimatorInterface::setGpsData(), EkfInitializationTest::SetUp(), Ekf2::update_gps_blend_states(), and Ekf2::update_gps_offsets().
int32_t estimator::gps_message::lon |
Longitude in 1E-7 degrees.
Definition at line 60 of file common.h.
Referenced by Ekf2::apply_gps_offsets(), Ekf2::calc_gps_blend_output(), Ekf::collect_gps(), Ekf2::fillGpsMsgWithVehicleGpsPosData(), Ekf::gps_is_good(), Ekf2::Run(), EstimatorInterface::setGpsData(), EkfInitializationTest::SetUp(), Ekf2::update_gps_blend_states(), and Ekf2::update_gps_offsets().
uint8_t estimator::gps_message::nsats |
number of satellites used
Definition at line 71 of file common.h.
Referenced by Ekf2::apply_gps_offsets(), Ekf2::calc_gps_blend_output(), Ekf2::fillGpsMsgWithVehicleGpsPosData(), Ekf::gps_is_good(), Ekf2::Run(), EkfInitializationTest::SetUp(), and Ekf2::update_gps_blend_states().
float estimator::gps_message::pdop |
position dilution of precision
Definition at line 72 of file common.h.
Referenced by Ekf2::apply_gps_offsets(), Ekf2::calc_gps_blend_output(), Ekf2::fillGpsMsgWithVehicleGpsPosData(), Ekf::gps_is_good(), EkfInitializationTest::SetUp(), and Ekf2::update_gps_blend_states().
float estimator::gps_message::sacc |
GPS speed accuracy in m/s.
Definition at line 67 of file common.h.
Referenced by Ekf2::apply_gps_offsets(), Ekf2::blend_gps_data(), Ekf2::calc_gps_blend_output(), Ekf2::fillGpsMsgWithVehicleGpsPosData(), Ekf::gps_is_good(), Ekf2::Run(), EstimatorInterface::setGpsData(), EkfInitializationTest::SetUp(), and Ekf2::update_gps_blend_states().
uint64_t estimator::gps_message::time_usec |
Definition at line 58 of file common.h.
Referenced by Ekf2::apply_gps_offsets(), Ekf2::blend_gps_data(), Ekf2::calc_gps_blend_output(), Ekf2::fillGpsMsgWithVehicleGpsPosData(), Ekf2::filter_altitude_ellipsoid(), Ekf2::Run(), EstimatorInterface::setGpsData(), EkfInitializationTest::SetUp(), Ekf2::update_gps_blend_states(), Ekf2::update_gps_offsets(), and EkfInitializationTest::update_with_const_sensors().
float estimator::gps_message::vel_m_s |
GPS ground speed (m/sec)
Definition at line 68 of file common.h.
Referenced by Ekf2::apply_gps_offsets(), Ekf2::calc_gps_blend_output(), Ekf2::fillGpsMsgWithVehicleGpsPosData(), Ekf2::Run(), EkfInitializationTest::SetUp(), and Ekf2::update_gps_blend_states().
float estimator::gps_message::vel_ned[3] |
GPS ground speed NED.
Definition at line 69 of file common.h.
Referenced by Ekf2::apply_gps_offsets(), Ekf2::calc_gps_blend_output(), Ekf2::fillGpsMsgWithVehicleGpsPosData(), Ekf::gps_is_good(), Ekf2::Run(), EstimatorInterface::setGpsData(), EkfInitializationTest::SetUp(), and Ekf2::update_gps_blend_states().
bool estimator::gps_message::vel_ned_valid |
GPS ground speed is valid.
Definition at line 70 of file common.h.
Referenced by Ekf2::apply_gps_offsets(), Ekf2::calc_gps_blend_output(), Ekf2::fillGpsMsgWithVehicleGpsPosData(), Ekf2::Run(), EstimatorInterface::setGpsData(), EkfInitializationTest::SetUp(), and Ekf2::update_gps_blend_states().
float estimator::gps_message::yaw |
yaw angle. NaN if not set (used for dual antenna GPS), (rad, [-PI, PI])
Definition at line 62 of file common.h.
Referenced by Ekf2::apply_gps_offsets(), Ekf2::calc_gps_blend_output(), Ekf2::fillGpsMsgWithVehicleGpsPosData(), Ekf2::Run(), EstimatorInterface::setGpsData(), EkfInitializationTest::SetUp(), and Ekf2::update_gps_blend_states().
float estimator::gps_message::yaw_offset |
Heading/Yaw offset for dual antenna GPS - refer to description for GPS_YAW_OFFSET.
Definition at line 63 of file common.h.
Referenced by Ekf2::apply_gps_offsets(), Ekf2::calc_gps_blend_output(), Ekf2::fillGpsMsgWithVehicleGpsPosData(), Ekf2::Run(), EstimatorInterface::setGpsData(), EkfInitializationTest::SetUp(), and Ekf2::update_gps_blend_states().