APM:Libraries
RPM_generic.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  * RPM_generic.cpp - RPM library example sketch
18  *
19  */
20 
21 #include <AP_RPM/AP_RPM.h>
22 #include <AP_HAL/AP_HAL.h>
23 
24 void setup();
25 void loop();
26 
28 
29 static AP_RPM RPM;
30 
32 
33 void setup()
34 {
35  hal.console->printf("APM RPM library test\n\n\n");
36  RPM.init();
37 
38  hal.console->printf("Detected %u RPM sensors\n\n", RPM.num_sensors());
39 }
40 
41 void loop(void)
42 {
43  RPM.update();
44 
45  for (uint8_t ii = 0; ii < RPM.num_sensors(); ii++) {
46 
47  // Determine sensor state
48  if (RPM.healthy(ii)) {
49  // Healthy sensor
50  sensor_state = 'h';
51  } else if (RPM.enabled(ii)) {
52  // Enabled but not healthy
53  sensor_state = 'e';
54  } else {
55  // Not enabled, not healthy
56  sensor_state = '-';
57  }
58 
59  hal.console->printf("%u - (%c) RPM: %8.2f Quality: %.2f ",
60  ii, sensor_state,
61  (double)RPM.get_rpm(ii),
62  (double)RPM.get_signal_quality(ii));
63 
64  if (ii+1 < RPM.num_sensors()) {
65  // Print a seperating bar if more sensors to process
66  hal.console->printf("| ");
67  }
68 
69  }
70 
71  hal.scheduler->delay(100);
72 
73  hal.console->printf("\n");
74 }
75 
76 AP_HAL_MAIN();
uint8_t num_sensors(void) const
Definition: AP_RPM.h:64
AP_HAL_MAIN()
void update(void)
Definition: AP_RPM.cpp:148
bool enabled(uint8_t instance) const
Definition: AP_RPM.cpp:181
float get_rpm(uint8_t instance) const
Definition: AP_RPM.h:77
AP_HAL::UARTDriver * console
Definition: HAL.h:110
char sensor_state
Definition: RPM_generic.cpp:31
void init(void)
Definition: AP_RPM.cpp:106
void loop()
Definition: RPM_generic.cpp:41
static AP_RPM RPM
Definition: RPM_generic.cpp:29
virtual void delay(uint16_t ms)=0
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
bool healthy(uint8_t instance) const
Definition: AP_RPM.cpp:164
Definition: AP_RPM.h:27
const HAL & get_HAL()
void setup()
Definition: RPM_generic.cpp:33
float get_signal_quality(uint8_t instance) const
Definition: AP_RPM.h:87
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: RPM_generic.cpp:27