mirror of https://github.com/ArduPilot/ardupilot
VibTest: fixed array bounds error
This commit is contained in:
parent
2c8240dbb4
commit
863e7a5f93
|
@ -94,7 +94,7 @@ void setup(void)
|
|||
accel_fd[i] = open(accel_path, O_RDONLY);
|
||||
gyro_fd[i] = open(gyro_path, O_RDONLY);
|
||||
}
|
||||
if (accel_fd[0] == -1 || gyro_fd[-1] == -1) {
|
||||
if (accel_fd[0] == -1 || gyro_fd[0] == -1) {
|
||||
hal.scheduler->panic("Failed to open accel/gyro 0");
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue