Files | Functions
Sensor Library

TBD. More...

Files

file  adc_dump_save_example.c
 
file  custom_structs.h
 
file  custom_types.h
 
file  example_common.c
 
file  example_common.h
 Library containing common functions that are used in the various examples.
 
file  log_message_example.c
 
file  message_flags.h
 Contains various enums and structs used to facilitate communication between Toposens sensors and other devices.
 
file  n_frames_single_shot_example.c
 
file  n_frames_single_shot_example_uart.c
 
file  sensor_lib.c
 This file contains the highlevel interface function code and the links to the low-level Protocol.
 
file  sensor_lib.h
 This file contains the highlevel interface prototypes to the low-level Protocol.
 
file  sensor_lib_config.h
 This file contains all library configurations.
 
file  uart_wrapper.h
 Header for UART wrapper.
 

Functions

void ACKADCDumpStart (uint16_t TargetSensor_u16)
 Accept ADCDump start for the target sensor. More...
 
void ACKSessionEnd ()
 Accept Session End for current sensor. More...
 
void ACKSessionStart (uint16_t TargetSensor_u16)
 Accept session start for the target sensor. More...
 
static bool ActionRequestSuccessful_b (const uint8_t *request, const uint8_t *response)
 Compares request and response payload and validates if the response indicates a success of the requested action. More...
 
static void AddInterfaceToInterfaceList (CommsInterfaceType_t SensorInterface_t, char *InterfaceName_cp)
 
static void AddSenderToKnownSensors (uint16_t Sender_u16, uint8_t SensorInterfaceIndex_u8)
 Tries to add the station with the Sender_u32 list of known stations. More...
 
static bool AllADCSessionsClosed_b ()
 
static bool AllSessionsActive_b ()
 
static bool AllSessionsClosed_b ()
 
uint8_t CalculateUARTChecksum (const uint8_t *Payload_pu8, uint8_t PayloadLength_u8)
 
static bool CloseADCSessionRecord_b (uint16_t SenderId_u16)
 
static bool CloseSessionRecord_b (uint16_t SenderId_u16)
 
static void ConfigureACKStatus (uint8_t *payload)
 This function is called from WaitForACK and configures CurrentACKStatus-Struct-Array. The content of this struct is in EvaluateACKStatus_b. More...
 
void DeinitInterface (CommsInterfaceType_t Interface_t)
 Instruction to deinit the specified interface type. More...
 
static bool EvaluateACKStatus_b (uint16_t SenderId_u16, uint8_t *ReceivedPayload_pu8)
 Validates whether the received message was sent by one of the sensors we expect an answer from and, if so, whether the payload contains an expected ACK message. If a responce was received from all senders we expect an answer from, the wait_ack_sem is also released 1x. More...
 
ADCDump_tGetADCDumpData (uint16_t Sender_u16)
 Interface function to get current ADC-Dump from SenderId. More...
 
bool GetADCSessionComplete_b (uint16_t TargetSensorId_u16)
 
bool GetADCSessionRunning_b (uint16_t TargetSensorId_u16)
 
bool GetBoolFromPayload_b (const uint8_t *Payload_pu8)
 Is called from Getter functions to extract values from payload. In this case a bool-value. More...
 
ACK_Status_tGetCurrentACKStatus (uint8_t index)
 Is called internally to get the current ACKStatus. More...
 
static int8_t GetCurrentSendersADCSessionIndex (uint16_t SenderId_u16)
 
static int8_t GetCurrentSendersSessionIndex (uint16_t SenderId_u16)
 
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. More...
 
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. More...
 
static int16_t GetInterfaceIndex_i16 (char *InterfaceName)
 
Sensor_tGetKnownSensors ()
 Returns pointer to array containing all known sensors. With GetNumberOfKnownSensors() users can get length of array. More...
 
uint8_t GetNumberOfKnownSensors ()
 Returns number of known sensors. With GetKnownSensors() users an pointer to an array containing the ID's of the sensors. More...
 
uint8_t GetParameterADCFixedFrameRate_u8 ()
 Blocking Request to read the current set ADC-Framerate from current sensor. More...
 
bool GetParameterADCUseFixedFrameRate_b ()
 Blocking Request to read the "Use fixed framerate" value from current sensor. More...
 
bool GetParameterSignalProcessingEnableAutoGain_b ()
 Blocking Request to read whether auto gain is enabled in the current sensor. More...
 
bool GetParameterSignalProcessingEnableMultipathFilter_b ()
 Blocking Request to read whether the multipath filter is enabled in the current sensor. More...
 
bool GetParameterSignalProcessingEnableNearFieldDetection_b ()
 Blocking Request to read whether near field detection is enabled in the current sensor. More...
 
uint8_t GetParameterSignalProcessingHumidity_u8 ()
 Blocking Request to read the current Transducer Humidity setting from current sensor. More...
 
float GetParameterSignalProcessingNoiseLevelThresholdFactor_f ()
 Blocking Request to read the current Noise Level Threshold Factor from current sensor. More...
 
uint8_t GetParameterSignalProcessingNoiseRatioThreshold_u8 ()
 Blocking Request to read the current Noise Ratio Threshold from current sensor. More...
 
float GetParameterSignalProcessingTemperature_f ()
 Blocking Request to read the current Transducer Temperature setting from current sensor. More...
 
bool GetParameterSystemCalibrationState_b ()
 Blocking Request to read whether the current sensor has been calibrated. More...
 
LogLevel_t GetParameterSystemLogLevel_t ()
 Blocking Request to read the current System Log Level from current sensor. More...
 
float GetParameterSystemMCUTemperature_f ()
 Blocking Request to read the current MCU Temperature from current sensor. More...
 
uint16_t GetParameterSystemNodeID_u16 ()
 Blocking Request to read the current NodeID setting from current sensor. More...
 
ResetReason_t GetParameterSystemResetReason_t ()
 Blocking Request to read the last Reset Reason from current sensor. More...
 
SensorMode_t GetParameterSystemSensorMode_t ()
 Blocking Request to read the Sensor Mode from current sensor. More...
 
SensorState_t GetParameterSystemSensorState_t ()
 Blocking Request to read the Sensor State from current sensor. More...
 
UID_t GetParameterSystemUniqueID_t (uint8_t Index_u8)
 Blocking Request to read the Unique ID from current sensor. More...
 
uint8_t GetParameterTransducerNumOfPulses_u8 ()
 Blocking Request to read the current Transducer Number of Pulses from current sensor. More...
 
uint8_t GetParameterTransducerVolume_u8 ()
 Blocking Request to read the current Transducer Volume from current sensor. More...
 
uint8_t * GetResponsePayloadFromACKStatus (ACK_Status_t *ackstatus)
 Is called internally to extract the payload of a response. More...
 
bool GetSessionComplete_b (uint16_t TargetSensorId_u16)
 
Sensor_Session_tGetSessionData (uint16_t Sender_u16)
 Interface function to query current session-data (ongoing and closed session) More...
 
