mirror of https://github.com/ArduPilot/ardupilot
AP_GPS_MAV: use GPS_INPUT_IGNORE_FLAGS
This commit is contained in:
parent
e34aa0bc72
commit
6e224158f1
|
@ -46,14 +46,14 @@ void AP_GPS_MAV::handle_msg(mavlink_message_t *msg)
|
|||
mavlink_gps_input_t packet;
|
||||
mavlink_msg_gps_input_decode(msg, &packet);
|
||||
|
||||
bool have_alt = ((packet.ignore_flags & (1<<0)) == 0);
|
||||
bool have_hdop = ((packet.ignore_flags & (1<<1)) == 0);
|
||||
bool have_vdop = ((packet.ignore_flags & (1<<2)) == 0);
|
||||
bool have_vel_h = ((packet.ignore_flags & (1<<3)) == 0);
|
||||
bool have_vel_v = ((packet.ignore_flags & (1<<4)) == 0);
|
||||
bool have_sa = ((packet.ignore_flags & (1<<5)) == 0);
|
||||
bool have_ha = ((packet.ignore_flags & (1<<6)) == 0);
|
||||
bool have_va = ((packet.ignore_flags & (1<<7)) == 0);
|
||||
bool have_alt = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_ALT) == 0);
|
||||
bool have_hdop = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_HDOP) == 0);
|
||||
bool have_vdop = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_VDOP) == 0);
|
||||
bool have_vel_h = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_VEL_HORIZ) == 0);
|
||||
bool have_vel_v = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_VEL_VERT) == 0);
|
||||
bool have_sa = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_SPEED_ACCURACY) == 0);
|
||||
bool have_ha = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_HORIZONTAL_ACCURACY) == 0);
|
||||
bool have_va = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_VERTICAL_ACCURACY) == 0);
|
||||
|
||||
state.time_week = packet.time_week;
|
||||
state.time_week_ms = packet.time_week_ms;
|
||||
|
|
Loading…
Reference in New Issue