mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
Incorporated dcm changes from arducopter into apo.
This commit is contained in:
parent
4b7d52b233
commit
4653ea7629
@ -80,6 +80,19 @@ public:
|
||||
pinMode(slideSwitchPin, INPUT);
|
||||
pinMode(pushButtonPin, INPUT);
|
||||
DDRL |= B00000100; // set port L, pint 2 to output for the relay
|
||||
} else if (board == BOARD_ARDUPILOTMEGA_2) {
|
||||
slideSwitchPin = 40;
|
||||
pushButtonPin = 41;
|
||||
aLedPin = 37;
|
||||
bLedPin = 36;
|
||||
cLedPin = 35;
|
||||
eepromMaxAddr = 2048;
|
||||
pinMode(aLedPin, OUTPUT); // extra led
|
||||
pinMode(bLedPin, OUTPUT); // imu ledclass AP_CommLink;
|
||||
pinMode(cLedPin, OUTPUT); // gps led
|
||||
pinMode(slideSwitchPin, INPUT);
|
||||
pinMode(pushButtonPin, INPUT);
|
||||
DDRL |= B00000100; // set port L, pint 2 to output for the relay
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -69,13 +69,25 @@ DcmNavigator::DcmNavigator(AP_HardwareAbstractionLayer * hal) :
|
||||
}
|
||||
|
||||
if (_hal->getMode() == MODE_LIVE) {
|
||||
if (_hal->adc)
|
||||
|
||||
if (_hal->adc) {
|
||||
_hal->imu = new AP_IMU_Oilpan(_hal->adc, k_sensorCalib);
|
||||
if (_hal->imu)
|
||||
}
|
||||
|
||||
if (_hal->imu) {
|
||||
_dcm = new AP_DCM(_hal->imu, _hal->gps, _hal->compass);
|
||||
|
||||
// tune down dcm
|
||||
_dcm->kp_roll_pitch(0.030000);
|
||||
_dcm->ki_roll_pitch(0.00001278), // 50 hz I term
|
||||
|
||||
// tune down compass in dcm
|
||||
_dcm->kp_yaw(0.08);
|
||||
_dcm->ki_yaw(0);
|
||||
}
|
||||
|
||||
if (_hal->compass) {
|
||||
_dcm->set_compass(_hal->compass);
|
||||
|
||||
}
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user