mirror of https://github.com/ArduPilot/ardupilot
Plane: use MAV_FRAME_GLOBAL instead of MAV_FRAME_GLOBAL_INT in send_position_target
This commit is contained in:
parent
5538800ad0
commit
05c608e725
|
@ -198,7 +198,7 @@ void GCS_MAVLINK_Plane::send_position_target_global_int()
|
||||||
mavlink_msg_position_target_global_int_send(
|
mavlink_msg_position_target_global_int_send(
|
||||||
chan,
|
chan,
|
||||||
AP_HAL::millis(), // time_boot_ms
|
AP_HAL::millis(), // time_boot_ms
|
||||||
MAV_FRAME_GLOBAL_INT, // targets are always global altitude
|
MAV_FRAME_GLOBAL, // targets are always global altitude
|
||||||
0xFFF8, // ignore everything except the x/y/z components
|
0xFFF8, // ignore everything except the x/y/z components
|
||||||
next_WP_loc.lat, // latitude as 1e7
|
next_WP_loc.lat, // latitude as 1e7
|
||||||
next_WP_loc.lng, // longitude as 1e7
|
next_WP_loc.lng, // longitude as 1e7
|
||||||
|
|
Loading…
Reference in New Issue