lib_utils.cpp
Go to the documentation of this file.
1 
3 
4 #include <ros/ros.h>
5 
6 namespace toposens_echo_driver
7 {
8 void InitCanInterface(const std::string& can_device, const int data_rate)
9 {
10  InitInterface(const_cast<char*>(can_device.c_str()), data_rate, IF_CAN);
11 }
12 
14 
15 void InitUARTInterface(const std::string& uart_device, const int data_rate)
16 {
17  InitInterface(const_cast<char*>(uart_device.c_str()), data_rate, IF_UART);
18 }
19 
21 
23 {
24  auto* const known_sensors = GetKnownSensors();
25  // NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
26  SetTargetSensor(known_sensors[0].InterfaceSensorId_u16);
27 
29  uint16_t sender = WaitForSessionEnd();
30  Sensor_Session_t* session_data = GetSessionData(sender);
31 
32  return session_data;
33 }
34 
35 auto SetTargetSensor(uint16_t TargetSensor_u16) -> bool
36 {
37  // TODO(tobi) Add GetTargetSensor to toposens_can_lib and compare if already set correctly
38 
39  auto* const known_sensors = GetKnownSensors();
40  const auto number_of_sensors = GetNumberOfKnownSensors();
41  for (auto i = 0; i < number_of_sensors; ++i)
42  {
43  if (known_sensors[i].InterfaceSensorId_u16 == TargetSensor_u16)
44  {
45  ::SetTargetSensor(TargetSensor_u16);
46  return true;
47  }
48  }
49 
50  ROS_ERROR("Requested target sensor ID (%d) is not known on bus!", TargetSensor_u16);
51  return false;
52 }
53 
55 {
56  std::stringstream ss;
57  ss << "Current sensor settings:\n";
58 
59  const auto FixedFrameRate_b = GetParameterADCUseFixedFrameRate_b();
60  ss << "FixedFrameRate_b: " << FixedFrameRate_b;
61  ss << "GetParameterADCFixedFrameRate_u8: " << std::to_string(GetParameterADCFixedFrameRate_u8());
62  ss << "\nGetParameterTransducerVolume_u8: " << std::to_string(GetParameterTransducerVolume_u8());
63  ss << "\nGetParameterTransducerNumOfPulses_u8: "
64  << std::to_string(GetParameterTransducerNumOfPulses_u8());
65  ss << "\nGetParameterSignalProcessingTemperature_f: "
66  << std::to_string(GetParameterSignalProcessingTemperature_f());
67  ss << "\nGetParameterSignalProcessingHumidity_u8: "
68  << std::to_string(GetParameterSignalProcessingHumidity_u8());
69  ss << "\nGetParameterSystemNodeID_u16: " << std::to_string(GetParameterSystemNodeID_u16());
70  ss << "\nGetParameterSystemMCUTemperature_f: "
71  << std::to_string(GetParameterSystemMCUTemperature_f());
72  ss << "\nGetParameterSystemLogLevel_t: " << std::to_string(GetParameterSystemLogLevel_t());
73  ss << "\nGetParameterSystemResetReason_t: " << std::to_string(GetParameterSystemResetReason_t());
74  ss << "\nGetParameterSystemSensorState_t: " << std::to_string(GetParameterSystemSensorState_t());
75  ss << "\nGetParameterSystemSensorMode_t: " << std::to_string(GetParameterSystemSensorMode_t());
76 
77  constexpr auto max_id_index = 2;
78  for (auto i = 0; i <= max_id_index; ++i)
79  {
80  const auto UniqueID_t = GetParameterSystemUniqueID_t(i);
81  ss << "\nUniqueID_cp[" << i << "]: ";
82  for (auto j = 0; j < UID_SIZE; ++j)
83  {
84  // NOLINTNEXTLINE (cppcoreguidelines-pro-bounds-constant-array-index)
85  ss << toHexString(UniqueID_t.values[j]);
86  if (j < (UID_SIZE - 1))
87  {
88  ss << ".";
89  }
90  }
91  }
92 
93  ROS_INFO("%s", ss.str().c_str());
94 }
95 
96 void LogKnownSensors(const double log_interval)
97 {
98  static ros::Time last_log_timestamp;
99  const auto logging_interval{ros::Duration(log_interval)};
100 
101  if ((ros::Time::now() - last_log_timestamp) > logging_interval)
102  {
103  const auto number_of_sensors_on_bus = GetNumberOfKnownSensors();
104  auto* known_sensors = GetKnownSensors();
105 
106  std::stringstream ss;
107  // NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
108  ss << "[" << std::to_string(known_sensors[0].InterfaceSensorId_u16);
109  for (auto i = 1; i < number_of_sensors_on_bus; ++i)
110  {
111  ss << ", ";
112  // NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
113  ss << std::to_string(known_sensors[i].InterfaceSensorId_u16);
114  }
115  ss << "]";
116 
117  ROS_INFO("%u known sensors on bus. IDs: %s", number_of_sensors_on_bus, ss.str().c_str());
118 
119  last_log_timestamp = ros::Time::now();
120  }
121 }
122 
124 {
125  Version_t version;
126  std::stringstream ss;
127  ss << "Versions:\n";
128 
129  auto to_string = [](Version_t version) {
130  return std::to_string(version.major) + "." + std::to_string(version.minor) + "." +
131  std::to_string(version.hotfix);
132  };
133 
135  ss << "Bootloader: " << to_string(version) << ",\n";
137  ss << "App: " << to_string(version) << ",\n";
139  ss << "Hardware: " << to_string(version) << ",\n";
141  ss << "Sig Pro Lib: " << to_string(version) << ",\n";
143  ss << "Comms Lib: " << to_string(version);
144 
145  ROS_INFO("%s", ss.str().c_str());
146 }
147 
148 void LogSessionData(const Sensor_Session_t* session)
149 {
150  if (session == nullptr)
151  {
152  ROS_WARN("LogSessionData: Received request to log session == nullptr!");
153  }
154 
155  auto to_string = [](bool b) { return b ? "true" : "false"; };
156 
157  ROS_DEBUG(
158  "LogSessionData:\nSessionActive_b:\t%s,\nsenderId_u16:\t\t%d,\nNumberOfPoints_u8:"
159  "\t%"
160  "d\nNoiseLevel_u16:\t\t%d\nNearFieldPoint_b:\t%"
161  "s",
162  // NOLINTNEXTLINE(clang-analyzer-core.NullDereference) session has been checked for nullptr
163  to_string(session->SessionState), session->SenderId_u16, session->NumberOfPoints_u8,
164  session->NoiseLevel_u16, to_string(session->NearFieldPoint_b));
165 
166  // 1D Points
167  std::stringstream ss;
168  // NOLINTNEXTLINE(clang-analyzer-core.NullDereference) session has been checked for nullptr
169  ss << "1D Points [VectorLength, Intensity], " << std::to_string(session->NumberOf1DPoints)
170  << " total:";
171  for (auto i = 0; i < session->NumberOf1DPoints; ++i)
172  {
173  // NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-constant-array-index)
174  ss << "\n\t" << i << ": [" << std::to_string(session->Point1D_tp[i].VectorLength_u16)
175  << ", "
176  // NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-constant-array-index)
177  << std::to_string(session->Point1D_tp[i].Intensity_u8) << "]";
178  }
179  ROS_DEBUG("%s", ss.str().c_str());
180 
181  // 3D Points
182  ss.str(std::string());
183  ss << "3D Points [x, y, z, intensity], " << std::to_string(session->NumberOf3DPoints)
184  << " total:";
185  for (auto i = 0; i < session->NumberOf3DPoints; ++i)
186  {
187  // NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-constant-array-index)
188  ss << "\n\t" << i << ": [" << std::to_string(session->Point3D_tp[i].X_i16)
189  << ", "
190  // NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-constant-array-index)
191  << std::to_string(session->Point3D_tp[i].Y_i16)
192  << ", "
193  // NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-constant-array-index)
194  << std::to_string(session->Point3D_tp[i].Z_i16)
195  << ", "
196  // NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-constant-array-index)
197  << std::to_string(session->Point3D_tp[i].Intensity_u8) << "]";
198  }
199  ROS_DEBUG("%s", ss.str().c_str());
200 }
201 
202 void ConfigureSensorLogMessages(void (*Callback)(uint16_t Sender_u16, uint8_t* ReceivedPayload_pu8),
203  const LogLevel_t log_level = LOG_LEVEL_INFO)
204 {
205  RegisterLogMsgCallback(Callback);
206  if (SetParameterSystemLogLevel(log_level))
207  {
208  ROS_DEBUG("Successfully configured sensor log level (%d)!", log_level);
209  }
210  else
211  {
212  ROS_WARN("Failed to configure sensor log level (%d)!", log_level);
213  }
214 }
215 
216 void LogMsgCallback(uint16_t SenderId_u16, uint8_t* ReceivedPayload_pu8)
217 {
218  char message_buffer[MAX_PARSED_LOG_MESSAGE_LEN];
219  ParseLogMessageToText(message_buffer, SenderId_u16, ReceivedPayload_pu8);
220 
221  std::stringstream ss;
222  ss << "Log-Msg Callback from Sender " << SenderId_u16 << ": " << message_buffer;
223 
224  const auto log_msg = ss.str();
225 
226  switch (ReceivedPayload_pu8[LOGGING_SEVERITY_BYTE])
227  {
229  ROS_DEBUG_STREAM(log_msg.c_str());
230  break;
232  ROS_INFO_STREAM(log_msg.c_str());
233  break;
235  ROS_WARN_STREAM(log_msg.c_str());
236  break;
238  ROS_ERROR_STREAM(log_msg.c_str());
239  break;
240  default:
241  break;
242  }
243 }
244 
245 } // namespace toposens_echo_driver
MAX_PARSED_LOG_MESSAGE_LEN
#define MAX_PARSED_LOG_MESSAGE_LEN
Definition: sensor_lib.h:30
GetParameterSystemSensorMode_t
SensorMode_t GetParameterSystemSensorMode_t()
Blocking Request to read the Sensor Mode from current sensor.
Definition: sensor_lib.c:3217
toposens_echo_driver::LogSessionData
void LogSessionData(const Sensor_Session_t *session)
Log given session data to ROS concole.
Definition: lib_utils.cpp:148
GetParameterSystemSensorState_t
SensorState_t GetParameterSystemSensorState_t()
Blocking Request to read the Sensor State from current sensor.
Definition: sensor_lib.c:3184
VERSION_BYTE_SIG_PRO_LIB
@ VERSION_BYTE_SIG_PRO_LIB
Definition: message_flags.h:148
CONTROL_BYTE_LOG_WARN
@ CONTROL_BYTE_LOG_WARN
Definition: message_flags.h:116
GetParameterSystemResetReason_t
ResetReason_t GetParameterSystemResetReason_t()
Blocking Request to read the last Reset Reason from current sensor.
Definition: sensor_lib.c:3170
toposens_echo_driver::toHexString
auto toHexString(const uint16_t i) -> std::string
Convert given i to hex string.
Definition: lib_utils.h:62
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
RequestVersion_t
Version_t RequestVersion_t(VersionByte_t TargetComponent_t)
Blocking - Request transmition of the current version of selected component from selected sensor.
Definition: sensor_lib.c:2193
GetParameterSystemUniqueID_t
UID_t GetParameterSystemUniqueID_t(uint8_t Index_u8)
Blocking Request to read the Unique ID from current sensor.
Definition: sensor_lib.c:3198
lib_utils.h
GetParameterTransducerNumOfPulses_u8
uint8_t GetParameterTransducerNumOfPulses_u8()
Blocking Request to read the current Transducer Number of Pulses from current sensor.
Definition: sensor_lib.c:2983
ros.h
GetKnownSensors
Sensor_t * GetKnownSensors()
Returns pointer to array containing all known sensors. With GetNumberOfKnownSensors() users can get l...
Definition: sensor_lib.c:765
Point3D_t::Intensity_u8
uint8_t Intensity_u8
Definition: sensor_lib.h:44
Version_t::hotfix
uint8_t hotfix
Definition: custom_structs.h:16
toposens_echo_driver::SetTargetSensor
auto SetTargetSensor(uint16_t TargetSensor_u16) -> bool
Checks if TargetSensor_u16 is known and sets current target accordingly.
Definition: lib_utils.cpp:35
DeinitInterface
void DeinitInterface(CommsInterfaceType_t Interface_t)
Instruction to deinit the specified interface type.
Definition: sensor_lib.c:2279
GetParameterSignalProcessingTemperature_f
float GetParameterSignalProcessingTemperature_f()
Blocking Request to read the current Transducer Temperature setting from current sensor.
Definition: sensor_lib.c:2997
toposens_echo_driver::InitCanInterface
void InitCanInterface(const std::string &can_device, int data_rate=1000000)
Inits the driver on given can_device with hard-coded data rate.
Definition: lib_utils.cpp:8
GetParameterTransducerVolume_u8
uint8_t GetParameterTransducerVolume_u8()
Blocking Request to read the current Transducer Volume from current sensor.
Definition: sensor_lib.c:2969
Sensor_Session_t::SessionState
SessionState_t SessionState
Definition: sensor_lib.h:63
GetParameterSystemLogLevel_t
LogLevel_t GetParameterSystemLogLevel_t()
Blocking Request to read the current System Log Level from current sensor.
Definition: sensor_lib.c:3156
Sensor_Session_t::NumberOf1DPoints
uint8_t NumberOf1DPoints
Definition: sensor_lib.h:68
Point1D_t::VectorLength_u16
uint16_t VectorLength_u16
Definition: sensor_lib.h:49
LogLevel_t
LogLevel_t
Definition: custom_types.h:101
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
VERSION_BYTE_HW
@ VERSION_BYTE_HW
Definition: message_flags.h:147
Point3D_t::X_i16
int16_t X_i16
Definition: sensor_lib.h:41
WaitForSessionEnd
uint16_t WaitForSessionEnd()
Blocking Function call to wait for SessionEnd Payload.
Definition: sensor_lib.c:3370
toposens_echo_driver::ConfigureSensorLogMessages
void ConfigureSensorLogMessages(void(*Callback)(uint16_t Sender_u16, uint8_t *ReceivedPayload_pu8), LogLevel_t log_level)
Sets log level with the sensor and registers callback.
Definition: lib_utils.cpp:202
GetParameterADCFixedFrameRate_u8
uint8_t GetParameterADCFixedFrameRate_u8()
Blocking Request to read the current set ADC-Framerate from current sensor.
Definition: sensor_lib.c:2953
toposens_echo_driver::DeinitUARTInterface
void DeinitUARTInterface()
Definition: lib_utils.cpp:20
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
Sensor_Session_t::Point1D_tp
Point1D_t Point1D_tp[MAX_NUMBER_OF_POINTS_PER_SESSION]
Definition: sensor_lib.h:70
toposens_echo_driver::LogVersions
void LogVersions()
Read all version information (such as bootloader version, app versionetc.) from sensor and log to ROS...
Definition: lib_utils.cpp:123
toposens_echo_driver::LogKnownSensors
void LogKnownSensors(double log_interval=3.0)
Get currently known sensors from driver and log to ROS console every log_interval seconds.
Definition: lib_utils.cpp:96
GetNumberOfKnownSensors
uint8_t GetNumberOfKnownSensors()
Returns number of known sensors. With GetKnownSensors() users an pointer to an array containing the I...
Definition: sensor_lib.c:799
RequestMeasurement
bool RequestMeasurement()
Send's a request to start a new measurement.
Definition: sensor_lib.c:2348
ROS_DEBUG
#define ROS_DEBUG(...)
SetParameterSystemLogLevel
bool SetParameterSystemLogLevel(LogLevel_t LogLevel_t)
Blocking Request to set the Loglevel for current target sensor.
Definition: sensor_lib.c:2798
Sensor_Session_t::NumberOf3DPoints
uint8_t NumberOf3DPoints
Definition: sensor_lib.h:69
CONTROL_BYTE_LOG_INFO
@ CONTROL_BYTE_LOG_INFO
Definition: message_flags.h:115
Sensor_Session_t::NumberOfPoints_u8
uint8_t NumberOfPoints_u8
Definition: sensor_lib.h:65
ParseLogMessageToText
void ParseLogMessageToText(char *Output_p8, uint16_t SenderId_u16, const uint8_t *ReceivedPayload_pu8)
Parses log messages into human readable text.
Definition: sensor_lib.c:3521
CONTROL_BYTE_LOG_ERROR
@ CONTROL_BYTE_LOG_ERROR
Definition: message_flags.h:117
Sensor_Session_t::SenderId_u16
uint16_t SenderId_u16
Definition: sensor_lib.h:64
CONTROL_BYTE_LOG_DEBUG
@ CONTROL_BYTE_LOG_DEBUG
Definition: message_flags.h:114
ROS_WARN
#define ROS_WARN(...)
Point3D_t::Y_i16
int16_t Y_i16
Definition: sensor_lib.h:42
GetParameterSystemNodeID_u16
uint16_t GetParameterSystemNodeID_u16()
Blocking Request to read the current NodeID setting from current sensor.
Definition: sensor_lib.c:3103
VERSION_BYTE_COMMS_LIB
@ VERSION_BYTE_COMMS_LIB
Definition: message_flags.h:149
toposens_echo_driver::DeinitCanInterface
void DeinitCanInterface()
Definition: lib_utils.cpp:13
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
GetSessionData
Sensor_Session_t * GetSessionData(uint16_t Sender_u16)
Interface function to query current session-data (ongoing and closed session)
Definition: sensor_lib.c:3422
Point3D_t::Z_i16
int16_t Z_i16
Definition: sensor_lib.h:43
GetParameterSignalProcessingHumidity_u8
uint8_t GetParameterSignalProcessingHumidity_u8()
Blocking Request to read the current Transducer Humidity setting from current sensor.
Definition: sensor_lib.c:3015
InitInterface
void InitInterface(char *InterfaceName, uint32_t DataRate_u32, CommsInterfaceType_t Interface_t)
Instruction to initialize the specified interface with the specified bit rate. Will also initialize t...
Definition: sensor_lib.c:2225
toposens_echo_driver
Definition: adc_dump.h:8
GetParameterADCUseFixedFrameRate_b
bool GetParameterADCUseFixedFrameRate_b()
Blocking Request to read the "Use fixed framerate" value from current sensor.
Definition: sensor_lib.c:2939
toposens_echo_driver::LogMsgCallback
void LogMsgCallback(uint16_t SenderId_u16, uint8_t *ReceivedPayload_pu8)
Callback handling log messages from sensor.
Definition: lib_utils.cpp:216
Version_t
Definition: custom_structs.h:12
VERSION_BYTE_BOOTLOADER
@ VERSION_BYTE_BOOTLOADER
Definition: message_flags.h:145
ros::Time
LOGGING_SEVERITY_BYTE
#define LOGGING_SEVERITY_BYTE
Definition: message_flags.h:73
IF_CAN
@ IF_CAN
Definition: custom_types.h:13
Sensor_Session_t::NoiseLevel_u16
uint16_t NoiseLevel_u16
Definition: sensor_lib.h:66
Point1D_t::Intensity_u8
uint8_t Intensity_u8
Definition: sensor_lib.h:50
Sensor_Session_t::NearFieldPoint_b
bool NearFieldPoint_b
Definition: sensor_lib.h:67
UID_SIZE
#define UID_SIZE
Definition: sensor_lib.h:29
Version_t::major
uint8_t major
Definition: custom_structs.h:14
ROS_ERROR
#define ROS_ERROR(...)
VERSION_BYTE_APP
@ VERSION_BYTE_APP
Definition: message_flags.h:146
Sensor_Session_t
Definition: sensor_lib.h:61
toposens_echo_driver::LogSettings
void LogSettings()
Read current configuration from sensor and log to ROS console.
Definition: lib_utils.cpp:54
RegisterLogMsgCallback
void RegisterLogMsgCallback(void(*Callback)(uint16_t Sender_u16, uint8_t *ReceivedPayload_pu8))
Interface function to register a callback function that is called whenever a Logmessage Payload is re...
Definition: sensor_lib.c:3409
GetParameterSystemMCUTemperature_f
float GetParameterSystemMCUTemperature_f()
Blocking Request to read the current MCU Temperature from current sensor.
Definition: sensor_lib.c:3138
toposens_echo_driver::InitUARTInterface
void InitUARTInterface(const std::string &uart_device, int data_rate=0010002)
Inits the driver on given uart_device with hard-coded data rate.
Definition: lib_utils.cpp:15
Version_t::minor
uint8_t minor
Definition: custom_structs.h:15
Sensor_Session_t::Point3D_tp
Point3D_t Point3D_tp[MAX_NUMBER_OF_POINTS_PER_SESSION]
Definition: sensor_lib.h:71
ROS_INFO
#define ROS_INFO(...)
toposens_echo_driver::RequestSessionData
auto RequestSessionData() -> Sensor_Session_t *
Requesting single shot measurement from first sensor in known sensors array.
Definition: lib_utils.cpp:22
ros::Duration
LOG_LEVEL_INFO
@ LOG_LEVEL_INFO
Definition: custom_types.h:104
ros::Time::now
static Time now()
IF_UART
@ IF_UART
Definition: custom_types.h:14


toposens_echo_driver
Author(s): Tobias Roth , Dennis Maier , Baris Yazici
autogenerated on Wed Mar 2 2022 01:12:32