mirror of https://github.com/ArduPilot/ardupilot
Blimp: create and use location_from_command_t
This commit is contained in:
parent
8df3c5a346
commit
7775b519bb
|
@ -450,19 +450,10 @@ MAV_RESULT GCS_MAVLINK_Blimp::handle_command_int_do_reposition(const mavlink_com
|
|||
}
|
||||
|
||||
Location request_location {};
|
||||
request_location.lat = packet.x;
|
||||
request_location.lng = packet.y;
|
||||
|
||||
if (fabsf(packet.z) > LOCATION_ALT_MAX_M) {
|
||||
if (!location_from_command_t(packet, request_location)) {
|
||||
return MAV_RESULT_DENIED;
|
||||
}
|
||||
|
||||
Location::AltFrame frame;
|
||||
if (!mavlink_coordinate_frame_to_location_alt_frame((MAV_FRAME)packet.frame, frame)) {
|
||||
return MAV_RESULT_DENIED; // failed as the location is not valid
|
||||
}
|
||||
request_location.set_alt_cm((int32_t)(packet.z * 100.0f), frame);
|
||||
|
||||
if (request_location.sanitize(blimp.current_loc)) {
|
||||
// if the location wasn't already sane don't load it
|
||||
return MAV_RESULT_DENIED; // failed as the location is not valid
|
||||
|
|
Loading…
Reference in New Issue