Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_DAL/AP_DAL_Airspeed.h
Views: 1798
#pragma once12#include <AP_Logger/LogStructure.h>34#include <AP_Airspeed/AP_Airspeed.h>56class AP_DAL_Airspeed {7public:89// Airspeed-like methods:1011// return health status of sensor12bool healthy(uint8_t i) const {13return _RASI[i].healthy;14}15// return health status of primary sensor16bool healthy() const {17return healthy(get_primary());18}1920// return true if airspeed is enabled, and airspeed use is set21bool use(uint8_t i) const {22return _RASI[i].use;23}24bool use() const {25return use(get_primary());26}2728// return the current airspeed in m/s29float get_airspeed(uint8_t i) const {30return _RASI[i].airspeed;31}32float get_airspeed() const {33return get_airspeed(get_primary());34}3536// return time in ms of last update37uint32_t last_update_ms(uint8_t i) const { return _RASI[i].last_update_ms; }38uint32_t last_update_ms() const { return last_update_ms(get_primary()); }3940// get number of sensors41uint8_t get_num_sensors(void) const { return _RASH.num_sensors; }4243// get current primary sensor44uint8_t get_primary(void) const { return _RASH.primary; }4546// AP_DAL methods:47AP_DAL_Airspeed();4849void start_frame();5051void handle_message(const log_RASH &msg) {52_RASH = msg;53}54void handle_message(const log_RASI &msg) {55_RASI[msg.instance] = msg;56}5758private:5960struct log_RASH _RASH;61struct log_RASI _RASI[AIRSPEED_MAX_SENSORS];62};636465