mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-11 02:13:57 -04:00
AP_Mount: fill in all Location flags in ROI pointing
This commit is contained in:
parent
cf76dcfbf3
commit
81f60bde06
@ -57,9 +57,11 @@ void AP_Mount_Backend::control_msg(mavlink_message_t *msg)
|
|||||||
// set lat, lon, alt position targets from mavlink message
|
// set lat, lon, alt position targets from mavlink message
|
||||||
case MAV_MOUNT_MODE_GPS_POINT:
|
case MAV_MOUNT_MODE_GPS_POINT:
|
||||||
Location target_location;
|
Location target_location;
|
||||||
|
memset(&target_location, 0, sizeof(target_location));
|
||||||
target_location.lat = packet.input_a;
|
target_location.lat = packet.input_a;
|
||||||
target_location.lng = packet.input_b;
|
target_location.lng = packet.input_b;
|
||||||
target_location.alt = packet.input_c;
|
target_location.alt = packet.input_c;
|
||||||
|
target_location.flags.relative_alt = true;
|
||||||
set_roi_target(target_location);
|
set_roi_target(target_location);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user