APM:Libraries
libraries
AP_RSSI
AP_RSSI.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
#include <
AP_HAL/AP_HAL.h
>
18
#include <
AP_Param/AP_Param.h
>
19
#include <
AP_Math/AP_Math.h
>
20
21
class
AP_RSSI
22
{
23
public
:
24
enum
RssiType
{
25
RSSI_DISABLED
= 0,
26
RSSI_ANALOG_PIN
= 1,
27
RSSI_RC_CHANNEL_VALUE
= 2,
28
RSSI_RECEIVER
= 3
29
};
30
31
AP_RSSI
();
32
33
/* Do not allow copies */
34
AP_RSSI
(
const
AP_RSSI
&other) =
delete
;
35
AP_RSSI
&
operator=
(
const
AP_RSSI
&) =
delete
;
36
37
// destructor
38
~AP_RSSI
(
void
);
39
40
static
AP_RSSI
*
get_instance
();
41
42
// Initialize the rssi object and prepare it for use
43
void
init
();
44
45
// return true if rssi reading is enabled
46
bool
enabled
()
const
{
return
rssi_type
!=
RSSI_DISABLED
; }
47
48
// Read the receiver RSSI value as a float 0.0f - 1.0f.
49
// 0.0 represents weakest signal, 1.0 represents maximum signal.
50
float
read_receiver_rssi
();
51
52
// Read the receiver RSSI value as an 8-bit integer
53
// 0 represents weakest signal, 255 represents maximum signal.
54
uint8_t
read_receiver_rssi_uint8
();
55
56
// parameter block
57
static
const
struct
AP_Param::GroupInfo
var_info
[];
58
59
private
:
60
61
static
AP_RSSI
*
_s_instance
;
62
63
// RSSI parameters
64
AP_Int8
rssi_type
;
// Type of RSSI being used
65
AP_Int8
rssi_analog_pin
;
// Analog pin RSSI value found on
66
AP_Float
rssi_analog_pin_range_low
;
// Voltage value for weakest rssi signal
67
AP_Float
rssi_analog_pin_range_high
;
// Voltage value for strongest rssi signal
68
AP_Int8
rssi_channel
;
// allows rssi to be read from given channel as PWM value
69
AP_Int16
rssi_channel_low_pwm_value
;
// PWM value for weakest rssi signal
70
AP_Int16
rssi_channel_high_pwm_value
;
// PWM value for strongest rssi signal
71
72
// Analog Inputs
73
// a pin for reading the receiver RSSI voltage.
74
AP_HAL::AnalogSource
*
rssi_analog_source
;
75
76
// read the RSSI value from an analog pin - returns float in range 0.0 to 1.0
77
float
read_pin_rssi
();
78
79
// read the RSSI value from a PWM value on a RC channel
80
float
read_channel_rssi
();
81
82
// Scale and constrain a float rssi value to 0.0 to 1.0 range
83
float
scale_and_constrain_float_rssi
(
float
current_rssi_value,
float
low_rssi_range,
float
high_rssi_range);
84
};
85
86
namespace
AP
{
87
AP_RSSI
*
rssi
();
88
};
AP_RSSI::RSSI_DISABLED
Definition:
AP_RSSI.h:25
AP_RSSI::rssi_channel_high_pwm_value
AP_Int16 rssi_channel_high_pwm_value
Definition:
AP_RSSI.h:70
AP_HAL.h
AP_RSSI::get_instance
static AP_RSSI * get_instance()
Definition:
AP_RSSI.cpp:114
AP_RSSI::read_receiver_rssi
float read_receiver_rssi()
Definition:
AP_RSSI.cpp:129
AP_RSSI::rssi_channel_low_pwm_value
AP_Int16 rssi_channel_low_pwm_value
Definition:
AP_RSSI.h:69
AP_RSSI::RSSI_RC_CHANNEL_VALUE
Definition:
AP_RSSI.h:27
AP_RSSI::RSSI_ANALOG_PIN
Definition:
AP_RSSI.h:26
AP::rssi
AP_RSSI * rssi()
Definition:
AP_RSSI.cpp:220
AP_RSSI::RssiType
RssiType
Definition:
AP_RSSI.h:24
AP_RSSI::scale_and_constrain_float_rssi
float scale_and_constrain_float_rssi(float current_rssi_value, float low_rssi_range, float high_rssi_range)
Definition:
AP_RSSI.cpp:187
AP_RSSI::RSSI_RECEIVER
Definition:
AP_RSSI.h:28
AP_RSSI::init
void init()
Definition:
AP_RSSI.cpp:120
AP_Param.h
A system for managing and storing variables that are of general interest to the system.
AP_RSSI::rssi_analog_pin_range_high
AP_Float rssi_analog_pin_range_high
Definition:
AP_RSSI.h:67
AP_RSSI::rssi_type
AP_Int8 rssi_type
Definition:
AP_RSSI.h:64
AP_RSSI::var_info
static const struct AP_Param::GroupInfo var_info[]
Definition:
AP_RSSI.h:57
AP
Definition:
AP_AHRS.cpp:486
AP_RSSI::~AP_RSSI
~AP_RSSI(void)
Definition:
AP_RSSI.cpp:107
AP_RSSI::read_receiver_rssi_uint8
uint8_t read_receiver_rssi_uint8()
Definition:
AP_RSSI.cpp:161
AP_RSSI::rssi_analog_pin
AP_Int8 rssi_analog_pin
Definition:
AP_RSSI.h:65
AP_RSSI::AP_RSSI
AP_RSSI()
Definition:
AP_RSSI.cpp:97
AP_Param::GroupInfo
Definition:
AP_Param.h:145
AP_Math.h
AP_RSSI
Definition:
AP_RSSI.h:21
AP_RSSI::read_channel_rssi
float read_channel_rssi()
Definition:
AP_RSSI.cpp:179
AP_RSSI::operator=
AP_RSSI & operator=(const AP_RSSI &)=delete
AP_RSSI::rssi_analog_pin_range_low
AP_Float rssi_analog_pin_range_low
Definition:
AP_RSSI.h:66
AP_RSSI::_s_instance
static AP_RSSI * _s_instance
Definition:
AP_RSSI.h:61
AP_RSSI::rssi_analog_source
AP_HAL::AnalogSource * rssi_analog_source
Definition:
AP_RSSI.h:74
AP_HAL::AnalogSource
Definition:
AnalogIn.h:7
AP_RSSI::enabled
bool enabled() const
Definition:
AP_RSSI.h:46
AP_RSSI::read_pin_rssi
float read_pin_rssi()
Definition:
AP_RSSI.cpp:170
AP_RSSI::rssi_channel
AP_Int8 rssi_channel
Definition:
AP_RSSI.h:68
Generated on Sun Jun 17 2018 14:18:51 for APM:Libraries by
1.8.13