APM:Libraries
RPM_SITL.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 #include <AP_HAL/AP_HAL.h>
17 
18 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
19 #include "RPM_SITL.h"
20 
21 extern const AP_HAL::HAL& hal;
22 
23 /*
24  open the sensor in constructor
25 */
26 AP_RPM_SITL::AP_RPM_SITL(AP_RPM &_ap_rpm, uint8_t _instance, AP_RPM::RPM_State &_state) :
27  AP_RPM_Backend(_ap_rpm, _instance, _state)
28 {
30  instance = _instance;
31 }
32 
34 {
35  if (sitl == nullptr) {
36  return;
37  }
38  if (instance == 0) {
40  } else {
42  }
44  state.signal_quality = 0.5f;
46 }
47 
48 #endif // CONFIG_HAL_BOARD
static AP_Param * find_object(const char *name)
Definition: AP_Param.cpp:939
AP_RPM & ap_rpm
Definition: RPM_Backend.h:43
SITL::SITL * sitl
Definition: RPM_SITL.h:32
float signal_quality
Definition: AP_RPM.h:50
uint8_t instance
Definition: RPM_SITL.h:33
uint32_t last_reading_ms
Definition: AP_RPM.h:49
double rpm1
Definition: SITL.h:25
uint8_t instance
Definition: AP_RPM.h:47
AP_RPM::RPM_State & state
Definition: RPM_Backend.h:44
uint32_t millis()
Definition: system.cpp:157
Definition: AP_RPM.h:27
double rpm2
Definition: SITL.h:26
AP_RPM_SITL(AP_RPM &ranger, uint8_t instance, AP_RPM::RPM_State &_state)
Definition: RPM_SITL.cpp:26
AP_Float _scaling[RPM_MAX_INSTANCES]
Definition: AP_RPM.h:56
float rate_rpm
Definition: AP_RPM.h:48
struct sitl_fdm state
Definition: SITL.h:71
void update(void)
Definition: RPM_SITL.cpp:33
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14