mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: support Fix2 message for UAVCAN
this allows for RTK fix levels
This commit is contained in:
parent
69b199cefa
commit
44257a0247
|
@ -1002,7 +1002,7 @@ void AP_GPS::send_mavlink_gps_raw(mavlink_channel_t chan)
|
|||
hacc * 1000, // one-sigma standard deviation in mm
|
||||
vacc * 1000, // one-sigma standard deviation in mm
|
||||
sacc * 1000, // one-sigma standard deviation in mm/s
|
||||
0, 0); // TODO one-sigma heading accuracy standard deviation
|
||||
0); // TODO one-sigma heading accuracy standard deviation
|
||||
}
|
||||
|
||||
#if GPS_MAX_RECEIVERS > 1
|
||||
|
@ -1032,7 +1032,7 @@ void AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan)
|
|||
ground_course(1)*100, // 1/100 degrees,
|
||||
num_sats(1),
|
||||
state[1].rtk_num_sats,
|
||||
state[1].rtk_age_ms, 0);
|
||||
state[1].rtk_age_ms);
|
||||
}
|
||||
#endif // GPS_MAX_RECEIVERS
|
||||
|
||||
|
|
|
@ -249,6 +249,15 @@ void AP_GPS_UAVCAN::handle_fix_msg(const FixCb &cb)
|
|||
interim_state.last_gps_time_ms = AP_HAL::millis();
|
||||
|
||||
_new_data = true;
|
||||
if (!seen_message) {
|
||||
if (interim_state.status == AP_GPS::GPS_Status::NO_GPS) {
|
||||
// the first time we see a fix message we change from
|
||||
// NO_GPS to NO_FIX, indicating to user that a UAVCAN GPS
|
||||
// has been seen
|
||||
interim_state.status = AP_GPS::GPS_Status::NO_FIX;
|
||||
}
|
||||
seen_message = true;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -62,8 +62,6 @@ private:
|
|||
HAL_Semaphore sem;
|
||||
|
||||
uint8_t _detected_module;
|
||||
bool seen_message;
|
||||
|
||||
bool seen_message;
|
||||
bool seen_fix2;
|
||||
bool seen_aux;
|
||||
|
|
|
@ -23,7 +23,6 @@
|
|||
#include <AP_HAL/Util.h>
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
#include <stdio.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || \
|
||||
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH
|
||||
|
|
Loading…
Reference in New Issue