mirror of https://github.com/ArduPilot/ardupilot
Plane: convert next WP alt to global frame in POSITION_TARGET_GLOBAL_INT
This commit is contained in:
parent
0c7ad9511f
commit
d914e4e63b
|
@ -214,6 +214,11 @@ void GCS_MAVLINK_Plane::send_position_target_global_int()
|
|||
static constexpr uint16_t TYPE_MASK = POSITION_TARGET_TYPEMASK_VX_IGNORE | POSITION_TARGET_TYPEMASK_VY_IGNORE | POSITION_TARGET_TYPEMASK_VZ_IGNORE |
|
||||
POSITION_TARGET_TYPEMASK_AX_IGNORE | POSITION_TARGET_TYPEMASK_AY_IGNORE | POSITION_TARGET_TYPEMASK_AZ_IGNORE |
|
||||
POSITION_TARGET_TYPEMASK_YAW_IGNORE | POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE | POSITION_TARGET_TYPEMASK_LAST_BYTE;
|
||||
int32_t alt = 0;
|
||||
if (!next_WP_loc.is_zero()) {
|
||||
UNUSED_RESULT(next_WP_loc.get_alt_cm(Location::AltFrame::ABSOLUTE, alt));
|
||||
}
|
||||
|
||||
mavlink_msg_position_target_global_int_send(
|
||||
chan,
|
||||
AP_HAL::millis(), // time_boot_ms
|
||||
|
@ -221,7 +226,7 @@ void GCS_MAVLINK_Plane::send_position_target_global_int()
|
|||
TYPE_MASK, // ignore everything except the x/y/z components
|
||||
next_WP_loc.lat, // latitude as 1e7
|
||||
next_WP_loc.lng, // longitude as 1e7
|
||||
next_WP_loc.alt * 0.01f, // altitude is sent as a float
|
||||
alt * 0.01, // altitude is sent as a float
|
||||
0.0f, // vx
|
||||
0.0f, // vy
|
||||
0.0f, // vz
|
||||
|
|
Loading…
Reference in New Issue