mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
Fixed mode switching.
This commit is contained in:
parent
64de8371a2
commit
999a5892f0
@ -43,6 +43,24 @@ void AP_Controller::setAllRadioChannelsManually() {
|
||||
|
||||
void AP_Controller::update(const float dt) {
|
||||
if (_armingMechanism) _armingMechanism->update(dt);
|
||||
// handle modes
|
||||
//
|
||||
// if in locked mode
|
||||
if (getMode() == MAV_MODE_LOCKED) {
|
||||
// if state is not stanby then set it to standby and alert gcs
|
||||
if (getState()!=MAV_STATE_STANDBY) {
|
||||
setState(MAV_STATE_STANDBY);
|
||||
_hal->gcs->sendText(SEVERITY_HIGH, PSTR("disarmed"));
|
||||
}
|
||||
}
|
||||
// if not locked
|
||||
else {
|
||||
|
||||
// if state is not active, set it to active and alert gcs
|
||||
if (getState()!=MAV_STATE_ACTIVE) {
|
||||
setState(MAV_STATE_ACTIVE);
|
||||
_hal->gcs->sendText(SEVERITY_HIGH, PSTR("armed"));
|
||||
}
|
||||
|
||||
// handle emergencies
|
||||
//
|
||||
@ -57,24 +75,6 @@ void AP_Controller::update(const float dt) {
|
||||
_hal->gcs->sendText(SEVERITY_HIGH, PSTR("recharge battery"));
|
||||
}
|
||||
|
||||
// handle modes
|
||||
//
|
||||
// if in locked mode
|
||||
if (getMode() == MAV_MODE_LOCKED) {
|
||||
// if state is not stanby then set it to standby and alert gcs
|
||||
if (getState()!=MAV_STATE_STANDBY) {
|
||||
setState(MAV_STATE_STANDBY);
|
||||
_hal->gcs->sendText(SEVERITY_HIGH, PSTR("disarmed"));
|
||||
}
|
||||
}
|
||||
// if not locked
|
||||
else {
|
||||
// if state is not active, set it to active and alert gcs
|
||||
if (getState()!=MAV_STATE_ACTIVE) {
|
||||
setState(MAV_STATE_ACTIVE);
|
||||
_hal->gcs->sendText(SEVERITY_HIGH, PSTR("armed"));
|
||||
}
|
||||
|
||||
// if in auto mode and manual switch set, change to manual
|
||||
if (_hal->rc[_chMode]->getRadioPosition() > 0) setMode(MAV_MODE_MANUAL);
|
||||
else setMode(MAV_MODE_AUTO);
|
||||
@ -84,6 +84,8 @@ void AP_Controller::update(const float dt) {
|
||||
manualLoop(dt);
|
||||
} else if (getMode()==MAV_MODE_AUTO) {
|
||||
autoLoop(dt);
|
||||
} else if (getMode()==MAV_MODE_FAILSAFE) {
|
||||
handleFailsafe();
|
||||
} else {
|
||||
_hal->gcs->sendText(SEVERITY_HIGH, PSTR("unknown mode"));
|
||||
setMode(MAV_MODE_FAILSAFE);
|
||||
|
Loading…
Reference in New Issue
Block a user