bool GetSessionRunning_b (uint16_t TargetSensorId_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. More...
 
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. More...
 
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. More...
 
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. More...
 
static uint16_t GetUARTNodeId (uint8_t InterfaceId_u8)
 
static void Init_Semaphores ()
 Inits all Semaphores needed for Operation. If more Semaphores are added, init them here, too. More...
 
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 the semaphores if necessary. More...
 
static bool Is1DFrame_b (uint16_t SenderId_u16, const uint8_t *ReceivedPayload_pu8)
 Validates whether the received point-data-payload is a 1D-Point-Data. If so, the associated session is searched for and the information is stored there. Number of 1D Points is incremented. More...
 
static bool Is3DFrame_b (uint16_t SenderId_u16, const uint8_t *ReceivedPayload_pu8)
 Validates whether the received point-data-payload is a 3D-Point-Data. If so, the associated session is searched for and the information is stored there. Number of 3D Points is incremented. More...
 
static bool IsACKResponse_b (const uint8_t *ReceivedPayload_pu8)
 Validates whether the received message contains an ACK message. No more feature atm. More...
 
static bool IsADCDataFrame_b (uint16_t SenderId_u16, uint8_t *ReceivedPayload_pu8, uint8_t len)
 Validates whether the received payload represents an ADC-Data Message. If so and there is an open adc session from that sender, the data will be added to the DumpBlob-Data Array of that adc-session. More...
 
static bool IsADCDumpStartFrame_b (uint16_t SenderId_u16, const uint8_t *ReceivedPayload_pu8)
 Validates whether the received payload represents an ADC-Dump Start Message. If so the new adc session is initialized with the corresponding data from the payload and if a callback has been registered, the callback is executed with the SenderId as parameter. More...
 
static bool IsLogMessage (uint16_t SenderId_u16, uint8_t *ReceivedPayload_pu8)
 Validates whether the received payload represents a LogMessage. If so and a callback has been registered, the callback is executed with the SenderId and Payload as parameters. More...
 
static bool IsNearFieldFrame_b (uint16_t SenderId_u16, const uint8_t *ReceivedPayload_pu8)
 Validates whether the received point-data-payload is a near-filed-information. If so, the associated session is searched for and the information is stored there. More...
 
static bool IsNoiseLevelFrame_b (uint16_t SenderId_u16, const uint8_t *ReceivedPayload_pu8)
 Validates whether the received point-data-payload is a noise-level-information. If so, the associated session is searched for and the information is stored there. More...
 
static bool IsReadyFrame (uint16_t SenderId_u16, const uint8_t *ReceivedPayload_pu8)
 Validates whether the received payload represents a "Ready"-Information. If so and a callback has been registered, the callback is executed with the SenderId as parameter. More...
 
static bool IsSessionDataFrame_b (uint16_t SenderId_u16, const uint8_t *ReceivedPayload_pu8)
 Validates whether the received payload represents a Session-Data-Information. More...
 
static bool IsSessionEndFrame_b (uint16_t SenderId_u16, const uint8_t *ReceivedPayload_pu8)
 Validates whether the received message contains an EOS command. If so, CloseSessionRecord_b or CloseADCSessionRecord_b is triggered. If a callback has been stored, it is called. wait_session_end_sem is resolved to resolve a possible blocking wait. More...
 
static bool IsSessionStartFrame_b (uint16_t SenderId_u16, const uint8_t *ReceivedPayload_pu8)
 Validates whether the received message contains an Session-Start command. If so, StartNewSessionRecord_b is triggered. wait_session_start_sem is resolved to resolve a possible blocking wait. If a callback has been stored, it is called. More...
 
void ParseBootloaderLogMessageToText (char *Output_p8, const uint8_t *ReceivedPayload_pu8)
 Parses Bootloader specific log messages into human readable text. More...
 
void ParseCalibrationLogMessageToText (char *Output_p8, const uint8_t *ReceivedPayload_pu8)
 Parses calibration related log messages into human readable text. More...
 
void ParseLogMessageToText (char *Output_p8, uint16_t SenderId_u16, const uint8_t *ReceivedPayload_pu8)
 Parses log messages into human readable text. More...
 
static bool ParseMessage_b (uint16_t SenderId_u16, uint8_t *msg, uint8_t len)
 Iterates the payload over all known message types, which in turn trigger their actions. Aborts when the payload corresponds to a known message. More...
 
void ParseResetReasonLogMessageToText (char *Output_p8, const uint8_t *ReceivedPayload_pu8)
 
void ParseSelfCheckLogMessageToText (char *Output_p8, const uint8_t *ReceivedPayload_pu8)
 Parses self check specific log messages into human readable text. More...
 
void ParseSignalProcessingLogMessageToText (char *Output_p8, const uint8_t *ReceivedPayload_pu8)
 Parses signal processing specific log messages into human readable text. More...
 
void ParseSoftwareLogMessageToText (char *Output_p8, const uint8_t *ReceivedPayload_pu8)
 Parses software-issue specific log messages into human readable text. More...
 
void ParseStringLogMessageToText (char *Output_p8, const uint8_t *ReceivedPayload_pu8)
 Parses string log messages into human readable text. More...
 
static void PrintADCBlob (uint16_t SenderId_u16)
 Debug Function to print. More...
 
static void PrintPayload (const uint8_t *payload)
 Only for debugging - print the content of payload to stdout. More...
 
void RegisterADCDumpSessionEndCallback (void(*Callback)(uint16_t Sender_u16))
 Interface function to register a callback function that is called whenever an SessionEnd Payload for an active ADCDump is received. More...
 
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 is received. More...
 
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 received. More...
 
void RegisterPointSessionEndCallback (void(*Callback)(uint16_t Sender_u16))
 Interface function to register a callback function that is called whenever an SessionEnd Payload is received. More...
 
void RegisterRdyCallback (void(*Callback)(uint16_t Sender_u16))
 Interface function to register a callback function that is called whenever an Ready Payload is received. More...
 
void RegisterSessionStartCallback (void(*Callback)(uint16_t Sender_u16))
 Interface function to register a callback function that is called whenever an SessionStart Payload is received. More...
 
static void RemoveSenderFromList (uint16_t Sender_u16)
 Will remove Sender_u16 from list of known sensors. More...
 
static void ReplaceIdInListOfKnownSensors (uint16_t OldId_u16, uint16_t NewId_u16)
 Replaces one known sensor-id with another. Called if Change-Node-Id Request is executed. More...
 
bool RequestADCDump ()
 Request selected sensor to create an ADC-Dump. More...
 
bool RequestFactoryReset ()
 Request selected sensor to reset to factory defaults. More...
 
bool RequestLoadSettings ()
 Request selected sensor to load saved settings. More...
 
bool RequestMeasurement ()
 Send's a request to start a new measurement. More...
 
bool RequestReboot ()
 Request selected sensor to reboot. More...
 
bool RequestStoreSettings ()
 Request selected sensor to store current settings. More...
 
Version_t RequestVersion_t (VersionByte_t TargetComponent_t)
 Blocking - Request transmition of the current version of selected component from selected sensor. More...
 
bool RequestWasSuccessful_b ()
 
static void ResetListOfKnownSensors ()
 Clears the list of known Sensors. More...
 
static void SendCommand (uint8_t *payload, uint16_t length)
 Generic Send-Function. Takes Payload, length and interface as arguments. Atm. only CAN-Bus is implemented. More...
 
static void SendViaCAN (uint8_t *payload, uint16_t length)
 
static void SendViaUART (uint8_t *payload, uint16_t length, uint8_t InterfaceId_u8)
 
void SetADCSessionStateExpected (uint16_t TargetSensorId_u16)
 
bool SetParameterADCFixedFrameRate (uint8_t FrameRate_u8)
 Blocking Request to set the fixed framerate for current target sensor. More...
 
bool SetParameterADCUseFixedFrameRate (bool UseFixedFrameRate_b)
 Blocking Request to use the fixed framerate for current target sensor. More...
 
bool SetParameterSignalProcessingEnableAutoGain (bool Enable_b)
 Blocking Request to enable auto gain for current target sensor. More...
 
bool SetParameterSignalProcessingEnableMultipathFilter (bool Enable_b)
 Blocking Request to enable near the multipath filter for current target sensor. More...
 
bool SetParameterSignalProcessingEnableNearFieldDetection (bool Enable_b)
 Blocking Request to enable near field detection for current target sensor. More...
 
bool SetParameterSignalProcessingHumidity (uint8_t Humidity_u8)
 Blocking Request to set the Humidity for current target sensor. More...
 
bool SetParameterSignalProcessingNoiseLevelThresholdFactor (float Factor_f)
 Blocking Request to set the Noise Level Threshold Factor for current target sensor. More...
 
bool SetParameterSignalProcessingNoiseRatioThreshold (uint8_t Threshold_u8)
 Blocking Request to set the Noise Ratio Threshold for current target sensor. More...
 
bool SetParameterSignalProcessingTemperature (float Temperature_f)
 Blocking Request to set the Temperature for current target sensor. More...
 
static bool SetParameterSuccessful_b (const uint8_t *request, const uint8_t *response)
 Compares request and response payload and validates if the response indicates a success when setting the parameter. More...
 
bool SetParameterSystemLogLevel (LogLevel_t LogLevel_t)
 Blocking Request to set the Loglevel for current target sensor. More...
 
bool SetParameterSystemNodeID (uint16_t NodeID_u16)
 Blocking Request to set a new NodeID for current target sensor. More...
 
bool SetParameterSystemSensorMode (SensorMode_t Mode_t)
 Blocking Request to set the Sensor Mode for current target sensor. More...
 
bool SetParameterTransducerNumOfPulses (uint8_t NumOfPulses_u8)
 Blocking Request to set the Number of Transducer Pulses for current target sensor. More...
 
bool SetParameterTransducerVolume (uint8_t Volume_u8)
 Blocking Request to set the Transducer Volume for current target sensor. More...
 
void SetSessionStateExpected (uint16_t TargetSensorId_u16)
 
void SetTargetSensor (uint16_t TargetSensor_u16)
 With this function, the user can set the current target-id, all comming messages will be send to. More...
 
static bool StartNewSessionRecord_b (uint16_t SenderId_u16, const uint8_t *ReceivedPayload_pu8)
 Starts a new point session recording for the given sender ID. The new session is initialized with the corresponding data from the payload (maximum number of points) More...
 
static void UARTReadCallback (uint8_t *ReceivedUARTMsg_pu8, uint16_t UARTMsgLength_u16, uint8_t InterfaceId_u8)
 This function can be registered in uart-interfaces as callback to be called if a uart message is received. More...
 
static bool ValidateUARTChecksum (UART_Msg_t *ReceivedUARTMsg_pt)
 
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 the EvaluateACKStatus_b function. The blocking behavior is achieved by trying to fetch the same semaphore twice. The second sem_wait blocks until sem_post is executed elsewhere. That happens in EvaluateACKStatus_b. More...
 
void * WaitForACKTimeout (void *vargp)
 
uint16_t WaitForADCSessionEnd ()
 Blocking Function call to wait for SessionEnd Payload. More...
 
uint16_t WaitForReady ()
 Blocking Function call to wait for Ready Payload. More...
 
uint16_t WaitForSessionEnd ()
 Blocking Function call to wait for SessionEnd Payload. More...
 
void * WaitForSessionEndTimeout (void *vargp)
 
uint16_t WaitForSessionStart ()
 Blocking Function call to wait for SessionStart Payload. More...
 
void * WaitForSessionStartTimeout (void *vargp)
 

Detailed Description

TBD.


Describe here the module structure, design and the interface to the system

Function Documentation

◆ ACKADCDumpStart()

void ACKADCDumpStart ( uint16_t  TargetSensor_u16)

Accept ADCDump start for the target sensor.


Parameters
[in]TargetSensor_u16Sensor that ADCDump start is to be accepted

Definition at line 3270 of file sensor_lib.c.

◆ ACKSessionEnd()

void ACKSessionEnd ( )

Accept Session End for current sensor.


Definition at line 3299 of file sensor_lib.c.

◆ ACKSessionStart()

void ACKSessionStart ( uint16_t  TargetSensor_u16)

Accept session start for the target sensor.


Parameters
[in]TargetSensor_u16Sensor that session start is to be accepted

Definition at line 3245 of file sensor_lib.c.

◆ ActionRequestSuccessful_b()

static bool ActionRequestSuccessful_b ( const uint8_t *  request,
const uint8_t *  response 
)
static

Compares request and response payload and validates if the response indicates a success of the requested action.


Parameters
[in]*request
[in]*response
Returns
bool true if action request was successful bool false in case of an error

Definition at line 2589 of file sensor_lib.c.

◆ AddInterfaceToInterfaceList()

static void AddInterfaceToInterfaceList ( CommsInterfaceType_t  SensorInterface_t,
char *  InterfaceName_cp 
)
static

Parameters
[in]SensorInterface_t
[in]*InterfaceName_cp

Definition at line 1011 of file sensor_lib.c.

◆ AddSenderToKnownSensors()

static void AddSenderToKnownSensors ( uint16_t  Sender_u16,
uint8_t  SensorInterfaceIndex_u8 
)
static

Tries to add the station with the Sender_u32 list of known stations.


Parameters
[in]Sender_u16to be added
[in]SensorInterfaceIndex_u8

Definition at line 1339 of file sensor_lib.c.

◆ AllADCSessionsClosed_b()

static bool AllADCSessionsClosed_b ( )
static

Returns
bool

Definition at line 1633 of file sensor_lib.c.

◆ AllSessionsActive_b()

static bool AllSessionsActive_b ( )
static

Returns
bool

Definition at line 1607 of file sensor_lib.c.

◆ AllSessionsClosed_b()

static bool AllSessionsClosed_b ( )
static

Returns
bool

Definition at line 1621 of file sensor_lib.c.

◆ CalculateUARTChecksum()

uint8_t CalculateUARTChecksum ( const uint8_t *  Payload_pu8,
uint8_t  PayloadLength_u8 
)

Parameters
[in]*Payload_pu
[in]PayloadLength_u8
Returns
uint8_t

Definition at line 1030 of file sensor_lib.c.

◆ CloseADCSessionRecord_b()

static bool CloseADCSessionRecord_b ( uint16_t  SenderId_u16)
static

Parameters
[in]SenderId_u16
Returns
bool

Definition at line 1556 of file sensor_lib.c.

◆ CloseSessionRecord_b()

static bool CloseSessionRecord_b ( uint16_t  SenderId_u16)
static

Parameters
[in]SenderId_u16
Returns
bool

Definition at line 1537 of file sensor_lib.c.

◆ ConfigureACKStatus()

static void ConfigureACKStatus ( uint8_t *  payload)
static

This function is called from WaitForACK and configures CurrentACKStatus-Struct-Array. The content of this struct is in EvaluateACKStatus_b.


Parameters
[in]*payloadThe payload is copied to wait_ack_payload_pu8. EvaluateACKStatus_b compares incoming ACKs whether they match the desired ACK.

Definition at line 1187 of file sensor_lib.c.

◆ DeinitInterface()

void DeinitInterface ( CommsInterfaceType_t  Interface_t)

Instruction to deinit the specified interface type.


Parameters
[in]Interface_tThe kind of interface to be deinit.

Definition at line 2279 of file sensor_lib.c.

◆ EvaluateACKStatus_b()

static bool EvaluateACKStatus_b ( uint16_t  SenderId_u16,
uint8_t *  ReceivedPayload_pu8 
)
static

Validates whether the received message was sent by one of the sensors we expect an answer from and, if so, whether the payload contains an expected ACK message. If a responce was received from all senders we expect an answer from, the wait_ack_sem is also released 1x.


Parameters
[in]SenderId_u16
[in]*ReceivedPayload_pu8
Returns
bool true if an expected ACK Response was received

Definition at line 1243 of file sensor_lib.c.

◆ GetADCDumpData()

ADCDump_t* GetADCDumpData ( uint16_t  Sender_u16)

Interface function to get current ADC-Dump from SenderId.


Parameters
[in]Sender_u16
Returns
ADCDump_t* ADC-Dump that belongs to SenderId. NULL if not found.

Definition at line 3443 of file sensor_lib.c.

◆ GetADCSessionComplete_b()

bool GetADCSessionComplete_b ( uint16_t  TargetSensorId_u16)

Parameters
[in]TargetSensorId_u16
Returns
bool

Definition at line 2533 of file sensor_lib.c.

◆ GetADCSessionRunning_b()

bool GetADCSessionRunning_b ( uint16_t  TargetSensorId_u16)

Parameters
[in]TargetSensorId_u16
Returns
bool

Definition at line 2507 of file sensor_lib.c.

◆ 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.


Parameters
[in]*Payload_pu8
Returns
bool true value was set bool false value was not set

Definition at line 2842 of file sensor_lib.c.

◆ GetCurrentACKStatus()

ACK_Status_t* GetCurrentACKStatus ( uint8_t  index)

Is called internally to get the current ACKStatus.


Parameters
[in]index
Returns
ACK_Status_t* pointer to the struct

Definition at line 908 of file sensor_lib.c.

◆ GetCurrentSendersADCSessionIndex()

static int8_t GetCurrentSendersADCSessionIndex ( uint16_t  SenderId_u16)
static

Parameters
[in]SenderId_u16
Returns
int8_t

Definition at line 1501 of file sensor_lib.c.

◆ GetCurrentSendersSessionIndex()

static int8_t GetCurrentSendersSessionIndex ( uint16_t  SenderId_u16)
static

Parameters
[in]SenderId_u16
Returns
int8_t

Definition at line 1465 of file sensor_lib.c.

◆ 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.


Parameters
[in]*Payload_pu8
Returns
int32_t value extracted from payload

Definition at line 2909 of file sensor_lib.c.

◆ 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.


Parameters
[in]*Payload_pu8
Returns
int32_t value extracted from payload

Definition at line 2924 of file sensor_lib.c.

◆ GetInterfaceIndex_i16()

static int16_t GetInterfaceIndex_i16 ( char *  InterfaceName)
static

Parameters
[in]*InterfaceName_cp
Returns
int16_t

Definition at line 997 of file sensor_lib.c.

◆ GetKnownSensors()

Sensor_t* GetKnownSensors ( )

Returns pointer to array containing all known sensors. With GetNumberOfKnownSensors() users can get length of array.


Returns
Sensor_t* Pointer to array containing all currently known Sensors on Bus

Definition at line 765 of file sensor_lib.c.

◆ GetNumberOfKnownSensors()

uint8_t GetNumberOfKnownSensors ( )

Returns number of known sensors. With GetKnownSensors() users an pointer to an array containing the ID's of the sensors.


Returns
uint8_t Number of currently known sensors on Bus

Definition at line 799 of file sensor_lib.c.

◆ GetParameterADCFixedFrameRate_u8()

uint8_t GetParameterADCFixedFrameRate_u8 ( )

Blocking Request to read the current set ADC-Framerate from current sensor.


Returns
uint8_t framerate

Definition at line 2953 of file sensor_lib.c.

◆ GetParameterADCUseFixedFrameRate_b()

bool GetParameterADCUseFixedFrameRate_b ( )

Blocking Request to read the "Use fixed framerate" value from current sensor.


Returns
bool true if fixed framerate is used

Definition at line 2939 of file sensor_lib.c.

◆ GetParameterSignalProcessingEnableAutoGain_b()

bool GetParameterSignalProcessingEnableAutoGain_b ( )

Blocking Request to read whether auto gain is enabled in the current sensor.


Returns
bool Enabled status

Definition at line 3087 of file sensor_lib.c.

◆ GetParameterSignalProcessingEnableMultipathFilter_b()

bool GetParameterSignalProcessingEnableMultipathFilter_b ( )

Blocking Request to read whether the multipath filter is enabled in the current sensor.


Returns
bool Enabled status

Definition at line 3073 of file sensor_lib.c.

◆ GetParameterSignalProcessingEnableNearFieldDetection_b()

bool GetParameterSignalProcessingEnableNearFieldDetection_b ( )

Blocking Request to read whether near field detection is enabled in the current sensor.


Returns
bool Enabled status

Definition at line 3059 of file sensor_lib.c.

◆ GetParameterSignalProcessingHumidity_u8()

uint8_t GetParameterSignalProcessingHumidity_u8 ( )

Blocking Request to read the current Transducer Humidity setting from current sensor.


Returns
uint8_t Set Humidity

Definition at line 3015 of file sensor_lib.c.

◆ GetParameterSignalProcessingNoiseLevelThresholdFactor_f()

float GetParameterSignalProcessingNoiseLevelThresholdFactor_f ( )

Blocking Request to read the current Noise Level Threshold Factor from current sensor.


Returns
float Noise Level Threshold Factor

Definition at line 3029 of file sensor_lib.c.

◆ GetParameterSignalProcessingNoiseRatioThreshold_u8()

uint8_t GetParameterSignalProcessingNoiseRatioThreshold_u8 ( )

Blocking Request to read the current Noise Ratio Threshold from current sensor.


Returns
uint8_t Noise Ratio Threshold

Definition at line 3045 of file sensor_lib.c.

◆ GetParameterSignalProcessingTemperature_f()

float GetParameterSignalProcessingTemperature_f ( )

Blocking Request to read the current Transducer Temperature setting from current sensor.


Returns
float Set Temperature

Definition at line 2997 of file sensor_lib.c.

◆ GetParameterSystemCalibrationState_b()

bool GetParameterSystemCalibrationState_b ( )

Blocking Request to read whether the current sensor has been calibrated.


Returns
bool Calibration status

Definition at line 3231 of file sensor_lib.c.

◆ GetParameterSystemLogLevel_t()

LogLevel_t GetParameterSystemLogLevel_t ( )

Blocking Request to read the current System Log Level from current sensor.


Returns
LogLevel_t SystemLogLevel

Definition at line 3156 of file sensor_lib.c.

◆ GetParameterSystemMCUTemperature_f()

float GetParameterSystemMCUTemperature_f ( )

Blocking Request to read the current MCU Temperature from current sensor.


Returns
float Temperature

Definition at line 3138 of file sensor_lib.c.

◆ GetParameterSystemNodeID_u16()

uint16_t GetParameterSystemNodeID_u16 ( )

Blocking Request to read the current NodeID setting from current sensor.


Returns
uint16_t NodeID

Definition at line 3103 of file sensor_lib.c.

◆ GetParameterSystemResetReason_t()

ResetReason_t GetParameterSystemResetReason_t ( )

Blocking Request to read the last Reset Reason from current sensor.


Returns
ResetReason_t ResetReason

Definition at line 3170 of file sensor_lib.c.

◆ GetParameterSystemSensorMode_t()

SensorMode_t GetParameterSystemSensorMode_t ( )

Blocking Request to read the Sensor Mode from current sensor.


Returns
SensorMode_t Sensor Mode

Definition at line 3217 of file sensor_lib.c.

◆ GetParameterSystemSensorState_t()

SensorState_t GetParameterSystemSensorState_t ( )

Blocking Request to read the Sensor State from current sensor.


Returns
SensorState_t Sensor State

Definition at line 3184 of file sensor_lib.c.

◆ GetParameterSystemUniqueID_t()

UID_t GetParameterSystemUniqueID_t ( uint8_t  Index_u8)

Blocking Request to read the Unique ID from current sensor.


Returns
UID_t Unique ID

Definition at line 3198 of file sensor_lib.c.

◆ GetParameterTransducerNumOfPulses_u8()

uint8_t GetParameterTransducerNumOfPulses_u8 ( )

Blocking Request to read the current Transducer Number of Pulses from current sensor.


Returns
uint8_t Transducer Number of Pulses

Definition at line 2983 of file sensor_lib.c.

◆ GetParameterTransducerVolume_u8()

uint8_t GetParameterTransducerVolume_u8 ( )

Blocking Request to read the current Transducer Volume from current sensor.


Returns
uint8_t current Transducer Volume

Definition at line 2969 of file sensor_lib.c.

◆ GetResponsePayloadFromACKStatus()

uint8_t* GetResponsePayloadFromACKStatus ( ACK_Status_t ackstatus)

Is called internally to extract the payload of a response.


Parameters
[in]*ackstatus
Returns
uint8_t* pointer to the payload

Definition at line 988 of file sensor_lib.c.

◆ GetSessionComplete_b()

bool GetSessionComplete_b ( uint16_t  TargetSensorId_u16)

Parameters
[in]TargetSensorId_u16
Returns
bool

Definition at line 2479 of file sensor_lib.c.

◆ GetSessionData()

Sensor_Session_t* GetSessionData ( uint16_t  Sender_u16)

Interface function to query current session-data (ongoing and closed session)


Parameters
[in]Sender_u16Sender-Id the suer wants to get current session-data from
Returns
Sensor_Session_t*

Definition at line 3422 of file sensor_lib.c.

◆ GetSessionRunning_b()

bool GetSessionRunning_b ( uint16_t  TargetSensorId_u16)

Parameters
[in]TargetSensorId_u16
Returns
bool

Definition at line 2450 of file sensor_lib.c.

◆ 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.


Parameters
[in]*Payload_pu8
Returns
uint16_t value extracted from payload

Definition at line 2878 of file sensor_lib.c.

◆ 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.


Parameters
[in]*Payload_pu8
Returns
uint16_t value extracted from payload

Definition at line 2894 of file sensor_lib.c.

◆ 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.


Parameters
[in]*Payload_pu8
Returns
uint8_t value extracted from payload

Definition at line 2856 of file sensor_lib.c.

◆ 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.


Parameters
[in]*Payload_pu8
Returns
uint8_t value extracted from payload

Definition at line 2867 of file sensor_lib.c.

◆ GetUARTNodeId()

static uint16_t GetUARTNodeId ( uint8_t  InterfaceId_u8)
static

Parameters
[in]InterfaceId_u8
Returns
uint16_t

Definition at line 3117 of file sensor_lib.c.

◆ Init_Semaphores()

static void Init_Semaphores ( )
static

Inits all Semaphores needed for Operation. If more Semaphores are added, init them here, too.


Definition at line 2212 of file sensor_lib.c.

◆ 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 the semaphores if necessary.


Parameters
[in]*InterfaceNamename of the linux /dev/ device that should be used for communication
[in]DataRate_u32Datarate the device should use. 1000000 for example on CAN Bus
[in]Interface_tThe kind of interface to be used. Attention! A wrong interfacename might lead to unexpected system behavior!

Definition at line 2225 of file sensor_lib.c.

◆ Is1DFrame_b()

static bool Is1DFrame_b ( uint16_t  SenderId_u16,
const uint8_t *  ReceivedPayload_pu8 
)
static

Validates whether the received point-data-payload is a 1D-Point-Data. If so, the associated session is searched for and the information is stored there. Number of 1D Points is incremented.


Parameters
[in]SenderId_u16
[in]*ReceivedPayload_pu8
Returns
bool true if the point-data-payload contains 1D-Point-informations.

Definition at line 1763 of file sensor_lib.c.

◆ Is3DFrame_b()

static bool Is3DFrame_b ( uint16_t  SenderId_u16,
const uint8_t *  ReceivedPayload_pu8 
)
static

Validates whether the received point-data-payload is a 3D-Point-Data. If so, the associated session is searched for and the information is stored there. Number of 3D Points is incremented.


Parameters
[in]SenderId_u16
[in]*ReceivedPayload_pu8
Returns
bool true if the point-data-payload contains 3D-Point-informations.

Definition at line 1808 of file sensor_lib.c.

◆ IsACKResponse_b()

static bool IsACKResponse_b ( const uint8_t *  ReceivedPayload_pu8)
static

Validates whether the received message contains an ACK message. No more feature atm.


Parameters
[in]*ReceivedPayload_pu8
Returns
bool true if message contains an ACK message

Definition at line 1369 of file sensor_lib.c.

◆ IsADCDataFrame_b()

static bool IsADCDataFrame_b ( uint16_t  SenderId_u16,
uint8_t *  ReceivedPayload_pu8,
uint8_t  len 
)
static

Validates whether the received payload represents an ADC-Data Message. If so and there is an open adc session from that sender, the data will be added to the DumpBlob-Data Array of that adc-session.


Parameters
[in]SenderId_u16
[in]*ReceivedPayload_pu8
[in]len
Returns
bool true if the received payload represents an DC-Data Message.

Definition at line 1974 of file sensor_lib.c.

◆ IsADCDumpStartFrame_b()

static bool IsADCDumpStartFrame_b ( uint16_t  SenderId_u16,
const uint8_t *  ReceivedPayload_pu8 
)
static

Validates whether the received payload represents an ADC-Dump Start Message. If so the new adc session is initialized with the corresponding data from the payload and if a callback has been registered, the callback is executed with the SenderId as parameter.


Parameters
[in]SenderId_u16
[in]*ReceivedPayload_pu8
Returns
bool true if the received payload represents an ADC-Dump Start Message.

Definition at line 1929 of file sensor_lib.c.

◆ IsLogMessage()

static bool IsLogMessage ( uint16_t  SenderId_u16,
uint8_t *  ReceivedPayload_pu8 
)
static

Validates whether the received payload represents a LogMessage. If so and a callback has been registered, the callback is executed with the SenderId and Payload as parameters.


Parameters
[in]SenderId_u16
[in]*ReceivedPayload_pu8
Returns
bool true if the received payload represents a LogMessage.

Definition at line 1911 of file sensor_lib.c.

◆ IsNearFieldFrame_b()

static bool IsNearFieldFrame_b ( uint16_t  SenderId_u16,
const uint8_t *  ReceivedPayload_pu8 
)
static

Validates whether the received point-data-payload is a near-filed-information. If so, the associated session is searched for and the information is stored there.


Parameters
[in]SenderId_u16
[in]*ReceivedPayload_pu8
Returns
bool true if the point-data-payload contains near-filed-informations.

Definition at line 1723 of file sensor_lib.c.

◆ IsNoiseLevelFrame_b()

static bool IsNoiseLevelFrame_b ( uint16_t  SenderId_u16,
const uint8_t *  ReceivedPayload_pu8 
)
static

Validates whether the received point-data-payload is a noise-level-information. If so, the associated session is searched for and the information is stored there.


Parameters
[in]SenderId_u16
[in]*ReceivedPayload_pu8
Returns
bool true if the point-data-payload contains noise-level-informations.

Definition at line 1741 of file sensor_lib.c.

◆ IsReadyFrame()

static bool IsReadyFrame ( uint16_t  SenderId_u16,
const uint8_t *  ReceivedPayload_pu8 
)
static

Validates whether the received payload represents a "Ready"-Information. If so and a callback has been registered, the callback is executed with the SenderId as parameter.


Parameters
[in]SenderId_u16
[in]*ReceivedPayload_pu8
Returns
bool true if the received payload represents a "Ready"-Information.

Definition at line 1877 of file sensor_lib.c.

◆ IsSessionDataFrame_b()

static bool IsSessionDataFrame_b ( uint16_t  SenderId_u16,
const uint8_t *  ReceivedPayload_pu8 
)
static

Validates whether the received payload represents a Session-Data-Information.


Parameters
[in]SenderId_u16
[in]*ReceivedPayload_pu8
Returns
bool true if the received payload represents a Session-Data.

Definition at line 1903 of file sensor_lib.c.

◆ IsSessionEndFrame_b()

static bool IsSessionEndFrame_b ( uint16_t  SenderId_u16,
const uint8_t *  ReceivedPayload_pu8 
)
static

Validates whether the received message contains an EOS command. If so, CloseSessionRecord_b or CloseADCSessionRecord_b is triggered. If a callback has been stored, it is called. wait_session_end_sem is resolved to resolve a possible blocking wait.


Parameters
[in]SenderId_u16
[in]*ReceivedPayload_pu8
Returns
bool true if message contains an EOS message

Definition at line 1647 of file sensor_lib.c.

◆ IsSessionStartFrame_b()

static bool IsSessionStartFrame_b ( uint16_t  SenderId_u16,
const uint8_t *  ReceivedPayload_pu8 
)
static

Validates whether the received message contains an Session-Start command. If so, StartNewSessionRecord_b is triggered. wait_session_start_sem is resolved to resolve a possible blocking wait. If a callback has been stored, it is called.


Parameters
[in]SenderId_u16
[in]*ReceivedPayload_pu8
Returns
bool true if message contains an Start Session message

Definition at line 1415 of file sensor_lib.c.

◆ ParseBootloaderLogMessageToText()

void ParseBootloaderLogMessageToText ( char *  Output_p8,
const uint8_t *  ReceivedPayload_pu8 
)

Parses Bootloader specific log messages into human readable text.


Parameters
[out]*Output_p8
[in]*ReceivedPayload_pu8

Definition at line 3599 of file sensor_lib.c.

◆ ParseCalibrationLogMessageToText()

void ParseCalibrationLogMessageToText ( char *  Output_p8,
const uint8_t *  ReceivedPayload_pu8 
)

Parses calibration related log messages into human readable text.


Parameters
[out]*Output_p8
[in]*ReceivedPayload_pu8

Definition at line 3763 of file sensor_lib.c.

◆ ParseLogMessageToText()

void ParseLogMessageToText ( char *  Output_p8,
uint16_t  SenderId_u16,
const uint8_t *  ReceivedPayload_pu8 
)

Parses log messages into human readable text.


Parameters
[out]*Output_p8
[in]SenderId_u16
[in]*ReceivedPayload_pu8

Definition at line 3521 of file sensor_lib.c.

◆ ParseMessage_b()

static bool ParseMessage_b ( uint16_t  SenderId_u16,
uint8_t *  msg,
uint8_t  len 
)
static

Iterates the payload over all known message types, which in turn trigger their actions. Aborts when the payload corresponds to a known message.


Parameters
[in]SenderId_u16
[in]*msg
[in]len
Returns
bool true if the received payload was a known message.

Definition at line 2010 of file sensor_lib.c.

◆ ParseResetReasonLogMessageToText()

void ParseResetReasonLogMessageToText ( char *  Output_p8,
const uint8_t *  ReceivedPayload_pu8 
)

Parameters
[out]*Output_p8
[in]*ReceivedPayload_pu8

Definition at line 3585 of file sensor_lib.c.

◆ ParseSelfCheckLogMessageToText()

void ParseSelfCheckLogMessageToText ( char *  Output_p8,
const uint8_t *  ReceivedPayload_pu8 
)

Parses self check specific log messages into human readable text.


Parameters
[out]*Output_p8
[in]*ReceivedPayload_pu8

Definition at line 3660 of file sensor_lib.c.

◆ ParseSignalProcessingLogMessageToText()

void ParseSignalProcessingLogMessageToText ( char *  Output_p8,
const uint8_t *  ReceivedPayload_pu8 
)

Parses signal processing specific log messages into human readable text.


Parameters
[out]*Output_p8
[in]*ReceivedPayload_pu8

Definition at line 3691 of file sensor_lib.c.

◆ ParseSoftwareLogMessageToText()

void ParseSoftwareLogMessageToText ( char *  Output_p8,
const uint8_t *  ReceivedPayload_pu8 
)

Parses software-issue specific log messages into human readable text.


Parameters
[out]*Output_p8
[in]*ReceivedPayload_pu8

Definition at line 3731 of file sensor_lib.c.

◆ ParseStringLogMessageToText()

void ParseStringLogMessageToText ( char *  Output_p8,
const uint8_t *  ReceivedPayload_pu8 
)

Parses string log messages into human readable text.


Parameters
[out]*Output_p8
[in]*ReceivedPayload_pu8

Definition at line 3756 of file sensor_lib.c.

◆ PrintADCBlob()

static void PrintADCBlob ( uint16_t  SenderId_u16)
static

Debug Function to print.


Parameters
[in]SenderId_u16

Definition at line 1571 of file sensor_lib.c.

◆ PrintPayload()

static void PrintPayload ( const uint8_t *  payload)
static

Only for debugging - print the content of payload to stdout.


Parameters
[in]*payloadpointer to payload that should be printed

Definition at line 1147 of file sensor_lib.c.

◆ RegisterADCDumpSessionEndCallback()

void RegisterADCDumpSessionEndCallback ( void(*)(uint16_t Sender_u16)  Callback)

Interface function to register a callback function that is called whenever an SessionEnd Payload for an active ADCDump is received.


Parameters
[in]Callbackfunction pointer

Definition at line 3364 of file sensor_lib.c.

◆ RegisterADCDumpStartRequestCallback()

void RegisterADCDumpStartRequestCallback ( void(*)(uint16_t Sender_u16, uint32_t ADCDumpSize_32)  Callback)

Interface function to register a callback function that is called whenever an ADC-Dump Start Payload is received.


Parameters
[in]Callbackfunction pointer

Definition at line 3415 of file sensor_lib.c.

◆ RegisterLogMsgCallback()

void RegisterLogMsgCallback ( void(*)(uint16_t Sender_u16, uint8_t *ReceivedPayload_pu8)  Callback)

Interface function to register a callback function that is called whenever a Logmessage Payload is received.


Parameters
[in]Callbackfunction pointer

Definition at line 3409 of file sensor_lib.c.

◆ RegisterPointSessionEndCallback()

void RegisterPointSessionEndCallback ( void(*)(uint16_t Sender_u16)  Callback)

Interface function to register a callback function that is called whenever an SessionEnd Payload is received.


Parameters
[in]Callbackfunction pointer

Definition at line 3358 of file sensor_lib.c.

◆ RegisterRdyCallback()

void RegisterRdyCallback ( void(*)(uint16_t Sender_u16)  Callback)

Interface function to register a callback function that is called whenever an Ready Payload is received.


Parameters
[in]Callbackfunction pointer

Definition at line 3403 of file sensor_lib.c.

◆ RegisterSessionStartCallback()

void RegisterSessionStartCallback ( void(*)(uint16_t Sender_u16)  Callback)

Interface function to register a callback function that is called whenever an SessionStart Payload is received.


Parameters
[in]Callbackfunction pointer

Definition at line 3309 of file sensor_lib.c.

◆ RemoveSenderFromList()

static void RemoveSenderFromList ( uint16_t  Sender_u16)
static

Will remove Sender_u16 from list of known sensors.


Parameters
[in]Sender_u16

Definition at line 3484 of file sensor_lib.c.

◆ ReplaceIdInListOfKnownSensors()

static void ReplaceIdInListOfKnownSensors ( uint16_t  OldId_u16,
uint16_t  NewId_u16 
)
static

Replaces one known sensor-id with another. Called if Change-Node-Id Request is executed.


Parameters
[in]OldId_u16
[in]NewId_u16

Definition at line 3463 of file sensor_lib.c.

◆ RequestADCDump()

bool RequestADCDump ( )

Request selected sensor to create an ADC-Dump.


Returns
bool true if ACK bool false in case of NACK / unexpected CurrentACKStatus[REQUEST_RESPONSE_INDEX].ResponsePayload_pu8

Definition at line 2559 of file sensor_lib.c.

◆ RequestFactoryReset()

bool RequestFactoryReset ( )

Request selected sensor to reset to factory defaults.


Returns
bool true if ACK bool false in case of NACK / unexpected CurrentACKStatus[REQUEST_RESPONSE_INDEX].ResponsePayload_pu8

Definition at line 2361 of file sensor_lib.c.

◆ RequestLoadSettings()

bool RequestLoadSettings ( )

Request selected sensor to load saved settings.


Returns
bool true if ACK bool false in case of NACK / unexpected CurrentACKStatus[REQUEST_RESPONSE_INDEX].ResponsePayload_pu8

Definition at line 2391 of file sensor_lib.c.

◆ RequestMeasurement()

bool RequestMeasurement ( )

Send's a request to start a new measurement.


Returns
bool true if ACK bool false in case of NACK / unexpected CurrentACKStatus[REQUEST_RESPONSE_INDEX].ResponsePayload_pu8

Definition at line 2348 of file sensor_lib.c.

◆ RequestReboot()

bool RequestReboot ( )

Request selected sensor to reboot.


Returns
bool true if ACK bool false in case of NACK / unexpected CurrentACKStatus[REQUEST_RESPONSE_INDEX].ResponsePayload_pu8

Definition at line 2330 of file sensor_lib.c.

◆ RequestStoreSettings()

bool RequestStoreSettings ( )

Request selected sensor to store current settings.


Returns
bool true if ACK bool false in case of NACK / unexpected CurrentACKStatus[REQUEST_RESPONSE_INDEX].ResponsePayload_pu8

Definition at line 2379 of file sensor_lib.c.

◆ RequestVersion_t()

Version_t RequestVersion_t ( VersionByte_t  TargetComponent_t)

Blocking - Request transmition of the current version of selected component from selected sensor.


Parameters
[in]TargetComponent_tComponent whose version number is required
Returns
Version_t Received version

Definition at line 2193 of file sensor_lib.c.

◆ RequestWasSuccessful_b()

bool RequestWasSuccessful_b ( )

Returns
bool

Definition at line 2317 of file sensor_lib.c.

◆ ResetListOfKnownSensors()

static void ResetListOfKnownSensors ( )
static

Clears the list of known Sensors.


Definition at line 3475 of file sensor_lib.c.

◆ SendCommand()

static void SendCommand ( uint8_t *  payload,
uint16_t  length 
)
static

Generic Send-Function. Takes Payload, length and interface as arguments. Atm. only CAN-Bus is implemented.


Parameters
[in]*payloadpointer to payload
[in]lengthThe number of bytes the payload is long

Definition at line 1105 of file sensor_lib.c.

◆ SendViaCAN()

static void SendViaCAN ( uint8_t *  payload,
uint16_t  length 
)
static

Parameters
[in]*payload
[in]length

Definition at line 1051 of file sensor_lib.c.

◆ SendViaUART()

static void SendViaUART ( uint8_t *  payload,
uint16_t  length,
uint8_t  InterfaceId_u8 
)
static

Parameters
[in]*payload
[in]length
[in]InterfaceId_u8

Definition at line 1064 of file sensor_lib.c.

◆ SetADCSessionStateExpected()

void SetADCSessionStateExpected ( uint16_t  TargetSensorId_u16)

Parameters
[in]TargetSensorId_u16

Definition at line 2432 of file sensor_lib.c.

◆ SetParameterADCFixedFrameRate()

bool SetParameterADCFixedFrameRate ( uint8_t  FrameRate_u8)

Blocking Request to set the fixed framerate for current target sensor.


Parameters
[in]FrameRate_u8
Returns
bool true if setting was successful bool false in case of an error

Definition at line 2615 of file sensor_lib.c.

◆ SetParameterADCUseFixedFrameRate()

bool SetParameterADCUseFixedFrameRate ( bool  UseFixedFrameRate_b)

Blocking Request to use the fixed framerate for current target sensor.


Parameters
[in]UseFixedFrameRate_b
Returns
bool true if setting was successful bool false in case of an error

Definition at line 2601 of file sensor_lib.c.

◆ SetParameterSignalProcessingEnableAutoGain()

bool SetParameterSignalProcessingEnableAutoGain ( bool  Enable_b)

Blocking Request to enable auto gain for current target sensor.


Parameters
[in]Enable_b
Returns
bool true if setting was successful bool false in case of an error

Definition at line 2749 of file sensor_lib.c.

◆ SetParameterSignalProcessingEnableMultipathFilter()

bool SetParameterSignalProcessingEnableMultipathFilter ( bool  Enable_b)

Blocking Request to enable near the multipath filter for current target sensor.


Parameters
[in]Enable_b
Returns
bool true if setting was successful bool false in case of an error

Definition at line 2735 of file sensor_lib.c.

◆ SetParameterSignalProcessingEnableNearFieldDetection()

bool SetParameterSignalProcessingEnableNearFieldDetection ( bool  Enable_b)

Blocking Request to enable near field detection for current target sensor.


Parameters
[in]Enable_b
Returns
bool true if setting was successful bool false in case of an error

Definition at line 2721 of file sensor_lib.c.

◆ SetParameterSignalProcessingHumidity()

bool SetParameterSignalProcessingHumidity ( uint8_t  Humidity_u8)

Blocking Request to set the Humidity for current target sensor.


Parameters
[in]Humidity_u8
Returns
bool true if setting was successful bool false in case of an error

Definition at line 2676 of file sensor_lib.c.

◆ SetParameterSignalProcessingNoiseLevelThresholdFactor()

bool SetParameterSignalProcessingNoiseLevelThresholdFactor ( float  Factor_f)

Blocking Request to set the Noise Level Threshold Factor for current target sensor.


Parameters
[in]Factor_f
Returns
bool true if setting was successful bool false in case of an error

Definition at line 2690 of file sensor_lib.c.

◆ SetParameterSignalProcessingNoiseRatioThreshold()

bool SetParameterSignalProcessingNoiseRatioThreshold ( uint8_t  Threshold_u8)

Blocking Request to set the Noise Ratio Threshold for current target sensor.


Parameters
[in]Threshold_u8
Returns
bool true if setting was successful bool false in case of an error

Definition at line 2707 of file sensor_lib.c.

◆ SetParameterSignalProcessingTemperature()

bool SetParameterSignalProcessingTemperature ( float  Temperature_f)

Blocking Request to set the Temperature for current target sensor.


Parameters
[in]Temperature_f
Returns
bool true if setting was successful bool false in case of an error

Definition at line 2659 of file sensor_lib.c.

◆ SetParameterSuccessful_b()

static bool SetParameterSuccessful_b ( const uint8_t *  request,
const uint8_t *  response 
)
static

Compares request and response payload and validates if the response indicates a success when setting the parameter.


Parameters
[in]*request
[in]*response
Returns
bool true if setting was successful bool false in case of an error

Definition at line 2574 of file sensor_lib.c.

◆ SetParameterSystemLogLevel()

bool SetParameterSystemLogLevel ( LogLevel_t  LogLevel_t)

Blocking Request to set the Loglevel for current target sensor.


Parameters
[in]LogLevel_tLogLevel_t
Returns
bool true if setting was successful bool false in case of an error

Definition at line 2798 of file sensor_lib.c.

◆ SetParameterSystemNodeID()

bool SetParameterSystemNodeID ( uint16_t  NodeID_u16)

Blocking Request to set a new NodeID for current target sensor.


Parameters
[in]NodeID_u16
Returns
bool true if setting was successful bool false in case of an error

Definition at line 2765 of file sensor_lib.c.

◆ SetParameterSystemSensorMode()

bool SetParameterSystemSensorMode ( SensorMode_t  Mode_t)

Blocking Request to set the Sensor Mode for current target sensor.


Parameters
[in]Mode_t
Returns
bool true if setting was successful bool false in case of an error

Definition at line 2812 of file sensor_lib.c.

◆ SetParameterTransducerNumOfPulses()

bool SetParameterTransducerNumOfPulses ( uint8_t  NumOfPulses_u8)

Blocking Request to set the Number of Transducer Pulses for current target sensor.


Parameters
[in]NumOfPulses_u8
Returns
bool true if setting was successful bool false in case of an error

Definition at line 2645 of file sensor_lib.c.

◆ SetParameterTransducerVolume()

bool SetParameterTransducerVolume ( uint8_t  Volume_u8)

Blocking Request to set the Transducer Volume for current target sensor.


Parameters
[in]Volume_u8
Returns
bool true if setting was successful bool false in case of an error

Definition at line 2631 of file sensor_lib.c.

◆ SetSessionStateExpected()

void SetSessionStateExpected ( uint16_t  TargetSensorId_u16)

Parameters
[in]TargetSensorId_u16

Definition at line 2409 of file sensor_lib.c.

◆ SetTargetSensor()

void SetTargetSensor ( uint16_t  TargetSensor_u16) -> bool

With this function, the user can set the current target-id, all comming messages will be send to.


Parameters
[in]TargetSensor_u16Target Id

With this function, the user can set the current target-id, all comming messages will be send to.

Returns
true if successful, false otherwise
Todo:
This would likely make sense to be moved to the Device Driver library itself!

Definition at line 35 of file lib_utils.cpp.

◆ StartNewSessionRecord_b()

static bool StartNewSessionRecord_b ( uint16_t  SenderId_u16,
const uint8_t *  ReceivedPayload_pu8 
)
static

Starts a new point session recording for the given sender ID. The new session is initialized with the corresponding data from the payload (maximum number of points)


Parameters
[in]SenderId_u16
[in]*ReceivedPayload_pu8
Returns
bool true if a new session could be started

Definition at line 1378 of file sensor_lib.c.

◆ UARTReadCallback()

static void UARTReadCallback ( uint8_t *  ReceivedUARTMsg_pu8,
uint16_t  UARTMsgLength_u16,
uint8_t  InterfaceId_u8 
)
static

This function can be registered in uart-interfaces as callback to be called if a uart message is received.


Parameters
[in]*ReceivedUARTMsg_pu8
[in]UARTMsgLength_u16
[in]InterfaceId_u8

Definition at line 2060 of file sensor_lib.c.

◆ ValidateUARTChecksum()

static bool ValidateUARTChecksum ( UART_Msg_t ReceivedUARTMsg_pt)
static

Parameters
[in]*ReceivedUARTMsg_pt
Returns
bool

Definition at line 1043 of file sensor_lib.c.

◆ 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 the EvaluateACKStatus_b function. The blocking behavior is achieved by trying to fetch the same semaphore twice. The second sem_wait blocks until sem_post is executed elsewhere. That happens in EvaluateACKStatus_b.


Parameters
[in]*payloadThe payload is copied to wait_ack_payload_pu8. EvaluateACKStatus_b compares incoming ACKs whether they match the desired ACK.
[in]length_u16

Definition at line 1316 of file sensor_lib.c.

◆ WaitForACKTimeout()

void * WaitForACKTimeout ( void *  vargp)

Parameters
[in]*vargp

Definition at line 3315 of file sensor_lib.c.

◆ WaitForADCSessionEnd()

uint16_t WaitForADCSessionEnd ( )

Blocking Function call to wait for SessionEnd Payload.


Returns
uint16_t SenderId

Definition at line 3384 of file sensor_lib.c.

◆ WaitForReady()

uint16_t WaitForReady ( )

Blocking Function call to wait for Ready Payload.


Returns
uint16_t SenderId

Definition at line 3395 of file sensor_lib.c.

◆ WaitForSessionEnd()

uint16_t WaitForSessionEnd ( )

Blocking Function call to wait for SessionEnd Payload.


Returns
uint16_t SenderId

Definition at line 3370 of file sensor_lib.c.

◆ WaitForSessionEndTimeout()

void * WaitForSessionEndTimeout ( void *  vargp)

Parameters
[in]*vargp

Definition at line 3333 of file sensor_lib.c.

◆ WaitForSessionStart()

uint16_t WaitForSessionStart ( )

Blocking Function call to wait for SessionStart Payload.


Returns
uint16_t SenderId

Definition at line 3342 of file sensor_lib.c.

◆ WaitForSessionStartTimeout()

void * WaitForSessionStartTimeout ( void *  vargp)

Parameters
[in]*vargp

Definition at line 3324 of file sensor_lib.c.



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