mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Blimp: use MAVLink POSITION_TARGET_TYPEMASK
This commit is contained in:
parent
14d351c2fd
commit
bb00340171
@ -94,11 +94,16 @@ void GCS_MAVLINK_Blimp::send_position_target_global_int()
|
||||
if (!blimp.flightmode->get_wp(target)) {
|
||||
return;
|
||||
}
|
||||
static constexpr uint16_t POSITION_TARGET_TYPEMASK_LAST_BYTE = 0xF000;
|
||||
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_FORCE_SET | POSITION_TARGET_TYPEMASK_YAW_IGNORE | POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE | POSITION_TARGET_TYPEMASK_LAST_BYTE;
|
||||
|
||||
mavlink_msg_position_target_global_int_send(
|
||||
chan,
|
||||
AP_HAL::millis(), // time_boot_ms
|
||||
MAV_FRAME_GLOBAL, // targets are always global altitude
|
||||
0xFFF8, // ignore everything except the x/y/z components
|
||||
TYPE_MASK, // ignore everything except the x/y/z components
|
||||
target.lat, // latitude as 1e7
|
||||
target.lng, // longitude as 1e7
|
||||
target.alt * 0.01f, // altitude is sent as a float
|
||||
|
Loading…
Reference in New Issue
Block a user