mirror of https://github.com/ArduPilot/ardupilot
Replay: use ARRAY_SIZE macro
This commit is contained in:
parent
e97034f8e9
commit
547dbb3906
|
@ -338,7 +338,7 @@ bool LR_MsgHandler::set_parameter(const char *name, float value)
|
|||
const char *ignore_parms[] = { "GPS_TYPE", "AHRS_EKF_USE",
|
||||
"COMPASS_ORIENT", "COMPASS_ORIENT2",
|
||||
"COMPASS_ORIENT3"};
|
||||
for (uint8_t i=0; i<sizeof(ignore_parms)/sizeof(ignore_parms[0]); i++) {
|
||||
for (uint8_t i=0; i < ARRAY_SIZE(ignore_parms); i++) {
|
||||
if (strncmp(name, ignore_parms[i], AP_MAX_NAME_SIZE) == 0) {
|
||||
::printf("Ignoring set of %s to %f\n", name, value);
|
||||
return true;
|
||||
|
|
|
@ -225,7 +225,7 @@ private:
|
|||
SITL sitl;
|
||||
#endif
|
||||
|
||||
LogReader logreader{_vehicle.ahrs, _vehicle.ins, _vehicle.barometer, _vehicle.compass, _vehicle.gps, _vehicle.airspeed, _vehicle.dataflash, log_structure, sizeof(log_structure)/sizeof(log_structure[0])};
|
||||
LogReader logreader{_vehicle.ahrs, _vehicle.ins, _vehicle.barometer, _vehicle.compass, _vehicle.gps, _vehicle.airspeed, _vehicle.dataflash, log_structure, ARRAY_SIZE(log_structure)};
|
||||
|
||||
FILE *plotf;
|
||||
FILE *plotf2;
|
||||
|
@ -357,7 +357,7 @@ void Replay::_parse_command_line(uint8_t argc, char * const argv[])
|
|||
strncpy(user_parameters[num_user_parameters].name, gopt.optarg, eq-gopt.optarg);
|
||||
user_parameters[num_user_parameters].value = atof(eq+1);
|
||||
num_user_parameters++;
|
||||
if (num_user_parameters >= sizeof(user_parameters)/sizeof(user_parameters[0])) {
|
||||
if (num_user_parameters >= ARRAY_SIZE(user_parameters)) {
|
||||
::printf("Too many user parameters\n");
|
||||
exit(1);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue