command.cpp
Go to the documentation of this file.
1 
7 
8 namespace toposens_driver
9 {
21 Command::Command(TsParam param, float value)
22 {
23  _param = param;
24  memset(&_bytes, '\0', sizeof(_bytes));
25  std::string format = "%c%s%05d\r";
26 
28  {
29  if (value >= 0)
30  value = std::max(value * 10, value);
31  else
32  value = std::min(value * 10, value);
33  }
34 
35  // Clips desired parameter value if they would cause a value overflow in the
36  // command message.
37  if ((value < MIN_VALUE) || (value > MAX_VALUE))
38  {
39  ROS_WARN_STREAM("Out of range value "
40  << (param == TsParam::ExternalTemperature ? value / 10 : value)
41  << " clipped to closest limit");
42  value = (value < MIN_VALUE) ? MIN_VALUE : MAX_VALUE;
43  }
44  _value = value;
45  std::sprintf(_bytes, format.c_str(), kPrefix, _getKey(param).c_str(), ((int)_value));
46 }
47 
56 {
57  memset(&_bytes, '\0', sizeof(_bytes));
58  std::string format = "%c%s\r";
59 
60  _value = 0;
61  std::sprintf(_bytes, format.c_str(), kPrefix, _getKey(service).c_str());
62 }
63 
65 std::string Command::_getKey(TsParam param)
66 {
68  return "sPuls";
70  return "sPeak";
72  return "sReje";
74  return "sTemp";
76  return "sNois";
77  else if (param == TsParam::ScanMode)
78  return "sMode";
79  return "";
80 }
81 
83 std::string Command::_getKey(TsService service)
84 {
85  if (service == TsService::FirmwareConfiguration)
86  return "gConf";
87  else if (service == TsService::FirmwareVersion)
88  return "gVers";
89  return "";
90 }
91 
93 std::string Command::getParamName()
94 {
95  if (this->_param == TsParam::NumberOfPulses)
96  return "Number of pulses";
97  else if (this->_param == TsParam::PeakDetectionWindow)
98  return "Peak detection window";
99  else if (this->_param == TsParam::EchoRejectionThreshold)
100  return "Echo rejection threshold";
101  else if (this->_param == TsParam::ExternalTemperature)
102  return "Calibration temperature";
103  else if (this->_param == TsParam::NoiseIndicatorThreshold)
104  return "Noise indicator threshold";
105  else if (this->_param == TsParam::ScanMode)
106  return "Scan mode";
107  return "Unknown parameter";
108 }
109 
110 } // namespace toposens_driver
toposens_driver::FirmwareConfiguration
@ FirmwareConfiguration
Definition: command.h:41
toposens_driver::FirmwareVersion
@ FirmwareVersion
Definition: command.h:42
toposens_driver::PeakDetectionWindow
@ PeakDetectionWindow
Definition: command.h:32
toposens_driver::Command::MIN_VALUE
const int MIN_VALUE
Definition: command.h:101
toposens_driver::ScanMode
@ ScanMode
Definition: command.h:35
toposens_driver::TsParam
TsParam
Definition: command.h:22
toposens_driver::Command::_getKey
std::string _getKey(TsParam param)
Definition: command.cpp:65
toposens_driver::NumberOfPulses
@ NumberOfPulses
Definition: command.h:30
toposens_driver
Definition: command.h:12
command.h
toposens_driver::ExternalTemperature
@ ExternalTemperature
Definition: command.h:34
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
toposens_driver::EchoRejectionThreshold
@ EchoRejectionThreshold
Definition: command.h:26
toposens_driver::Command::_bytes
char _bytes[50]
Definition: command.h:103
toposens_driver::Command::_param
TsParam _param
Definition: command.h:105
toposens_driver::NoiseIndicatorThreshold
@ NoiseIndicatorThreshold
Definition: command.h:28
toposens_driver::Command::kPrefix
static const char kPrefix
Definition: command.h:104
toposens_driver::Command::MAX_VALUE
const int MAX_VALUE
Definition: command.h:100
toposens_driver::Command::_value
float _value
Definition: command.h:106
toposens_driver::Command::getParamName
std::string getParamName()
Definition: command.cpp:93
param
T param(const std::string &param_name, const T &default_val)
toposens_driver::Command::Command
Command(TsParam param, float value)
Definition: command.cpp:21
toposens_driver::TsService
TsService
Definition: command.h:39


toposens_driver
Author(s): Adi Singh, Sebastian Dengler, Christopher Lang, Roua Mokchah, Nancy Seckel, Georgiana Barbut
autogenerated on Wed Mar 2 2022 01:12:30