include
toposens_driver
command.h
Go to the documentation of this file.
1
6
#ifndef COMMANDS_H
7
#define COMMANDS_H
8
9
#include <toposens_driver/TsDriverConfig.h>
10
#define USE_INTERNAL_TEMPERATURE -100.0
11
12
namespace
toposens_driver
13
{
22
enum
TsParam
23
{
24
UseExternalTemperature
= 0b00000001,
26
EchoRejectionThreshold
= 0b00000010,
28
NoiseIndicatorThreshold
= 0b00000100,
30
NumberOfPulses
= 0b00001000,
32
PeakDetectionWindow
= 0b00010000,
34
ExternalTemperature
= 0b00100000,
35
ScanMode
= 0b01000000,
37
};
38
39
enum
TsService
40
{
41
FirmwareConfiguration
,
42
FirmwareVersion
43
};
44
60
class
Command
61
{
62
public
:
67
Command
(
TsParam
param
,
float
value);
68
72
Command
(
TsService
service);
73
79
TsParam
getParam
() {
return
_param
; }
80
86
float
getValue
() {
return
_value
; }
87
91
char
*
getBytes
() {
return
_bytes
; }
92
97
std::string
getParamName
();
98
99
private
:
100
const
int
MAX_VALUE
= 9999;
101
const
int
MIN_VALUE
= -9999;
102
103
char
_bytes
[50];
104
static
const
char
kPrefix
=
'C'
;
105
TsParam
_param
;
106
float
_value
;
113
std::string
_getKey
(
TsParam
param);
114
119
std::string
_getKey
(
TsService
service);
120
};
121
122
}
// namespace toposens_driver
123
124
#endif
param
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val)
toposens_driver::Command::MIN_VALUE
const int MIN_VALUE
Definition:
command.h:101
toposens_driver::Command::getParamName
std::string getParamName()
Definition:
command.cpp:93
toposens_driver::UseExternalTemperature
Definition:
command.h:24
toposens_driver::ScanMode
Definition:
command.h:35
toposens_driver::PeakDetectionWindow
Definition:
command.h:32
toposens_driver::Command::getParam
TsParam getParam()
Definition:
command.h:79
toposens_driver::FirmwareVersion
Definition:
command.h:42
toposens_driver::Command::_value
float _value
Definition:
command.h:106
toposens_driver::NumberOfPulses
Definition:
command.h:30
toposens_driver::ExternalTemperature
Definition:
command.h:34
toposens_driver::TsParam
TsParam
Definition:
command.h:22
toposens_driver::Command::_getKey
std::string _getKey(TsParam param)
Definition:
command.cpp:65
toposens_driver::EchoRejectionThreshold
Definition:
command.h:26
toposens_driver::Command::_bytes
char _bytes[50]
Definition:
command.h:103
toposens_driver::NoiseIndicatorThreshold
Definition:
command.h:28
toposens_driver::TsService
TsService
Definition:
command.h:39
toposens_driver::Command::getBytes
char * getBytes()
Definition:
command.h:91
toposens_driver::Command::kPrefix
static const char kPrefix
Definition:
command.h:104
toposens_driver
Definition:
command.h:12
toposens_driver::Command::Command
Command(TsParam param, float value)
Definition:
command.cpp:21
toposens_driver::Command::MAX_VALUE
const int MAX_VALUE
Definition:
command.h:100
toposens_driver::Command
Generates firmware-compatible commands for tuning performance parameters.
Definition:
command.h:60
toposens_driver::Command::_param
TsParam _param
Definition:
command.h:105
toposens_driver::Command::getValue
float getValue()
Definition:
command.h:86
toposens_driver::FirmwareConfiguration
Definition:
command.h:41
toposens_driver
Author(s): Adi Singh, Sebastian Dengler, Christopher Lang, Roua Mokchah, Nancy Seckel, Georgiana Barbut
autogenerated on Mon Feb 28 2022 23:57:40