forked from Archive/PX4-Autopilot
vehicle_gps_position: remove timestamp_variance & timestamp_velocity (they're not used)
This commit is contained in:
parent
89f5bd27e8
commit
e2a7145379
|
@ -1,10 +1,10 @@
|
|||
# GPS position in WGS84 coordinates.
|
||||
# the auto-generated field 'timestamp' is for the position & velocity (microseconds)
|
||||
int32 lat # Latitude in 1E-7 degrees
|
||||
int32 lon # Longitude in 1E-7 degrees
|
||||
int32 alt # Altitude in 1E-3 meters above MSL, (millimetres)
|
||||
int32 alt_ellipsoid # Altitude in 1E-3 meters bove Ellipsoid, (millimetres)
|
||||
|
||||
uint64 timestamp_variance # Time of the accuracy estimates since system start, (microseconds)
|
||||
float32 s_variance_m_s # GPS speed accuracy estimate, (metres/sec)
|
||||
float32 c_variance_rad # GPS course accuracy estimate, (radians)
|
||||
uint8 fix_type # 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: RTCM code differential, 5: Real-Time Kinematic, float, 6: Real-Time Kinematic, fixed, 8: Extrapolated. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
|
||||
|
@ -18,7 +18,6 @@ float32 vdop # Vertical dilution of precision
|
|||
int32 noise_per_ms # GPS noise per millisecond
|
||||
int32 jamming_indicator # indicates jamming is occurring
|
||||
|
||||
uint64 timestamp_velocity # Time of the velocity estimates since system start, (microseconds)
|
||||
float32 vel_m_s # GPS ground speed, (metres/sec)
|
||||
float32 vel_n_m_s # GPS North velocity, (metres/sec)
|
||||
float32 vel_e_m_s # GPS East velocity, (metres/sec)
|
||||
|
|
|
@ -1 +1 @@
|
|||
Subproject commit 9e7ed8a5ea85c76c5d563413df051f138b9a0622
|
||||
Subproject commit 682fca425e6f3d67ac8062dcc9b36d8bca210175
|
|
@ -691,13 +691,11 @@ GPS::task_main()
|
|||
_report_gps_pos.lat = (int32_t)47.378301e7f;
|
||||
_report_gps_pos.lon = (int32_t)8.538777e7f;
|
||||
_report_gps_pos.alt = (int32_t)1200e3f;
|
||||
_report_gps_pos.timestamp_variance = hrt_absolute_time();
|
||||
_report_gps_pos.s_variance_m_s = 10.0f;
|
||||
_report_gps_pos.c_variance_rad = 0.1f;
|
||||
_report_gps_pos.fix_type = 3;
|
||||
_report_gps_pos.eph = 0.9f;
|
||||
_report_gps_pos.epv = 1.8f;
|
||||
_report_gps_pos.timestamp_velocity = hrt_absolute_time();
|
||||
_report_gps_pos.vel_n_m_s = 0.0f;
|
||||
_report_gps_pos.vel_e_m_s = 0.0f;
|
||||
_report_gps_pos.vel_d_m_s = 0.0f;
|
||||
|
@ -756,10 +754,8 @@ GPS::task_main()
|
|||
|
||||
_report_gps_pos.timestamp_time = hrt_absolute_time();
|
||||
|
||||
/* reset the timestamps for data, because we have no data yet */
|
||||
/* reset the timestamp for data, because we have no data yet */
|
||||
_report_gps_pos.timestamp = 0;
|
||||
_report_gps_pos.timestamp_variance = 0;
|
||||
_report_gps_pos.timestamp_velocity = 0;
|
||||
|
||||
/* set a massive variance */
|
||||
_report_gps_pos.eph = 10000.0f;
|
||||
|
|
|
@ -525,7 +525,7 @@ void Ekf2::task_main()
|
|||
gps_msg.eph = gps.eph;
|
||||
gps_msg.epv = gps.epv;
|
||||
gps_msg.sacc = gps.s_variance_m_s;
|
||||
gps_msg.time_usec_vel = gps.timestamp_velocity;
|
||||
gps_msg.time_usec_vel = gps.timestamp;
|
||||
gps_msg.vel_m_s = gps.vel_m_s;
|
||||
gps_msg.vel_ned[0] = gps.vel_n_m_s;
|
||||
gps_msg.vel_ned[1] = gps.vel_e_m_s;
|
||||
|
@ -910,7 +910,7 @@ void Ekf2::task_main()
|
|||
// only write gps data if we had a gps update.
|
||||
if (gps_updated) {
|
||||
replay.time_usec = gps.timestamp;
|
||||
replay.time_usec_vel = gps.timestamp_velocity;
|
||||
replay.time_usec_vel = gps.timestamp;
|
||||
replay.lat = gps.lat;
|
||||
replay.lon = gps.lon;
|
||||
replay.alt = gps.alt;
|
||||
|
|
|
@ -1791,10 +1791,8 @@ MavlinkReceiver::handle_message_hil_gps(mavlink_message_t *msg)
|
|||
hil_gps.eph = (float)gps.eph * 1e-2f; // from cm to m
|
||||
hil_gps.epv = (float)gps.epv * 1e-2f; // from cm to m
|
||||
|
||||
hil_gps.timestamp_variance = timestamp;
|
||||
hil_gps.s_variance_m_s = 5.0f;
|
||||
|
||||
hil_gps.timestamp_velocity = timestamp;
|
||||
hil_gps.vel_m_s = (float)gps.vel * 1e-2f; // from cm/s to m/s
|
||||
hil_gps.vel_n_m_s = gps.vn * 1e-2f; // from cm to m
|
||||
hil_gps.vel_e_m_s = gps.ve * 1e-2f; // from cm to m
|
||||
|
|
|
@ -1212,7 +1212,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
|
|||
inertial_filter_correct(corr_gps[0][0], dt, x_est, 0, w_xy_gps_p);
|
||||
inertial_filter_correct(corr_gps[1][0], dt, y_est, 0, w_xy_gps_p);
|
||||
|
||||
if (gps.vel_ned_valid && t < gps.timestamp_velocity + gps_topic_timeout) {
|
||||
if (gps.vel_ned_valid && t < gps.timestamp + gps_topic_timeout) {
|
||||
inertial_filter_correct(corr_gps[0][1], dt, x_est, 1, w_xy_gps_v);
|
||||
inertial_filter_correct(corr_gps[1][1], dt, y_est, 1, w_xy_gps_v);
|
||||
}
|
||||
|
|
|
@ -109,8 +109,6 @@ void UavcanGnssBridge::gnss_fix_sub_cb(const uavcan::ReceivedDataStructure<uavca
|
|||
report.lon = msg.longitude_deg_1e8 / 10;
|
||||
report.alt = msg.height_msl_mm;
|
||||
|
||||
report.timestamp_variance = report.timestamp;
|
||||
|
||||
|
||||
// Check if the msg contains valid covariance information
|
||||
const bool valid_position_covariance = !msg.position_covariance.empty();
|
||||
|
@ -163,7 +161,6 @@ void UavcanGnssBridge::gnss_fix_sub_cb(const uavcan::ReceivedDataStructure<uavca
|
|||
|
||||
report.fix_type = msg.status;
|
||||
|
||||
report.timestamp_velocity = report.timestamp;
|
||||
report.vel_n_m_s = msg.ned_velocity[0];
|
||||
report.vel_e_m_s = msg.ned_velocity[1];
|
||||
report.vel_d_m_s = msg.ned_velocity[2];
|
||||
|
|
|
@ -282,10 +282,8 @@ GPSSIM::receive(int timeout)
|
|||
_report_gps_pos.lat = gps.lat;
|
||||
_report_gps_pos.lon = gps.lon;
|
||||
_report_gps_pos.alt = gps.alt;
|
||||
_report_gps_pos.timestamp_variance = _report_gps_pos.timestamp;
|
||||
_report_gps_pos.eph = (float)gps.eph * 1e-2f;
|
||||
_report_gps_pos.epv = (float)gps.epv * 1e-2f;
|
||||
_report_gps_pos.timestamp_velocity = _report_gps_pos.timestamp;
|
||||
_report_gps_pos.vel_m_s = (float)(gps.vel) / 100.0f;
|
||||
_report_gps_pos.vel_n_m_s = (float)(gps.vn) / 100.0f;
|
||||
_report_gps_pos.vel_e_m_s = (float)(gps.ve) / 100.0f;
|
||||
|
@ -310,13 +308,11 @@ GPSSIM::task_main()
|
|||
_report_gps_pos.lat = (int32_t)47.378301e7f;
|
||||
_report_gps_pos.lon = (int32_t)8.538777e7f;
|
||||
_report_gps_pos.alt = (int32_t)1200e3f;
|
||||
_report_gps_pos.timestamp_variance = _report_gps_pos.timestamp;
|
||||
_report_gps_pos.s_variance_m_s = 10.0f;
|
||||
_report_gps_pos.c_variance_rad = 0.1f;
|
||||
_report_gps_pos.fix_type = 3;
|
||||
_report_gps_pos.eph = 0.9f;
|
||||
_report_gps_pos.epv = 1.8f;
|
||||
_report_gps_pos.timestamp_velocity = _report_gps_pos.timestamp;
|
||||
_report_gps_pos.vel_n_m_s = 0.0f;
|
||||
_report_gps_pos.vel_e_m_s = 0.0f;
|
||||
_report_gps_pos.vel_d_m_s = 0.0f;
|
||||
|
@ -343,8 +339,6 @@ GPSSIM::task_main()
|
|||
//Make sure to clear any stale data in case driver is reset
|
||||
memset(&_report_gps_pos, 0, sizeof(_report_gps_pos));
|
||||
_report_gps_pos.timestamp = hrt_absolute_time();
|
||||
_report_gps_pos.timestamp_variance = hrt_absolute_time();
|
||||
_report_gps_pos.timestamp_velocity = hrt_absolute_time();
|
||||
_report_gps_pos.timestamp_time = hrt_absolute_time();
|
||||
|
||||
if (!(m_pub_blocked)) {
|
||||
|
|
Loading…
Reference in New Issue