39 void set_object_value(
const void *object_pointer,
44 hal.
console->
printf(
"WARNING: AP_Param::set object value \"%s::%s\" Failed.\n",
45 group_info->
name, name);
54 set_object_value(&airspeed, airspeed.
var_info,
"PIN", 65);
55 set_object_value(&airspeed, airspeed.
var_info,
"ENABLE", 1);
56 set_object_value(&airspeed, airspeed.
var_info,
"USE", 1);
66 static uint32_t
timer;
72 hal.
console->
printf(
"airspeed %5.2f temperature %6.2f healthy = %u\n",
static const struct AP_Param::GroupInfo var_info[]
AP_HAL::UARTDriver * console
float get_airspeed(uint8_t i) const
static AP_BoardConfig board_config
virtual void delay(uint16_t ms)=0
virtual void printf(const char *,...) FMT_PRINTF(2
void calibrate(bool in_startup)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
bool get_temperature(uint8_t i, float &temperature)
static bool set_object_value(const void *object_pointer, const struct GroupInfo *group_info, const char *name, float value)
bool healthy(uint8_t i) const
AP_HAL::Scheduler * scheduler