Fixed APO controller bug preventing motor arming.

This commit is contained in:
James Goppert 2011-10-27 16:19:42 -04:00
parent 5a44298d57
commit d1d82077c7
2 changed files with 4 additions and 1 deletions

View File

@ -35,8 +35,10 @@ void AP_Controller::setAllRadioChannelsToNeutral() {
}
void AP_Controller::setAllRadioChannelsManually() {
//_hal->debug->printf_P(PSTR("\tsize: %d\n"),_hal->rc.getSize());
for (uint8_t i = 0; i < _hal->rc.getSize(); i++) {
_hal->rc[i]->setUsingRadio();
//_hal->debug->printf_P(PSTR("\trc %d: %f\n"),i,_hal->rc[i]->getPosition());
}
}
@ -100,6 +102,7 @@ void AP_Controller::setMotors() {
case MAV_STATE_ACTIVE: {
digitalWrite(_hal->aLedPin, HIGH);
setMotorsActive();
break;
}
case MAV_STATE_EMERGENCY: {
digitalWrite(_hal->aLedPin, LOW);

View File

@ -61,7 +61,7 @@ public:
new AP_RcChannel(ch8Key, PSTR("CH8"), APM_RC, 7, 1100, 1500,
1900, RC_MODE_INOUT, false));
Serial.begin(115200);
Serial.begin(57600);
delay(2000);
Serial.println("ArduPilot RC Channel test");
APM_RC.Init(); // APM Radio initialization