Copter: move command-long DO_SET_HOME up

This commit is contained in:
Peter Barker 2019-03-05 22:57:41 +11:00 committed by Peter Barker
parent 6b26e87854
commit f4a21d446f
1 changed files with 0 additions and 24 deletions

View File

@ -645,30 +645,6 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
}
return MAV_RESULT_FAILED;
case MAV_CMD_DO_SET_HOME:
// param1 : use current (1=use current location, 0=use specified location)
// param5 : latitude
// param6 : longitude
// param7 : altitude (absolute)
if (is_equal(packet.param1,1.0f)) {
if (copter.set_home_to_current_location(true)) {
return MAV_RESULT_ACCEPTED;
}
} else {
// ensure param1 is zero
if (!is_zero(packet.param1)) {
return MAV_RESULT_FAILED;
}
Location new_home_loc;
new_home_loc.lat = (int32_t)(packet.param5 * 1.0e7f);
new_home_loc.lng = (int32_t)(packet.param6 * 1.0e7f);
new_home_loc.alt = (int32_t)(packet.param7 * 100.0f);
if (copter.set_home(new_home_loc, true)) {
return MAV_RESULT_ACCEPTED;
}
}
return MAV_RESULT_FAILED;
#if MODE_AUTO_ENABLED == ENABLED
case MAV_CMD_MISSION_START:
if (copter.motors->armed() && copter.set_mode(AUTO, MODE_REASON_GCS_COMMAND)) {