mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
AP_InertialSensor: fixed example build
This commit is contained in:
parent
26ced77ebc
commit
3fb0b8f69d
@ -20,7 +20,7 @@ void setup(void)
|
|||||||
{
|
{
|
||||||
hal.console->println("AP_InertialSensor startup...");
|
hal.console->println("AP_InertialSensor startup...");
|
||||||
|
|
||||||
ins.init(AP_InertialSensor::RATE_100HZ);
|
ins.init(100);
|
||||||
|
|
||||||
// display initial values
|
// display initial values
|
||||||
display_offsets_and_scaling();
|
display_offsets_and_scaling();
|
||||||
|
Loading…
Reference in New Issue
Block a user