Browse Source

APMRover2: unhide default NAVL1_PERIOD with a define

set the correct value to param
master
Pierre Kancir 8 years ago committed by Grant Morphett
parent
commit
d4bd61d859
  1. 2
      APMrover2/Parameters.cpp
  2. 7
      APMrover2/config.h
  3. 2
      Tools/autotest/default_params/rover-skid.parm
  4. 2
      Tools/autotest/default_params/rover.parm

2
APMrover2/Parameters.cpp

@ -621,5 +621,5 @@ void Rover::load_parameters(void) @@ -621,5 +621,5 @@ void Rover::load_parameters(void)
cliSerial->printf("load_all took %luus\n", micros() - before);
// set a more reasonable default NAVL1_PERIOD for rovers
L1_controller.set_default_period(8);
L1_controller.set_default_period(NAVL1_PERIOD);
}

7
APMrover2/config.h

@ -182,6 +182,13 @@ @@ -182,6 +182,13 @@
#define CAMERA ENABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// NAVL1
//
#ifndef NAVL1
#define NAVL1_PERIOD 8
#endif
//////////////////////////////////////////////////////////////////////////////
// AIRSPEED_CRUISE
//

2
Tools/autotest/default_params/rover-skid.parm

@ -27,7 +27,7 @@ MODE5 2 @@ -27,7 +27,7 @@ MODE5 2
MODE6 0
STEER2SRV_P 1.8
SIM_GPS_DELAY 1
NAVL1_PERIOD 6
NAVL1_PERIOD 8
# we need small INS_ACC offsets so INS is recognised as being calibrated
INS_ACCOFFS_X 0.001
INS_ACCOFFS_Y 0.001

2
Tools/autotest/default_params/rover.parm

@ -21,7 +21,7 @@ MODE5 2 @@ -21,7 +21,7 @@ MODE5 2
MODE6 0
STEER2SRV_P 1.8
SIM_GPS_DELAY 1
NAVL1_PERIOD 6
NAVL1_PERIOD 8
# we need small INS_ACC offsets so INS is recognised as being calibrated
INS_ACCOFFS_X 0.001
INS_ACCOFFS_Y 0.001

Loading…
Cancel
Save