diff --git a/libraries/APO/AP_Controller.cpp b/libraries/APO/AP_Controller.cpp index 933727a3d5..dca385c29b 100644 --- a/libraries/APO/AP_Controller.cpp +++ b/libraries/APO/AP_Controller.cpp @@ -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); diff --git a/libraries/APO/examples/ServoManual/ServoManual.pde b/libraries/APO/examples/ServoManual/ServoManual.pde index d8abddc9ca..8c28ab1a89 100644 --- a/libraries/APO/examples/ServoManual/ServoManual.pde +++ b/libraries/APO/examples/ServoManual/ServoManual.pde @@ -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