mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_OADatabase: send_adsb uses vehicle's current altitude
This commit is contained in:
parent
bfa6886e50
commit
9750f99b91
@ -341,6 +341,12 @@ void AP_OADatabase::send_adsb_vehicle(mavlink_channel_t chan, uint16_t interval_
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// use vehicle's current altitude
|
||||||
|
Location current_loc;
|
||||||
|
if (!AP::ahrs().get_position(current_loc)) {
|
||||||
|
current_loc.alt = 0;
|
||||||
|
}
|
||||||
|
|
||||||
const uint8_t chan_as_bitmask = 1 << chan;
|
const uint8_t chan_as_bitmask = 1 << chan;
|
||||||
const char callsign[9] = "OA_DB";
|
const char callsign[9] = "OA_DB";
|
||||||
|
|
||||||
@ -381,7 +387,7 @@ void AP_OADatabase::send_adsb_vehicle(mavlink_channel_t chan, uint16_t interval_
|
|||||||
item_loc.lat,
|
item_loc.lat,
|
||||||
item_loc.lng,
|
item_loc.lng,
|
||||||
0, // altitude_type
|
0, // altitude_type
|
||||||
0, // altitude is always zero
|
current_loc.alt, // use vehicle's current altitude
|
||||||
0, // heading
|
0, // heading
|
||||||
0, // hor_velocity
|
0, // hor_velocity
|
||||||
0, // ver_velocity
|
0, // ver_velocity
|
||||||
|
Loading…
Reference in New Issue
Block a user