mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_Mount: adjust for Location_Class and Location unification
This commit is contained in:
parent
b12dc3cde7
commit
2f3237143f
@ -61,15 +61,17 @@ void AP_Mount_Backend::control(int32_t pitch_or_lat, int32_t roll_or_lon, int32_
|
|||||||
break;
|
break;
|
||||||
|
|
||||||
// set lat, lon, alt position targets from mavlink message
|
// set lat, lon, alt position targets from mavlink message
|
||||||
case MAV_MOUNT_MODE_GPS_POINT:
|
|
||||||
Location target_location;
|
case MAV_MOUNT_MODE_GPS_POINT: {
|
||||||
memset(&target_location, 0, sizeof(target_location));
|
const Location target_location{
|
||||||
target_location.lat = pitch_or_lat;
|
pitch_or_lat,
|
||||||
target_location.lng = roll_or_lon;
|
roll_or_lon,
|
||||||
target_location.alt = yaw_or_alt;
|
yaw_or_alt,
|
||||||
target_location.relative_alt = true;
|
Location::ALT_FRAME_ABOVE_HOME
|
||||||
|
};
|
||||||
set_roi_target(target_location);
|
set_roi_target(target_location);
|
||||||
break;
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
default:
|
default:
|
||||||
// do nothing
|
// do nothing
|
||||||
|
Loading…
Reference in New Issue
Block a user