sensor_lib.h
Go to the documentation of this file.
1 
8 #ifndef TOPOSENS_SENSOR_LIB_H /* include control, avoid multiple includes of header file */
9 #define TOPOSENS_SENSOR_LIB_H
10 
11 #ifdef __cplusplus
12 extern "C"
13 {
14 #endif
15 
16 /*---- "library includes" -------------------------------------------------------------*/
17 
18 /*---- "project includes" -------------------------------------------------------------*/
20 #include "custom_structs.h"
21 #include "custom_types.h"
22 #include "message_flags.h"
23 
24 /*---- <system includes> --------------------------------------------------------------*/
25 #include <stdbool.h>
26 #include <stdint.h>
27 
28 /*---- public macros and constants ----------------------------------------------------*/
29 #define UID_SIZE 4
30 #define MAX_PARSED_LOG_MESSAGE_LEN 200
31 #define TIMEOUT_M_SECONDS 200000
32 
33  /*---- public types -------------------------------------------------------------------*/
34  typedef struct UID_t
35  {
36  uint8_t values[UID_SIZE];
37  } UID_t;
38 
39  typedef struct Point3D_t
40  {
41  int16_t X_i16;
42  int16_t Y_i16;
43  int16_t Z_i16;
44  uint8_t Intensity_u8;
45  } Point3D_t;
46 
47  typedef struct Point1D_t
48  {
49  uint16_t VectorLength_u16;
50  uint8_t Intensity_u8;
51  } Point1D_t;
52 
53  typedef enum SessionState_t
54  {
60 
61  typedef struct Sensor_Session_t
62  {
64  uint16_t SenderId_u16;
66  uint16_t NoiseLevel_u16;
73 
74  typedef struct ADCDump_t
75  {
77  uint16_t SenderId_u16;
80  uint8_t* DumpBlob_pu8;
81  } ADCDump_t;
82 
83  typedef struct Sensor_t
84  {
88  } Sensor_t;
89 
93  typedef struct ACK_Status_t
94  {
95  uint16_t SenderId_u16;
96  bool WaitForACK_b;
97  bool ACK_b;
100  } ACK_Status_t;
101 
102  /*---- public variables prototypes ----------------------------------------------------*/
103 
104  /*---- public functions prototypes ----------------------------------------------------*/
105 
113 
120  uint8_t GetNumberOfKnownSensors();
121 
128  void SetTargetSensor(uint16_t TargetSensor_u16);
129 
137  Version_t RequestVersion_t(VersionByte_t TargetComponent_t);
138 
139  // Actions
140 
148  bool RequestReboot();
149 
157  bool RequestMeasurement();
158 
166  bool RequestFactoryReset();
167 
175  bool RequestStoreSettings();
176 
184  bool RequestLoadSettings();
185 
193  bool RequestADCDump();
194 
195  // Setter
196 
197  // ADC
198 
206  bool SetParameterADCUseFixedFrameRate(bool UseFixedFrameRate_b);
207 
215  bool SetParameterADCFixedFrameRate(uint8_t FrameRate_u8);
216 
217  // Transducer
218 
226  bool SetParameterTransducerVolume(uint8_t Volume_u8);
227 
235  bool SetParameterTransducerNumOfPulses(uint8_t NumOfPulses_u8);
236 
237  // SignalProcessing
238 
246  bool SetParameterSignalProcessingTemperature(float Temperature_f);
247 
255  bool SetParameterSignalProcessingHumidity(uint8_t Humidity_u8);
256 
265 
273  bool SetParameterSignalProcessingNoiseRatioThreshold(uint8_t Threshold_u8);
274 
283 
292 
300  bool SetParameterSignalProcessingEnableAutoGain(bool Enable_b);
301 
302  // System
303 
311  bool SetParameterSystemNodeID(uint16_t NodeID_u16);
312 
321 
330 
331  // Getter
332 
339 
346 
347  // Transducer
348 
355 
363 
364  // SignalProcessing
365 
373 
381 
389 
396 
404 
412 
419 
420  // System
421 
427  uint16_t GetParameterSystemNodeID_u16();
428 
435 
442 
449 
456 
462  UID_t GetParameterSystemUniqueID_t(uint8_t Index_u8);
463 
470 
477 
478  // Sessions
479 
485  uint16_t WaitForSessionStart();
486 
492  uint16_t WaitForSessionEnd();
493 
499  uint16_t WaitForADCSessionEnd();
500 
507  Sensor_Session_t* GetSessionData(uint16_t Sender_u16);
508 
515  ADCDump_t* GetADCDumpData(uint16_t Sender_u16);
516 
517  // Ready
518 
524  uint16_t WaitForReady();
525 
526  // Connections
527 
538  void InitInterface(char* InterfaceName, uint32_t DataRate_u32, CommsInterfaceType_t Interface_t);
539 
546 
547  // Callbacks
548 
555  void RegisterSessionStartCallback(void (*Callback)(uint16_t Sender_u16));
556 
563  void RegisterPointSessionEndCallback(void (*Callback)(uint16_t Sender_u16));
564 
571  void RegisterADCDumpSessionEndCallback(void (*Callback)(uint16_t Sender_u16));
572 
579  void RegisterRdyCallback(void (*Callback)(uint16_t Sender_u16));
580 
587  void RegisterADCDumpStartRequestCallback(void (*Callback)(uint16_t Sender_u16,
588  uint32_t ADCDumpSize_32));
589 
596  void RegisterLogMsgCallback(void (*Callback)(uint16_t Sender_u16, uint8_t* ReceivedPayload_pu8));
597 
598  // Logging
599 
607  void ParseLogMessageToText(char* Output_p8, uint16_t SenderId_u16,
608  const uint8_t* ReceivedPayload_pu8);
609 
610  // Helpers
611 
622  void WaitForACK(uint8_t* payload, uint16_t length_u16);
623 
632  bool GetBoolFromPayload_b(const uint8_t* Payload_pu8);
633 
641  uint8_t GetU8FromPayload_u8(const uint8_t* Payload_pu8);
642 
650  uint8_t GetU8FromTwoArgumentPayload_u8(const uint8_t* Payload_pu8);
651 
659  uint16_t GetU16FromPayload_u16(const uint8_t* Payload_pu8);
660 
668  uint16_t GetU16FromTwoArgumentPayload_u16(const uint8_t* Payload_pu8);
669 
674  bool RequestWasSuccessful_b();
675 
682  uint8_t* GetResponsePayloadFromACKStatus(ACK_Status_t* ackstatus);
683 
690  ACK_Status_t* GetCurrentACKStatus(uint8_t index);
691 
699  int32_t GetI32FromPayload_i32(const uint8_t* Payload_pu8);
700 
708  int32_t GetI32FromTwoArgumentPayload_i32(const uint8_t* Payload_pu8);
709 
710  /*---- public inline functions --------------------------------------------------------*/
711 
712 #ifdef __cplusplus
713 }
714 #endif
715 
716 #endif // TOPOSENS_SENSOR_LIB_H
SetParameterADCUseFixedFrameRate
bool SetParameterADCUseFixedFrameRate(bool UseFixedFrameRate_b)
Blocking Request to use the fixed framerate for current target sensor.
Definition: sensor_lib.c:2601
RequestReboot
bool RequestReboot()
Request selected sensor to reboot.
Definition: sensor_lib.c:2330
GetParameterSystemSensorMode_t
SensorMode_t GetParameterSystemSensorMode_t()
Blocking Request to read the Sensor Mode from current sensor.
Definition: sensor_lib.c:3217
SessionState_t
SessionState_t
Definition: sensor_lib.h:53
GetParameterSystemSensorState_t
SensorState_t GetParameterSystemSensorState_t()
Blocking Request to read the Sensor State from current sensor.
Definition: sensor_lib.c:3184
GetBoolFromPayload_b
bool GetBoolFromPayload_b(const uint8_t *Payload_pu8)
Is called from Getter functions to extract values from payload. In this case a bool-value.
Definition: sensor_lib.c:2842
custom_types.h
GetCurrentACKStatus
ACK_Status_t * GetCurrentACKStatus(uint8_t index)
Is called internally to get the current ACKStatus.
Definition: sensor_lib.c:908
RequestFactoryReset
bool RequestFactoryReset()
Request selected sensor to reset to factory defaults.
Definition: sensor_lib.c:2361
GetU16FromPayload_u16
uint16_t GetU16FromPayload_u16(const uint8_t *Payload_pu8)
Is called from Getter functions to extract values from payload. In this case a uint16-value.
Definition: sensor_lib.c:2878
GetParameterSystemResetReason_t
ResetReason_t GetParameterSystemResetReason_t()
Blocking Request to read the last Reset Reason from current sensor.
Definition: sensor_lib.c:3170
CommsInterfaceType_t
CommsInterfaceType_t
Definition: custom_types.h:10
SetParameterSignalProcessingNoiseRatioThreshold
bool SetParameterSignalProcessingNoiseRatioThreshold(uint8_t Threshold_u8)
Blocking Request to set the Noise Ratio Threshold for current target sensor.
Definition: sensor_lib.c:2707
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
Point3D_t
struct Point3D_t Point3D_t
GetU8FromTwoArgumentPayload_u8
uint8_t GetU8FromTwoArgumentPayload_u8(const uint8_t *Payload_pu8)
Is called from Getter functions to extract values from payload. In this case a uint8-value.
Definition: sensor_lib.c:2867
ADCDump_t
struct ADCDump_t ADCDump_t
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
sensor_lib_config.h
This file contains all library configurations.
ACK_Status_t
Definition: sensor_lib.h:93
VersionByte_t
VersionByte_t
Definition: message_flags.h:143
GetParameterTransducerNumOfPulses_u8
uint8_t GetParameterTransducerNumOfPulses_u8()
Blocking Request to read the current Transducer Number of Pulses from current sensor.
Definition: sensor_lib.c:2983
Point1D_t
struct Point1D_t Point1D_t
ACK_Status_t::SenderId_u16
uint16_t SenderId_u16
Definition: sensor_lib.h:95
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
SetTargetSensor
void SetTargetSensor(uint16_t TargetSensor_u16)
With this function, the user can set the current target-id, all comming messages will be send to.
Definition: lib_utils.cpp:35
GetParameterSignalProcessingEnableNearFieldDetection_b
bool GetParameterSignalProcessingEnableNearFieldDetection_b()
Blocking Request to read whether near field detection is enabled in the current sensor.
Definition: sensor_lib.c:3059
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
GetParameterSignalProcessingEnableAutoGain_b
bool GetParameterSignalProcessingEnableAutoGain_b()
Blocking Request to read whether auto gain is enabled in the current sensor.
Definition: sensor_lib.c:3087
RequestLoadSettings
bool RequestLoadSettings()
Request selected sensor to load saved settings.
Definition: sensor_lib.c:2391
GetParameterTransducerVolume_u8
uint8_t GetParameterTransducerVolume_u8()
Blocking Request to read the current Transducer Volume from current sensor.
Definition: sensor_lib.c:2969
SetParameterSignalProcessingEnableNearFieldDetection
bool SetParameterSignalProcessingEnableNearFieldDetection(bool Enable_b)
Blocking Request to enable near field detection for current target sensor.
Definition: sensor_lib.c:2721
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
Sensor_t
Definition: sensor_lib.h:83
custom_structs.h
Point1D_t::VectorLength_u16
uint16_t VectorLength_u16
Definition: sensor_lib.h:49
LogLevel_t
LogLevel_t
Definition: custom_types.h:101
WaitForADCSessionEnd
uint16_t WaitForADCSessionEnd()
Blocking Function call to wait for SessionEnd Payload.
Definition: sensor_lib.c:3384
Sensor_t::InterfaceIndex_u8
uint8_t InterfaceIndex_u8
Definition: sensor_lib.h:86
Interface_t
Definition: sensor_lib.c:182
SensorState_t
SensorState_t
Definition: custom_types.h:24
RegisterRdyCallback
void RegisterRdyCallback(void(*Callback)(uint16_t Sender_u16))
Interface function to register a callback function that is called whenever an Ready Payload is receiv...
Definition: sensor_lib.c:3403
Point3D_t::X_i16
int16_t X_i16
Definition: sensor_lib.h:41
GetParameterSystemCalibrationState_b
bool GetParameterSystemCalibrationState_b()
Blocking Request to read whether the current sensor has been calibrated.
Definition: sensor_lib.c:3231
SetParameterADCFixedFrameRate
bool SetParameterADCFixedFrameRate(uint8_t FrameRate_u8)
Blocking Request to set the fixed framerate for current target sensor.
Definition: sensor_lib.c:2615
WaitForSessionEnd
uint16_t WaitForSessionEnd()
Blocking Function call to wait for SessionEnd Payload.
Definition: sensor_lib.c:3370
SetParameterTransducerVolume
bool SetParameterTransducerVolume(uint8_t Volume_u8)
Blocking Request to set the Transducer Volume for current target sensor.
Definition: sensor_lib.c:2631
GetADCDumpData
ADCDump_t * GetADCDumpData(uint16_t Sender_u16)
Interface function to get current ADC-Dump from SenderId.
Definition: sensor_lib.c:3443
ACK_Status_t::WaitForACK_b
bool WaitForACK_b
Definition: sensor_lib.h:96
SetParameterSignalProcessingEnableMultipathFilter
bool SetParameterSignalProcessingEnableMultipathFilter(bool Enable_b)
Blocking Request to enable near the multipath filter for current target sensor.
Definition: sensor_lib.c:2735
RegisterSessionStartCallback
void RegisterSessionStartCallback(void(*Callback)(uint16_t Sender_u16))
Interface function to register a callback function that is called whenever an SessionStart Payload is...
Definition: sensor_lib.c:3309
ACK_Status_t::ACK_b
bool ACK_b
Definition: sensor_lib.h:97
SetParameterTransducerNumOfPulses
bool SetParameterTransducerNumOfPulses(uint8_t NumOfPulses_u8)
Blocking Request to set the Number of Transducer Pulses for current target sensor.
Definition: sensor_lib.c:2645
GetParameterADCFixedFrameRate_u8
uint8_t GetParameterADCFixedFrameRate_u8()
Blocking Request to read the current set ADC-Framerate from current sensor.
Definition: sensor_lib.c:2953
GetResponsePayloadFromACKStatus
uint8_t * GetResponsePayloadFromACKStatus(ACK_Status_t *ackstatus)
Is called internally to extract the payload of a response.
Definition: sensor_lib.c:988
Sensor_Session_t::Point1D_tp
Point1D_t Point1D_tp[MAX_NUMBER_OF_POINTS_PER_SESSION]
Definition: sensor_lib.h:70
SetParameterSignalProcessingNoiseLevelThresholdFactor
bool SetParameterSignalProcessingNoiseLevelThresholdFactor(float Factor_f)
Blocking Request to set the Noise Level Threshold Factor for current target sensor.
Definition: sensor_lib.c:2690
Point1D_t
Definition: sensor_lib.h:47
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
RegisterADCDumpSessionEndCallback
void RegisterADCDumpSessionEndCallback(void(*Callback)(uint16_t Sender_u16))
Interface function to register a callback function that is called whenever an SessionEnd Payload for ...
Definition: sensor_lib.c:3364
SetParameterSystemLogLevel
bool SetParameterSystemLogLevel(LogLevel_t LogLevel_t)
Blocking Request to set the Loglevel for current target sensor.
Definition: sensor_lib.c:2798
WaitForReady
uint16_t WaitForReady()
Blocking Function call to wait for Ready Payload.
Definition: sensor_lib.c:3395
Sensor_Session_t::NumberOf3DPoints
uint8_t NumberOf3DPoints
Definition: sensor_lib.h:69
ResetReason_t
ResetReason_t
Definition: custom_types.h:77
Sensor_t
struct Sensor_t Sensor_t
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
WaitForACK
void WaitForACK(uint8_t *payload, uint16_t length_u16)
This function is called from blocking Set* Functions and blocks until the wait_ack_sem is unlocked by...
Definition: sensor_lib.c:1316
Sensor_t::SensorMode
enum SensorMode_t SensorMode
Definition: sensor_lib.h:87
ADCDump_t::DumpBlob_pu8
uint8_t * DumpBlob_pu8
Definition: sensor_lib.h:80
Sensor_Session_t::SenderId_u16
uint16_t SenderId_u16
Definition: sensor_lib.h:64
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
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
GetU16FromTwoArgumentPayload_u16
uint16_t GetU16FromTwoArgumentPayload_u16(const uint8_t *Payload_pu8)
Is called from Getter functions to extract values from payload. In this case a uint16-value.
Definition: sensor_lib.c:2894
GetI32FromPayload_i32
int32_t GetI32FromPayload_i32(const uint8_t *Payload_pu8)
Is called from Getter functions to extract values from payload. In this case a i32-value.
Definition: sensor_lib.c:2909
Point3D_t
Definition: sensor_lib.h:39
Point3D_t::Z_i16
int16_t Z_i16
Definition: sensor_lib.h:43
Sensor_t::InterfaceSensorId_u16
uint16_t InterfaceSensorId_u16
Definition: sensor_lib.h:85
GetParameterSignalProcessingHumidity_u8
uint8_t GetParameterSignalProcessingHumidity_u8()
Blocking Request to read the current Transducer Humidity setting from current sensor.
Definition: sensor_lib.c:3015
ADCDump_t::ReceivedDumpSize_u32
uint32_t ReceivedDumpSize_u32
Definition: sensor_lib.h:79
CAN_MAX_FRAME_LEN
#define CAN_MAX_FRAME_LEN
Definition: message_flags.h:15
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
ADCDump_t::SessionState
SessionState_t SessionState
Definition: sensor_lib.h:76
GetParameterADCUseFixedFrameRate_b
bool GetParameterADCUseFixedFrameRate_b()
Blocking Request to read the "Use fixed framerate" value from current sensor.
Definition: sensor_lib.c:2939
Version_t
Definition: custom_structs.h:12
GetParameterSignalProcessingEnableMultipathFilter_b
bool GetParameterSignalProcessingEnableMultipathFilter_b()
Blocking Request to read whether the multipath filter is enabled in the current sensor.
Definition: sensor_lib.c:3073
SetParameterSystemSensorMode
bool SetParameterSystemSensorMode(SensorMode_t Mode_t)
Blocking Request to set the Sensor Mode for current target sensor.
Definition: sensor_lib.c:2812
SensorMode_t
SensorMode_t
Definition: custom_types.h:65
RequestADCDump
bool RequestADCDump()
Request selected sensor to create an ADC-Dump.
Definition: sensor_lib.c:2559
Sensor_Session_t::NoiseLevel_u16
uint16_t NoiseLevel_u16
Definition: sensor_lib.h:66
message_flags.h
Contains various enums and structs used to facilitate communication between Toposens sensors and othe...
UID_t
struct UID_t UID_t
UID_t
Definition: sensor_lib.h:34
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_t::values
uint8_t values[UID_SIZE]
Definition: sensor_lib.h:36
UID_SIZE
#define UID_SIZE
Definition: sensor_lib.h:29
MAX_NUMBER_OF_POINTS_PER_SESSION
#define MAX_NUMBER_OF_POINTS_PER_SESSION
Upper Limit of suppored POINT Data per Point Data Session. 3D OR 2D. A maximum of 2x as much point da...
Definition: sensor_lib_config.h:40
WaitForSessionStart
uint16_t WaitForSessionStart()
Blocking Function call to wait for SessionStart Payload.
Definition: sensor_lib.c:3342
GetI32FromTwoArgumentPayload_i32
int32_t GetI32FromTwoArgumentPayload_i32(const uint8_t *Payload_pu8)
Is called from Getter functions to extract values from two argument payload. In this case a i32-value...
Definition: sensor_lib.c:2924
Sensor_Session_t
struct Sensor_Session_t Sensor_Session_t
ADCDump_t::ExpectedDumpSize_u32
uint32_t ExpectedDumpSize_u32
Definition: sensor_lib.h:78
Sensor_Session_t
Definition: sensor_lib.h:61
GetParameterSignalProcessingNoiseRatioThreshold_u8
uint8_t GetParameterSignalProcessingNoiseRatioThreshold_u8()
Blocking Request to read the current Noise Ratio Threshold from current sensor.
Definition: sensor_lib.c:3045
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
ACK_Status_t
struct ACK_Status_t ACK_Status_t
SetParameterSignalProcessingHumidity
bool SetParameterSignalProcessingHumidity(uint8_t Humidity_u8)
Blocking Request to set the Humidity for current target sensor.
Definition: sensor_lib.c:2676
GetParameterSignalProcessingNoiseLevelThresholdFactor_f
float GetParameterSignalProcessingNoiseLevelThresholdFactor_f()
Blocking Request to read the current Noise Level Threshold Factor from current sensor.
Definition: sensor_lib.c:3029
RequestStoreSettings
bool RequestStoreSettings()
Request selected sensor to store current settings.
Definition: sensor_lib.c:2379
ADCDump_t::SenderId_u16
uint16_t SenderId_u16
Definition: sensor_lib.h:77
RegisterADCDumpStartRequestCallback
void RegisterADCDumpStartRequestCallback(void(*Callback)(uint16_t Sender_u16, uint32_t ADCDumpSize_32))
Interface function to register a callback function that is called whenever an ADC-Dump Start Payload ...
Definition: sensor_lib.c:3415
Sensor_Session_t::Point3D_tp
Point3D_t Point3D_tp[MAX_NUMBER_OF_POINTS_PER_SESSION]
Definition: sensor_lib.h:71
RUNNING
@ RUNNING
Definition: sensor_lib.h:57
SetParameterSystemNodeID
bool SetParameterSystemNodeID(uint16_t NodeID_u16)
Blocking Request to set a new NodeID for current target sensor.
Definition: sensor_lib.c:2765
ACK_Status_t::ResponsePayload_pu8
uint8_t ResponsePayload_pu8[CAN_MAX_FRAME_LEN]
Definition: sensor_lib.h:98
ADCDump_t
Definition: sensor_lib.h:74
SetParameterSignalProcessingEnableAutoGain
bool SetParameterSignalProcessingEnableAutoGain(bool Enable_b)
Blocking Request to enable auto gain for current target sensor.
Definition: sensor_lib.c:2749
SetParameterSignalProcessingTemperature
bool SetParameterSignalProcessingTemperature(float Temperature_f)
Blocking Request to set the Temperature for current target sensor.
Definition: sensor_lib.c:2659
GetU8FromPayload_u8
uint8_t GetU8FromPayload_u8(const uint8_t *Payload_pu8)
Is called from Getter functions to extract values from payload. In this case a uint8-value.
Definition: sensor_lib.c:2856
COMPLETE
@ COMPLETE
Definition: sensor_lib.h:58
RequestWasSuccessful_b
bool RequestWasSuccessful_b()
Definition: sensor_lib.c:2317
INIT
@ INIT
Definition: sensor_lib.h:55
EXPECTED
@ EXPECTED
Definition: sensor_lib.h:56
RegisterPointSessionEndCallback
void RegisterPointSessionEndCallback(void(*Callback)(uint16_t Sender_u16))
Interface function to register a callback function that is called whenever an SessionEnd Payload is r...
Definition: sensor_lib.c:3358


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