mirror of https://github.com/ArduPilot/ardupilot
AP_Hott_Telem: use GPS single-char representation of fix type
This commit is contained in:
parent
9da9d8c94b
commit
f124cf0991
|
@ -275,18 +275,7 @@ void AP_Hott_Telem::send_GPS(void)
|
|||
msg.vel_east = vel.y * 1000 + 0.5;
|
||||
msg.altitude = uint16_t(500.5 + alt);
|
||||
|
||||
switch (gps.status()) {
|
||||
case AP_GPS::NO_GPS:
|
||||
case AP_GPS::NO_FIX:
|
||||
msg.gps_fix_char = '-';
|
||||
break;
|
||||
case AP_GPS::GPS_OK_FIX_2D:
|
||||
msg.gps_fix_char = '2';
|
||||
break;
|
||||
default:
|
||||
msg.gps_fix_char = '3';
|
||||
break;
|
||||
}
|
||||
msg.gps_fix_char = gps.status_onechar();
|
||||
msg.free_char3 = msg.gps_fix_char;
|
||||
|
||||
msg.home_direction = degrees(atan2f(home_vec.y, home_vec.x)) * 0.5 + 0.5;
|
||||
|
|
Loading…
Reference in New Issue