mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Mission: address minor review comments
This commit is contained in:
parent
d845af9bc3
commit
55075961b2
@ -1239,7 +1239,6 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_
|
|||||||
|
|
||||||
case MAV_CMD_DO_FENCE_ENABLE: // MAV ID: 207
|
case MAV_CMD_DO_FENCE_ENABLE: // MAV ID: 207
|
||||||
cmd.p1 = packet.param1; // action 0=disable, 1=enable, 2=disable floor
|
cmd.p1 = packet.param1; // action 0=disable, 1=enable, 2=disable floor
|
||||||
// packet.param2; // bitmask see FENCE_TYPE enum
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MAV_CMD_DO_AUX_FUNCTION:
|
case MAV_CMD_DO_AUX_FUNCTION:
|
||||||
|
@ -357,15 +357,15 @@ bool AP_Mission::start_command_fence(const AP_Mission::Mission_Command& cmd)
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (cmd.p1 == 0) { // disable fence
|
if (cmd.p1 == uint8_t(AC_Fence::MavlinkFenceActions::DISABLE_FENCE)) { // disable fence
|
||||||
uint8_t fences = fence->enable_configured(false);
|
uint8_t fences = fence->enable_configured(false);
|
||||||
fence->print_fence_message("disabled", fences);
|
fence->print_fence_message("disabled", fences);
|
||||||
return true;
|
return true;
|
||||||
} else if (cmd.p1 == 1) { // enable fence
|
} else if (cmd.p1 == uint8_t(AC_Fence::MavlinkFenceActions::ENABLE_FENCE)) { // enable fence
|
||||||
uint8_t fences = fence->enable_configured(true);
|
uint8_t fences = fence->enable_configured(true);
|
||||||
fence->print_fence_message("enabled", fences);
|
fence->print_fence_message("enabled", fences);
|
||||||
return true;
|
return true;
|
||||||
} else if (cmd.p1 == 2) { // disable fence floor only
|
} else if (cmd.p1 == uint8_t(AC_Fence::MavlinkFenceActions::DISABLE_ALT_MIN_FENCE)) { // disable fence floor only
|
||||||
fence->disable_floor();
|
fence->disable_floor();
|
||||||
fence->print_fence_message("disabled", AC_FENCE_TYPE_ALT_MIN);
|
fence->print_fence_message("disabled", AC_FENCE_TYPE_ALT_MIN);
|
||||||
return true;
|
return true;
|
||||||
|
Loading…
Reference in New Issue
Block a user