Browse Source

AP_Hott_Telem: use GPS single-char representation of fix type

zr-v5.1
Peter Barker 5 years ago committed by Peter Barker
parent
commit
f124cf0991
  1. 13
      libraries/AP_Hott_Telem/AP_Hott_Telem.cpp

13
libraries/AP_Hott_Telem/AP_Hott_Telem.cpp

@ -275,18 +275,7 @@ void AP_Hott_Telem::send_GPS(void) @@ -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…
Cancel
Save