Arming fixes.

This commit is contained in:
James Goppert 2011-10-19 20:09:06 -04:00
parent b16666bf2f
commit 4e89f61e27
4 changed files with 9 additions and 9 deletions

View File

@ -55,8 +55,8 @@ static const bool rangeFinderDownEnabled = false;
// loop rates
static const float loopRate = 250; // attitude nav
static const float loop0Rate = 40; // controller
static const float loop1Rate = 5; // pos nav/ gcs fast
static const float loop0Rate = 50; // controller
static const float loop1Rate = 10; // pos nav/ gcs fast
static const float loop2Rate = 1; // gcs slow
static const float loop3Rate = 0.1;

View File

@ -15,7 +15,7 @@ namespace apo {
void AP_ArmingMechanism::update(const float dt) {
// arming
if ( (_hal->getState() != MAV_STATE_ACTIVE) &
if ( (_hal->getState() != MAV_STATE_ACTIVE) &&
(_hal->rc[_ch1]->getRadioPosition() < _ch1Min) &&
(_hal->rc[_ch2]->getRadioPosition() < _ch2Min) ) {
@ -30,7 +30,7 @@ void AP_ArmingMechanism::update(const float dt) {
}
}
// disarming
else if ( (_hal->getState() == MAV_STATE_ACTIVE) &
else if ( (_hal->getState() == MAV_STATE_ACTIVE) &&
(_hal->rc[_ch1]->getRadioPosition() < _ch1Min) &&
(_hal->rc[_ch2]->getRadioPosition() > _ch2Max) ) {

View File

@ -28,7 +28,7 @@ public:
AP_ArmingMechanism(AP_HardwareAbstractionLayer * hal,
uint8_t ch1, uint8_t ch2, float ch1Min, float ch2Min,
float ch2Max) : _armingClock(0), _hal(hal), _ch1(ch1), _ch2(ch2),
_ch1Min(ch1Min), _ch2Min(ch2Min) {
_ch1Min(ch1Min), _ch2Min(ch2Min), _ch2Max(ch2Max) {
}
/**

View File

@ -98,9 +98,9 @@ AP_Autopilot::AP_Autopilot(AP_Navigator * navigator, AP_Guide * guide,
*/
hal->debug->println_P(PSTR("attaching loops"));
subLoops().push_back(new Loop(loop0Rate, callback0, this));
subLoops()[0]->subLoops().push_back(new Loop(loop1Rate, callback1, this));
subLoops()[0]->subLoops()[0]->subLoops().push_back(new Loop(loop2Rate, callback2, this));
subLoops()[0]->subLoops()[0]->subLoops()[0]->subLoops().push_back(new Loop(loop3Rate, callback3, this));
subLoops().push_back(new Loop(loop1Rate, callback1, this));
subLoops().push_back(new Loop(loop2Rate, callback2, this));
subLoops().push_back(new Loop(loop3Rate, callback3, this));
hal->debug->println_P(PSTR("running"));
hal->gcs->sendText(SEVERITY_LOW, PSTR("running"));
@ -162,7 +162,7 @@ void AP_Autopilot::callback1(void * data) {
* slow navigation loop update
*/
if (apo->getNavigator()) {
apo->getNavigator()->updateSlow(apo->subLoops()[0]->subLoops()[0]->dt());
apo->getNavigator()->updateSlow(apo->subLoops()[1]->dt());
}
/*