mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Added loop priority, fixed arming bug for apo.
This commit is contained in:
parent
35e8503b9e
commit
73c3f1098a
@ -54,9 +54,9 @@ static const bool rangeFinderUpEnabled = false;
|
||||
static const bool rangeFinderDownEnabled = false;
|
||||
|
||||
// loop rates
|
||||
static const float loopRate = 400; // attitude nav
|
||||
static const float loop0Rate = 50; // controller
|
||||
static const float loop1Rate = 10; // pos nav/ gcs fast
|
||||
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 loop2Rate = 1; // gcs slow
|
||||
static const float loop3Rate = 0.1;
|
||||
|
||||
|
@ -52,7 +52,7 @@ public:
|
||||
private:
|
||||
|
||||
AP_HardwareAbstractionLayer * _hal;
|
||||
uint8_t _armingClock;
|
||||
int8_t _armingClock;
|
||||
uint8_t _ch1; /// typically throttle channel
|
||||
uint8_t _ch2; /// typically yaw channel
|
||||
float _ch1Min; /// arms/disarms below this on ch1
|
||||
|
@ -94,13 +94,13 @@ AP_Autopilot::AP_Autopilot(AP_Navigator * navigator, AP_Guide * guide,
|
||||
AP_MavlinkCommand::home.getCommand());
|
||||
|
||||
/*
|
||||
* Attach loops
|
||||
* Attach loops, stacking for priority
|
||||
*/
|
||||
hal->debug->println_P(PSTR("attaching loops"));
|
||||
subLoops().push_back(new Loop(loop0Rate, callback0, 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));
|
||||
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));
|
||||
|
||||
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()[1]->dt());
|
||||
apo->getNavigator()->updateSlow(apo->subLoops()[0]->subLoops()[0]->dt());
|
||||
}
|
||||
|
||||
/*
|
||||
|
Loading…
Reference in New Issue
Block a user