mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Airspeed: add more comments to example
This commit is contained in:
parent
4c809888de
commit
eddeea18de
@ -29,7 +29,10 @@ void loop();
|
|||||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||||
|
|
||||||
float temperature;
|
float temperature;
|
||||||
|
|
||||||
|
// create airspeed object
|
||||||
AP_Airspeed airspeed;
|
AP_Airspeed airspeed;
|
||||||
|
|
||||||
static AP_BoardConfig board_config;
|
static AP_BoardConfig board_config;
|
||||||
|
|
||||||
namespace {
|
namespace {
|
||||||
@ -45,28 +48,38 @@ void set_object_value(const void *object_pointer,
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// to be called only once on boot for initializing objects
|
||||||
void setup()
|
void setup()
|
||||||
{
|
{
|
||||||
hal.console->printf("ArduPilot Airspeed library test\n");
|
hal.console->printf("ArduPilot Airspeed library test\n");
|
||||||
|
|
||||||
|
// set airspeed pin to 65, enable and use to true
|
||||||
set_object_value(&airspeed, airspeed.var_info, "PIN", 65);
|
set_object_value(&airspeed, airspeed.var_info, "PIN", 65);
|
||||||
set_object_value(&airspeed, airspeed.var_info, "ENABLE", 1);
|
set_object_value(&airspeed, airspeed.var_info, "ENABLE", 1);
|
||||||
set_object_value(&airspeed, airspeed.var_info, "USE", 1);
|
set_object_value(&airspeed, airspeed.var_info, "USE", 1);
|
||||||
|
|
||||||
board_config.init();
|
board_config.init();
|
||||||
|
|
||||||
|
// initialize airspeed
|
||||||
airspeed.init();
|
airspeed.init();
|
||||||
|
|
||||||
airspeed.calibrate(false);
|
airspeed.calibrate(false);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// loop
|
||||||
void loop(void)
|
void loop(void)
|
||||||
{
|
{
|
||||||
static uint32_t timer;
|
static uint32_t timer;
|
||||||
|
|
||||||
|
// run read() and get_temperature() in 10Hz
|
||||||
if ((AP_HAL::millis() - timer) > 100) {
|
if ((AP_HAL::millis() - timer) > 100) {
|
||||||
|
|
||||||
|
// current system time in milliseconds
|
||||||
timer = AP_HAL::millis();
|
timer = AP_HAL::millis();
|
||||||
airspeed.update(false);
|
airspeed.update(false);
|
||||||
airspeed.get_temperature(temperature);
|
airspeed.get_temperature(temperature);
|
||||||
|
|
||||||
|
// print temperature and airspeed to console
|
||||||
hal.console->printf("airspeed %5.2f temperature %6.2f healthy = %u\n",
|
hal.console->printf("airspeed %5.2f temperature %6.2f healthy = %u\n",
|
||||||
(double)airspeed.get_airspeed(), (double)temperature, airspeed.healthy());
|
(double)airspeed.get_airspeed(), (double)temperature, airspeed.healthy());
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user