AP_OpticalFlow: run PX4 flow sensor at 10Hz

Pair-Programmed-With: Paul Riseborough <p_riseborough@live.com.au>
This commit is contained in:
Andrew Tridgell 2014-12-06 18:14:43 +11:00
parent a2bd3b4a42
commit ed510d4f87
1 changed files with 5 additions and 0 deletions

View File

@ -47,6 +47,11 @@ void AP_OpticalFlow_PX4::init(void)
return;
}
// change to 10Hz update
if (ioctl(_fd, SENSORIOCSPOLLRATE, 10) != 0) {
hal.console->printf("Unable to set flow rate to 10Hz\n");
}
// if we got this far, the sensor must be healthy
_flags.healthy = true;
}