The sensors module is central to the whole system. It takes low-level output from drivers, turns
it into a more usable form, and publishes it for the rest of the system.
The provided functionality includes:
- Read the output from the sensor drivers (`sensor_gyro`, etc.).
If there are multiple of the same type, do voting and failover handling.
Then apply the board rotation and temperature calibration (if enabled). And finally publish the data; one of the
topics is `sensor_combined`, used by many parts of the system.
- Do RC channel mapping: read the raw input channels (`input_rc`), then apply the calibration, map the RC channels
to the configured channels & mode switches, low-pass filter, and then publish as `rc_channels` and
`manual_control_setpoint`.
- Read the output from the ADC driver (via ioctl interface) and publish `battery_status`.
- Make sure the sensor drivers get the updated calibration parameters (scale & offset) when the parameters change or
on startup. The sensor drivers use the ioctl interface for parameter updates. For this to work properly, the
sensor drivers must already be running when `sensors` is started.
- Do preflight sensor consistency checks and publish the `sensor_preflight` topic.
It runs in its own thread and polls on the currently selected gyro topic.
Usage: sensors <command> [arguments...]
INFO [sensors] gyro status:
INFO [lib__ecl] validator: best: 0, prev best: 0, failsafe: NO (0 events)
INFO [lib__ecl] sensor #0, prio: 100, state: OK
INFO [lib__ecl] val: 0.0039, lp: -0.0002 mean dev: 0.0000 RMS: 0.0065 conf: 1.0000
INFO [lib__ecl] val: 0.0048, lp: -0.0004 mean dev: 0.0000 RMS: 0.0065 conf: 1.0000
INFO [lib__ecl] val: -0.0002, lp: 0.0005 mean dev: -0.0000 RMS: 0.0065 conf: 1.0000
INFO [sensors] accel status:
INFO [lib__ecl] validator: best: 0, prev best: 0, failsafe: NO (0 events)
INFO [lib__ecl] sensor #0, prio: 100, state: OK
INFO [lib__ecl] val: -0.0219, lp: -0.0011 mean dev: 0.0000 RMS: 0.0327 conf: 1.0000
INFO [lib__ecl] val: -0.0463, lp: -0.0001 mean dev: 0.0001 RMS: 0.0326 conf: 1.0000
INFO [lib__ecl] val: -9.8411, lp: -9.8098 mean dev: -0.0001 RMS: 0.0327 conf: 1.0000
INFO [lib__ecl] sensor #1, prio: 75, state: OK
INFO [lib__ecl] val: -0.1093, lp: 0.0007 mean dev: -0.0002 RMS: 0.0499 conf: 1.0000
INFO [lib__ecl] val: -0.0478, lp: -0.0015 mean dev: 0.0001 RMS: 0.0505 conf: 1.0000
INFO [lib__ecl] val: -9.7975, lp: -9.8113 mean dev: -0.0001 RMS: 0.0503 conf: 1.0000
INFO [sensors] mag status:
INFO [lib__ecl] validator: best: 0, prev best: 0, failsafe: NO (0 events)
INFO [lib__ecl] sensor #0, prio: 50, state: OK
INFO [lib__ecl] val: 0.8874, lp: 0.8977 mean dev: -0.0000 RMS: 0.0050 conf: 1.0000
INFO [lib__ecl] val: 0.0264, lp: 0.0331 mean dev: 0.0000 RMS: 0.0050 conf: 1.0000
INFO [lib__ecl] val: 1.7816, lp: 1.7868 mean dev: -0.0000 RMS: 0.0050 conf: 1.0000
INFO [sensors] baro status:
INFO [lib__ecl] validator: best: 0, prev best: 0, failsafe: NO (0 events)
INFO [lib__ecl] sensor #0, prio: 75, state: OK
INFO [lib__ecl] val: 487.8885, lp: 487.9854 mean dev: -0.0009 RMS: 0.1011 conf: 1.0000
INFO [lib__ecl] val: 0.0000, lp: 0.0000 mean dev: 0.0000 RMS: 0.0000 conf: 1.0000
INFO [lib__ecl] val: 0.0000, lp: 0.0000 mean dev: 0.0000 RMS: 0.0000 conf: 1.0000
INFO [sensors] Temperature Compensation:
INFO [sensors] gyro: enabled: 0
INFO [sensors] accel: enabled: 0
INFO [sensors] baro: enabled: 0
INFO [sensors] Airspeed status: