APM:Libraries
libraries
AP_Airspeed
AP_Airspeed_MS5525.h
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
#pragma once
16
17
/*
18
backend driver for airspeed from I2C
19
*/
20
21
#include <
AP_HAL/AP_HAL.h
>
22
#include <
AP_Param/AP_Param.h
>
23
#include <
AP_HAL/utility/OwnPtr.h
>
24
#include <
AP_HAL/I2CDevice.h
>
25
#include <utility>
26
27
#include "
AP_Airspeed_Backend.h
"
28
#include <
AP_HAL/I2CDevice.h
>
29
30
class
AP_Airspeed_MS5525
:
public
AP_Airspeed_Backend
31
{
32
public
:
33
enum
MS5525_ADDR
{
34
MS5525_ADDR_1
= 0,
35
MS5525_ADDR_2
= 1,
36
MS5525_ADDR_AUTO
= 255,
// does not need to be 255, just needs to be out of the address array
37
};
38
39
AP_Airspeed_MS5525
(
AP_Airspeed
&
frontend
, uint8_t _instance,
MS5525_ADDR
address);
40
~AP_Airspeed_MS5525
(
void
) {}
41
42
// probe and initialise the sensor
43
bool
init
()
override
;
44
45
// return the current differential_pressure in Pascal
46
bool
get_differential_pressure
(
float
&
pressure
)
override
;
47
48
// return the current temperature in degrees C, if available
49
bool
get_temperature
(
float
&
temperature
)
override
;
50
51
private
:
52
void
measure
();
53
void
collect
();
54
void
timer
();
55
bool
read_prom
(
void
);
56
uint16_t
crc4_prom
(
void
);
57
int32_t
read_adc
();
58
void
calculate
();
59
60
float
pressure
;
61
float
temperature
;
62
float
temperature_sum
;
63
float
pressure_sum
;
64
uint32_t
temp_count
;
65
uint32_t
press_count
;
66
67
uint32_t
last_sample_time_ms
;
68
69
uint16_t
prom
[8];
70
uint8_t
state
;
71
int32_t
D1
;
72
int32_t
D2
;
73
uint32_t
command_send_us
;
74
bool
ignore_next
;
75
uint8_t
cmd_sent
;
76
MS5525_ADDR
_address
;
77
78
AP_HAL::OwnPtr<AP_HAL::I2CDevice>
dev
;
79
};
AP_Airspeed
Definition:
AP_Airspeed.h:35
AP_Airspeed_MS5525::dev
AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev
Definition:
AP_Airspeed_MS5525.h:78
AP_Airspeed_MS5525::MS5525_ADDR_2
Definition:
AP_Airspeed_MS5525.h:35
AP_Airspeed_MS5525::measure
void measure()
AP_Airspeed_MS5525::collect
void collect()
AP_Airspeed_MS5525::D1
int32_t D1
Definition:
AP_Airspeed_MS5525.h:71
AP_Airspeed_MS5525::MS5525_ADDR_AUTO
Definition:
AP_Airspeed_MS5525.h:36
AP_HAL.h
AP_Airspeed_Backend.h
AP_Airspeed_MS5525::temp_count
uint32_t temp_count
Definition:
AP_Airspeed_MS5525.h:64
AP_Airspeed_MS5525::prom
uint16_t prom[8]
Definition:
AP_Airspeed_MS5525.h:69
I2CDevice.h
AP_Airspeed_MS5525::crc4_prom
uint16_t crc4_prom(void)
Definition:
AP_Airspeed_MS5525.cpp:114
AP_Airspeed_MS5525::temperature
float temperature
Definition:
AP_Airspeed_MS5525.h:61
AP_Airspeed_MS5525::MS5525_ADDR
MS5525_ADDR
Definition:
AP_Airspeed_MS5525.h:33
AP_Airspeed_MS5525::get_temperature
bool get_temperature(float &temperature) override
Definition:
AP_Airspeed_MS5525.cpp:303
AP_Airspeed_MS5525::cmd_sent
uint8_t cmd_sent
Definition:
AP_Airspeed_MS5525.h:75
AP_Airspeed_MS5525
Definition:
AP_Airspeed_MS5525.h:30
AP_HAL::OwnPtr< AP_HAL::I2CDevice >
AP_Airspeed_MS5525::init
bool init() override
Definition:
AP_Airspeed_MS5525.cpp:61
AP_Airspeed_MS5525::command_send_us
uint32_t command_send_us
Definition:
AP_Airspeed_MS5525.h:73
AP_Param.h
A system for managing and storing variables that are of general interest to the system.
AP_Airspeed_MS5525::~AP_Airspeed_MS5525
~AP_Airspeed_MS5525(void)
Definition:
AP_Airspeed_MS5525.h:40
AP_Airspeed_MS5525::read_adc
int32_t read_adc()
Definition:
AP_Airspeed_MS5525.cpp:182
AP_Airspeed_MS5525::state
uint8_t state
Definition:
AP_Airspeed_MS5525.h:70
AP_Airspeed_MS5525::read_prom
bool read_prom(void)
Definition:
AP_Airspeed_MS5525.cpp:139
AP_Airspeed_MS5525::pressure_sum
float pressure_sum
Definition:
AP_Airspeed_MS5525.h:63
AP_Airspeed_MS5525::MS5525_ADDR_1
Definition:
AP_Airspeed_MS5525.h:34
AP_Airspeed_MS5525::D2
int32_t D2
Definition:
AP_Airspeed_MS5525.h:72
AP_Airspeed_MS5525::timer
void timer()
Definition:
AP_Airspeed_MS5525.cpp:232
AP_Airspeed_MS5525::last_sample_time_ms
uint32_t last_sample_time_ms
Definition:
AP_Airspeed_MS5525.h:67
AP_Airspeed_MS5525::get_differential_pressure
bool get_differential_pressure(float &pressure) override
Definition:
AP_Airspeed_MS5525.cpp:285
OwnPtr.h
AP_Airspeed_Backend::frontend
AP_Airspeed & frontend
Definition:
AP_Airspeed_Backend.h:71
AP_Airspeed_MS5525::press_count
uint32_t press_count
Definition:
AP_Airspeed_MS5525.h:65
AP_Airspeed_MS5525::_address
MS5525_ADDR _address
Definition:
AP_Airspeed_MS5525.h:76
AP_Airspeed_MS5525::AP_Airspeed_MS5525
AP_Airspeed_MS5525(AP_Airspeed &frontend, uint8_t _instance, MS5525_ADDR address)
Definition:
AP_Airspeed_MS5525.cpp:54
AP_Airspeed_MS5525::pressure
float pressure
Definition:
AP_Airspeed_MS5525.h:60
AP_Airspeed_MS5525::ignore_next
bool ignore_next
Definition:
AP_Airspeed_MS5525.h:74
AP_Airspeed_MS5525::temperature_sum
float temperature_sum
Definition:
AP_Airspeed_MS5525.h:62
AP_Airspeed_Backend
Definition:
AP_Airspeed_Backend.h:25
AP_Airspeed_MS5525::calculate
void calculate()
Definition:
AP_Airspeed_MS5525.cpp:194
Generated on Sun Jun 17 2018 14:18:47 for APM:Libraries by
1.8.13