VibTest: fixed array bounds error

This commit is contained in:
Andrew Tridgell 2014-07-09 08:11:52 +10:00
parent 2c8240dbb4
commit 863e7a5f93
1 changed files with 1 additions and 1 deletions

View File

@ -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");
}