APM:Libraries
Airspeed.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 /*
17  * Airspeed.cpp - airspeed example sketch
18  *
19  */
20 
21 #include <AP_ADC/AP_ADC.h>
23 #include <AP_HAL/AP_HAL.h>
25 #include <GCS_MAVLink/GCS_Dummy.h>
26 
27 void setup();
28 void loop();
29 
31 
33 
36 
37 namespace {
38 // try to set the object value but provide diagnostic if it failed
39 void set_object_value(const void *object_pointer,
40  const struct AP_Param::GroupInfo *group_info,
41  const char *name, float value)
42 {
43  if (!AP_Param::set_object_value(object_pointer, group_info, name, value)) {
44  hal.console->printf("WARNING: AP_Param::set object value \"%s::%s\" Failed.\n",
45  group_info->name, name);
46  }
47 }
48 }
49 
50 void setup()
51 {
52  hal.console->printf("ArduPilot Airspeed library test\n");
53 
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);
57 
58  board_config.init();
59 
60  airspeed.init();
61  airspeed.calibrate(false);
62 }
63 
64 void loop(void)
65 {
66  static uint32_t timer;
67  if ((AP_HAL::millis() - timer) > 100) {
68  timer = AP_HAL::millis();
69  airspeed.read();
70  airspeed.get_temperature(temperature);
71 
72  hal.console->printf("airspeed %5.2f temperature %6.2f healthy = %u\n",
73  (double)airspeed.get_airspeed(), (double)temperature, airspeed.healthy());
74  }
75  hal.scheduler->delay(1);
76 }
77 
78 const struct AP_Param::GroupInfo GCS_MAVLINK::var_info[] = {
80 };
82 
83 AP_HAL_MAIN();
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_Airspeed.h:151
AP_HAL::UARTDriver * console
Definition: HAL.h:110
float get_airspeed(uint8_t i) const
Definition: AP_Airspeed.h:53
uint32_t timer
AP_HAL_MAIN()
const char * name
Definition: BusTest.cpp:11
static AP_BoardConfig board_config
Definition: Airspeed.cpp:35
float temperature
Definition: Airspeed.cpp:32
virtual void delay(uint16_t ms)=0
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
void read(void)
void loop()
Definition: Airspeed.cpp:64
uint32_t millis()
Definition: system.cpp:157
void calibrate(bool in_startup)
const char * name
Definition: AP_Param.h:148
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: Airspeed.cpp:30
bool get_temperature(uint8_t i, float &temperature)
const HAL & get_HAL()
void init(void)
AP_Airspeed airspeed
Definition: Airspeed.cpp:34
float value
static bool set_object_value(const void *object_pointer, const struct GroupInfo *group_info, const char *name, float value)
Definition: AP_Param.cpp:1231
bool healthy(uint8_t i) const
Definition: AP_Airspeed.h:135
void setup()
Definition: Airspeed.cpp:50
#define AP_GROUPEND
Definition: AP_Param.h:121
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
GCS_Dummy _gcs
Definition: Airspeed.cpp:81