example_common.c
Go to the documentation of this file.
1 
7 #include "example_common.h"
8 #include <stdio.h>
9 
11 {
12  // ADC settings
13  printf("\n\nADC settings:\n");
14  printf("GetParameterADCUseFixedFrameRate_b: %d\n", GetParameterADCUseFixedFrameRate_b());
15  printf("GetParameterADCFixedFrameRate_u8: %d\n", GetParameterADCFixedFrameRate_u8());
16 
17  // Transducer settings
18  printf("\n\nTransducer settings:\n");
19  printf("GetParameterTransducerVolume_u8: %d\n", GetParameterTransducerVolume_u8());
20  printf("GetParameterTransducerNumOfPulses_u8: %d\n", GetParameterTransducerNumOfPulses_u8());
21 
22  // Signal processing settings
23  printf("\n\nSignal processing settings:\n");
24  printf("GetParameterSignalProcessingTemperature_f: %.6f\n",
26  printf("GetParameterSignalProcessingHumidity_u8: %d\n",
28  printf("GetParameterSignalProcessingNoiseLevelThresholdFactor_f: %f\n",
30  printf("GetParameterSignalProcessingNoiseRatioThreshold_u8: %d\n",
32  printf("GetParameterSignalProcessingEnableNearFieldDetection_b: %d\n",
34  printf("GetParameterSignalProcessingEnableMultipathFilter_b: %d\n",
36  printf("GetParameterSignalProcessingEnableAutoGain_b: %d\n",
38 
39  // System settings
40  printf("\n\nSystem settings:\n");
41  printf("GetParameterSystemNodeID_u16: 0x%02X\n", GetParameterSystemNodeID_u16());
42  printf("GetParameterSystemMCUTemperature_f: %.6f\n", GetParameterSystemMCUTemperature_f());
43  printf("GetParameterSystemLogLevel_t: %d\n", GetParameterSystemLogLevel_t());
44  printf("GetParameterSystemResetReason_t: %d\n", GetParameterSystemResetReason_t());
45  printf("GetParameterSystemSensorState_t: %d\n", GetParameterSystemSensorState_t());
46  printf("GetParameterSystemUniqueID_t:");
47 
48  for (int Index = 0; Index < 3; Index++)
49  {
50  UID_t UniqueID_t = GetParameterSystemUniqueID_t(Index);
51  for (int i = 0; i < 4; i++)
52  {
53  printf(" %02X", UniqueID_t.values[i]);
54  }
55  }
56  printf("\nGetParameterSystemSensorMode_t: %d\n", GetParameterSystemSensorMode_t());
57  printf("GetParameterSystemCalibrationState_b: %d\n", GetParameterSystemCalibrationState_b());
58 }
59 
61 {
62  printf("%d.%d.%d\n", Version_t.major, Version_t.minor, Version_t.hotfix);
63 }
64 
66 {
67  Version_t Version;
68  printf("Bootloader version: ");
70  PrintVersion(Version);
71  printf("Application version: ");
73  PrintVersion(Version);
74  printf("Hardware version: ");
76  PrintVersion(Version);
77  printf("Signal Processing Library version: ");
79  PrintVersion(Version);
80  printf("Communication Library version: ");
82  PrintVersion(Version);
83 }
84 
86 {
87  if (Session != NULL)
88  {
89  printf("---------------------------\n");
90  printf("SessionState:%d\n", Session->SessionState);
91  printf("SenderId_u16:%d\n", Session->SenderId_u16);
92  printf("NumberOfPoints_u8:%d\n", Session->NumberOfPoints_u8);
93  printf("NoiseLevel_u16:%d\n", Session->NoiseLevel_u16);
94  printf("NearFieldPoint_b:%d\n", Session->NearFieldPoint_b);
95  printf("NumberOf1DPoints:%d\n", Session->NumberOf1DPoints);
96  printf("NumberOf3DPoints:%d\n", Session->NumberOf3DPoints);
97  printf("1-D Points: \n");
98  for (int i = 0; i < Session->NumberOf1DPoints; i++)
99  {
100  printf(" 1D-Point-%d VectorLength: %d\n", i, Session->Point1D_tp[i].VectorLength_u16);
101  printf(" 1D-Point-%d Intensity_u8: %d\n", i, Session->Point1D_tp[i].Intensity_u8);
102  }
103  printf("3-D Points: \n");
104  for (int i = 0; i < Session->NumberOf3DPoints; i++)
105  {
106  printf(" 3D-Point-%d X_i16: %d\n", i, Session->Point3D_tp[i].X_i16);
107  printf(" 3D-Point-%d Y_i16: %d\n", i, Session->Point3D_tp[i].Y_i16);
108  printf(" 3D-Point-%d Z_i16: %d\n", i, Session->Point3D_tp[i].Z_i16);
109  printf(" 3D-Point-%d Intensity_u8: %d\n", i, Session->Point3D_tp[i].Intensity_u8);
110  }
111  printf("---------------------------\n");
112  }
113 }
114 
116 {
117  uint32_t DumpSize_u32 = ADCDump->ReceivedDumpSize_u32;
118  printf("ADC-Session closed\n");
119  printf("ReceivedDumpSize_u32:%d\n", DumpSize_u32);
120  for (uint32_t Idx_u32 = 0; Idx_u32 < DumpSize_u32; Idx_u32++)
121  {
122  printf("%02X ", ADCDump->DumpBlob_pu8[Idx_u32]);
123  if (Idx_u32 % 48 == 0)
124  {
125  printf("\n");
126  }
127  }
128  printf("\n");
129 }
130 
131 void SaveADCBlobData(ADCDump_t* ADCDump, const char* filepath)
132 {
133  uint32_t DumpSize_u32 = ADCDump->ReceivedDumpSize_u32;
134 
135  FILE* fptr;
136  fptr = fopen(filepath, "wb");
137 
138  if (fptr == NULL)
139  {
140  printf("\033[0;31mADC Dump file open error!\n\033[0m");
141  return;
142  }
143 
144  size_t number_of_bytes_written = fwrite(ADCDump->DumpBlob_pu8, 1, DumpSize_u32, fptr);
145 
146  if (number_of_bytes_written == DumpSize_u32)
147  printf("Save sucessful\n");
148  else
149  printf("\033[0;31mADC Dump file write error!\n\033[0m");
150 
151  fclose(fptr);
152 }
153 
154 void PrintLogMessage(uint16_t SenderId_u16, const uint8_t* ReceivedPayload_pu8)
155 {
156  char message_buffer[MAX_PARSED_LOG_MESSAGE_LEN];
157  ParseLogMessageToText(message_buffer, SenderId_u16, ReceivedPayload_pu8);
158  switch (ReceivedPayload_pu8[LOGGING_SEVERITY_BYTE])
159  {
161  printf("\033[0;34m");
162  break;
164  printf("\033[0;32m");
165  break;
167  printf("\033[0;33m");
168  break;
170  printf("\033[0;31m");
171  break;
172  default:
173  break;
174  }
175  printf("%s\n", message_buffer);
176  printf("\033[0m");
177 }
178 
180 {
181  Sensor_t* KnownSensors_pu16 = GetKnownSensors();
182  uint8_t NumberOfSensors_u8 = GetNumberOfKnownSensors();
183  for (int i = 0; i < NumberOfSensors_u8; i++)
184  {
185  printf("Sensor %d has ID: %02X\n", i, KnownSensors_pu16[i].InterfaceSensorId_u16);
186  }
187 }
Library containing common functions that are used in the various examples.
uint8_t NumberOf3DPoints
Definition: sensor_lib.h:69
uint16_t NoiseLevel_u16
Definition: sensor_lib.h:66
void GetSettings()
SensorState_t GetParameterSystemSensorState_t()
Blocking Request to read the Sensor State from current sensor.
Definition: sensor_lib.c:3184
ResetReason_t GetParameterSystemResetReason_t()
Blocking Request to read the last Reset Reason from current sensor.
Definition: sensor_lib.c:3170
void SaveADCBlobData(ADCDump_t *ADCDump, const char *filepath)
void GetVersions()
void PrintVersion(Version_t Version_t)
uint8_t hotfix
bool GetParameterSignalProcessingEnableNearFieldDetection_b()
Blocking Request to read whether near field detection is enabled in the current sensor.
Definition: sensor_lib.c:3059
uint8_t GetParameterTransducerVolume_u8()
Blocking Request to read the current Transducer Volume from current sensor.
Definition: sensor_lib.c:2969
UID_t GetParameterSystemUniqueID_t(uint8_t Index_u8)
Blocking Request to read the Unique ID from current sensor.
Definition: sensor_lib.c:3198
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
uint8_t NumberOf1DPoints
Definition: sensor_lib.h:68
uint8_t GetParameterTransducerNumOfPulses_u8()
Blocking Request to read the current Transducer Number of Pulses from current sensor.
Definition: sensor_lib.c:2983
LogLevel_t GetParameterSystemLogLevel_t()
Blocking Request to read the current System Log Level from current sensor.
Definition: sensor_lib.c:3156
Sensor_t * GetKnownSensors()
Returns pointer to array containing all known sensors. With GetNumberOfKnownSensors() users can get l...
Definition: sensor_lib.c:765
uint8_t NumberOfPoints_u8
Definition: sensor_lib.h:65
float GetParameterSignalProcessingTemperature_f()
Blocking Request to read the current Transducer Temperature setting from current sensor.
Definition: sensor_lib.c:2997
uint8_t values[UID_SIZE]
Definition: sensor_lib.h:36
bool GetParameterSignalProcessingEnableAutoGain_b()
Blocking Request to read whether auto gain is enabled in the current sensor.
Definition: sensor_lib.c:3087
SessionState_t SessionState
Definition: sensor_lib.h:63
#define LOGGING_SEVERITY_BYTE
Definition: message_flags.h:73
uint8_t Intensity_u8
Definition: sensor_lib.h:44
uint16_t VectorLength_u16
Definition: sensor_lib.h:49
int16_t X_i16
Definition: sensor_lib.h:41
uint8_t * DumpBlob_pu8
Definition: sensor_lib.h:80
void PrintSensorsOnBus()
bool GetParameterSystemCalibrationState_b()
Blocking Request to read whether the current sensor has been calibrated.
Definition: sensor_lib.c:3231
uint8_t GetNumberOfKnownSensors()
Returns number of known sensors. With GetKnownSensors() users an pointer to an array containing the I...
Definition: sensor_lib.c:799
uint8_t GetParameterADCFixedFrameRate_u8()
Blocking Request to read the current set ADC-Framerate from current sensor.
Definition: sensor_lib.c:2953
uint32_t ReceivedDumpSize_u32
Definition: sensor_lib.h:79
#define MAX_PARSED_LOG_MESSAGE_LEN
Definition: sensor_lib.h:30
uint8_t GetParameterSignalProcessingHumidity_u8()
Blocking Request to read the current Transducer Humidity setting from current sensor.
Definition: sensor_lib.c:3015
int16_t Z_i16
Definition: sensor_lib.h:43
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
Point3D_t Point3D_tp[MAX_NUMBER_OF_POINTS_PER_SESSION]
Definition: sensor_lib.h:71
uint16_t SenderId_u16
Definition: sensor_lib.h:64
bool GetParameterSignalProcessingEnableMultipathFilter_b()
Blocking Request to read whether the multipath filter is enabled in the current sensor.
Definition: sensor_lib.c:3073
bool NearFieldPoint_b
Definition: sensor_lib.h:67
int16_t Y_i16
Definition: sensor_lib.h:42
uint16_t GetParameterSystemNodeID_u16()
Blocking Request to read the current NodeID setting from current sensor.
Definition: sensor_lib.c:3103
void PrintSessionData(Sensor_Session_t *Session)
bool GetParameterADCUseFixedFrameRate_b()
Blocking Request to read the "Use fixed framerate" value from current sensor.
Definition: sensor_lib.c:2939
uint8_t GetParameterSignalProcessingNoiseRatioThreshold_u8()
Blocking Request to read the current Noise Ratio Threshold from current sensor.
Definition: sensor_lib.c:3045
uint8_t Intensity_u8
Definition: sensor_lib.h:50
void PrintLogMessage(uint16_t SenderId_u16, const uint8_t *ReceivedPayload_pu8)
float GetParameterSignalProcessingNoiseLevelThresholdFactor_f()
Blocking Request to read the current Noise Level Threshold Factor from current sensor.
Definition: sensor_lib.c:3029
uint8_t minor
uint8_t major
Point1D_t Point1D_tp[MAX_NUMBER_OF_POINTS_PER_SESSION]
Definition: sensor_lib.h:70
float GetParameterSystemMCUTemperature_f()
Blocking Request to read the current MCU Temperature from current sensor.
Definition: sensor_lib.c:3138
void PrintADCBlobData(ADCDump_t *ADCDump)
SensorMode_t GetParameterSystemSensorMode_t()
Blocking Request to read the Sensor Mode from current sensor.
Definition: sensor_lib.c:3217


toposens_echo_driver
Author(s): Tobias Roth , Dennis Maier , Baris Yazici
autogenerated on Mon Feb 28 2022 23:57:42