Added missing const to apo settings files.
This commit is contained in:
parent
57e4a80fe1
commit
905200c7e4
@ -28,10 +28,10 @@ static const uint8_t heartBeatTimeout = 3;
|
||||
#define RANGE_FINDER_CLASS AP_RangeFinder_MaxsonarXL
|
||||
|
||||
// baud rates
|
||||
static uint32_t debugBaud = 57600;
|
||||
static uint32_t telemBaud = 57600;
|
||||
static uint32_t gpsBaud = 38400;
|
||||
static uint32_t hilBaud = 57600;
|
||||
static const uint32_t debugBaud = 57600;
|
||||
static const uint32_t telemBaud = 57600;
|
||||
static const uint32_t gpsBaud = 38400;
|
||||
static const uint32_t hilBaud = 57600;
|
||||
|
||||
// optional sensors
|
||||
static const bool gpsEnabled = false;
|
||||
|
@ -28,10 +28,10 @@ static const uint8_t heartBeatTimeout = 3;
|
||||
#define RANGE_FINDER_CLASS AP_RangeFinder_MaxsonarXL
|
||||
|
||||
// baud rates
|
||||
static uint32_t debugBaud = 57600;
|
||||
static uint32_t telemBaud = 57600;
|
||||
static uint32_t gpsBaud = 38400;
|
||||
static uint32_t hilBaud = 57600;
|
||||
static const uint32_t debugBaud = 57600;
|
||||
static const uint32_t telemBaud = 57600;
|
||||
static const uint32_t gpsBaud = 38400;
|
||||
static const uint32_t hilBaud = 57600;
|
||||
|
||||
// optional sensors
|
||||
static const bool gpsEnabled = false;
|
||||
|
@ -29,10 +29,10 @@ static const uint8_t heartBeatTimeout = 3;
|
||||
#define RANGE_FINDER_CLASS AP_RangeFinder_MaxsonarXL
|
||||
|
||||
// baud rates
|
||||
static uint32_t debugBaud = 57600;
|
||||
static uint32_t telemBaud = 57600;
|
||||
static uint32_t gpsBaud = 38400;
|
||||
static uint32_t hilBaud = 57600;
|
||||
static const uint32_t debugBaud = 57600;
|
||||
static const uint32_t telemBaud = 57600;
|
||||
static const uint32_t gpsBaud = 38400;
|
||||
static const uint32_t hilBaud = 57600;
|
||||
|
||||
// optional sensors
|
||||
static const bool gpsEnabled = false;
|
||||
|
@ -27,10 +27,10 @@ static const uint8_t heartBeatTimeout = 3;
|
||||
#define RANGE_FINDER_CLASS AP_RangeFinder_MaxsonarXL
|
||||
|
||||
// baud rates
|
||||
static uint32_t debugBaud = 57600;
|
||||
static uint32_t telemBaud = 57600;
|
||||
static uint32_t gpsBaud = 38400;
|
||||
static uint32_t hilBaud = 57600;
|
||||
static const uint32_t debugBaud = 57600;
|
||||
static const uint32_t telemBaud = 57600;
|
||||
static const uint32_t gpsBaud = 38400;
|
||||
static const uint32_t hilBaud = 57600;
|
||||
|
||||
// optional sensors
|
||||
static const bool gpsEnabled = false;
|
||||
|
@ -27,10 +27,10 @@ static const uint8_t heartBeatTimeout = 3;
|
||||
#define RANGE_FINDER_CLASS AP_RangeFinder_MaxsonarXL
|
||||
|
||||
// baud rates
|
||||
static uint32_t debugBaud = 57600;
|
||||
static uint32_t telemBaud = 57600;
|
||||
static uint32_t gpsBaud = 38400;
|
||||
static uint32_t hilBaud = 57600;
|
||||
static const uint32_t debugBaud = 57600;
|
||||
static const uint32_t telemBaud = 57600;
|
||||
static const uint32_t gpsBaud = 38400;
|
||||
static const uint32_t hilBaud = 57600;
|
||||
|
||||
// optional sensors
|
||||
static const bool gpsEnabled = false;
|
||||
|
Loading…
Reference in New Issue
Block a user