mirror of https://github.com/ArduPilot/ardupilot
APMRover2: unhide default NAVL1_PERIOD with a define
set the correct value to param
This commit is contained in:
parent
01e01d1df9
commit
d4bd61d859
|
@ -621,5 +621,5 @@ void Rover::load_parameters(void)
|
||||||
cliSerial->printf("load_all took %luus\n", micros() - before);
|
cliSerial->printf("load_all took %luus\n", micros() - before);
|
||||||
|
|
||||||
// set a more reasonable default NAVL1_PERIOD for rovers
|
// set a more reasonable default NAVL1_PERIOD for rovers
|
||||||
L1_controller.set_default_period(8);
|
L1_controller.set_default_period(NAVL1_PERIOD);
|
||||||
}
|
}
|
||||||
|
|
|
@ -182,6 +182,13 @@
|
||||||
#define CAMERA ENABLED
|
#define CAMERA ENABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
|
// NAVL1
|
||||||
|
//
|
||||||
|
#ifndef NAVL1
|
||||||
|
#define NAVL1_PERIOD 8
|
||||||
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// AIRSPEED_CRUISE
|
// AIRSPEED_CRUISE
|
||||||
//
|
//
|
||||||
|
|
|
@ -27,7 +27,7 @@ MODE5 2
|
||||||
MODE6 0
|
MODE6 0
|
||||||
STEER2SRV_P 1.8
|
STEER2SRV_P 1.8
|
||||||
SIM_GPS_DELAY 1
|
SIM_GPS_DELAY 1
|
||||||
NAVL1_PERIOD 6
|
NAVL1_PERIOD 8
|
||||||
# we need small INS_ACC offsets so INS is recognised as being calibrated
|
# we need small INS_ACC offsets so INS is recognised as being calibrated
|
||||||
INS_ACCOFFS_X 0.001
|
INS_ACCOFFS_X 0.001
|
||||||
INS_ACCOFFS_Y 0.001
|
INS_ACCOFFS_Y 0.001
|
||||||
|
|
|
@ -21,7 +21,7 @@ MODE5 2
|
||||||
MODE6 0
|
MODE6 0
|
||||||
STEER2SRV_P 1.8
|
STEER2SRV_P 1.8
|
||||||
SIM_GPS_DELAY 1
|
SIM_GPS_DELAY 1
|
||||||
NAVL1_PERIOD 6
|
NAVL1_PERIOD 8
|
||||||
# we need small INS_ACC offsets so INS is recognised as being calibrated
|
# we need small INS_ACC offsets so INS is recognised as being calibrated
|
||||||
INS_ACCOFFS_X 0.001
|
INS_ACCOFFS_X 0.001
|
||||||
INS_ACCOFFS_Y 0.001
|
INS_ACCOFFS_Y 0.001
|
||||||
|
|
Loading…
Reference in New Issue