mirror of https://github.com/ArduPilot/ardupilot
Fixed APO controller bug preventing motor arming.
This commit is contained in:
parent
c0c771042f
commit
5d9c37bbed
|
@ -35,8 +35,10 @@ void AP_Controller::setAllRadioChannelsToNeutral() {
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_Controller::setAllRadioChannelsManually() {
|
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++) {
|
for (uint8_t i = 0; i < _hal->rc.getSize(); i++) {
|
||||||
_hal->rc[i]->setUsingRadio();
|
_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: {
|
case MAV_STATE_ACTIVE: {
|
||||||
digitalWrite(_hal->aLedPin, HIGH);
|
digitalWrite(_hal->aLedPin, HIGH);
|
||||||
setMotorsActive();
|
setMotorsActive();
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
case MAV_STATE_EMERGENCY: {
|
case MAV_STATE_EMERGENCY: {
|
||||||
digitalWrite(_hal->aLedPin, LOW);
|
digitalWrite(_hal->aLedPin, LOW);
|
||||||
|
|
|
@ -61,7 +61,7 @@ public:
|
||||||
new AP_RcChannel(ch8Key, PSTR("CH8"), APM_RC, 7, 1100, 1500,
|
new AP_RcChannel(ch8Key, PSTR("CH8"), APM_RC, 7, 1100, 1500,
|
||||||
1900, RC_MODE_INOUT, false));
|
1900, RC_MODE_INOUT, false));
|
||||||
|
|
||||||
Serial.begin(115200);
|
Serial.begin(57600);
|
||||||
delay(2000);
|
delay(2000);
|
||||||
Serial.println("ArduPilot RC Channel test");
|
Serial.println("ArduPilot RC Channel test");
|
||||||
APM_RC.Init(); // APM Radio initialization
|
APM_RC.Init(); // APM Radio initialization
|
||||||
|
|
Loading…
Reference in New Issue