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 | 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_t * | GetADCDumpData (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_t * | GetCurrentACKStatus (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_t * | GetKnownSensors () |
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_t * | GetSessionData (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) |
TBD.
Describe here the module structure, design and the interface to the system
void ACKADCDumpStart | ( | uint16_t | TargetSensor_u16 | ) |
Accept ADCDump start for the target sensor.
[in] | TargetSensor_u16 | Sensor that ADCDump start is to be accepted |
Definition at line 3270 of file sensor_lib.c.
void ACKSessionEnd | ( | ) |
void ACKSessionStart | ( | uint16_t | TargetSensor_u16 | ) |
Accept session start for the target sensor.
[in] | TargetSensor_u16 | Sensor that session start is to be accepted |
Definition at line 3245 of file sensor_lib.c.
|
static |
Compares request and response payload and validates if the response indicates a success of the requested action.
[in] | *request | |
[in] | *response |
Definition at line 2589 of file sensor_lib.c.
|
static |
[in] | SensorInterface_t | |
[in] | *InterfaceName_cp |
Definition at line 1011 of file sensor_lib.c.
|
static |
Tries to add the station with the Sender_u32 list of known stations.
[in] | Sender_u16 | to be added |
[in] | SensorInterfaceIndex_u8 |
Definition at line 1339 of file sensor_lib.c.
|
static |
|
static |
|
static |
uint8_t CalculateUARTChecksum | ( | const uint8_t * | Payload_pu8, |
uint8_t | PayloadLength_u8 | ||
) |
[in] | *Payload_pu | |
[in] | PayloadLength_u8 |
Definition at line 1030 of file sensor_lib.c.
|
static |
|
static |
|
static |
This function is called from WaitForACK and configures CurrentACKStatus-Struct-Array. The content of this struct is in EvaluateACKStatus_b.
[in] | *payload | The 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.
void DeinitInterface | ( | CommsInterfaceType_t | Interface_t | ) |
Instruction to deinit the specified interface type.
[in] | Interface_t | The kind of interface to be deinit. |
Definition at line 2279 of file sensor_lib.c.
|
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.
[in] | SenderId_u16 | |
[in] | *ReceivedPayload_pu8 |
Definition at line 1243 of file sensor_lib.c.
ADCDump_t* GetADCDumpData | ( | uint16_t | Sender_u16 | ) |
Interface function to get current ADC-Dump from SenderId.
[in] | Sender_u16 |
Definition at line 3443 of file sensor_lib.c.
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.
[in] | *Payload_pu8 |
Definition at line 2842 of file sensor_lib.c.
ACK_Status_t* GetCurrentACKStatus | ( | uint8_t | index | ) |
Is called internally to get the current ACKStatus.
[in] | index |
Definition at line 908 of file sensor_lib.c.
|
static |
|
static |
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.
[in] | *Payload_pu8 |
Definition at line 2909 of file sensor_lib.c.
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.
[in] | *Payload_pu8 |
Definition at line 2924 of file sensor_lib.c.
|
static |
Sensor_t* GetKnownSensors | ( | ) |
Returns pointer to array containing all known sensors. With GetNumberOfKnownSensors() users can get length of array.
Definition at line 765 of file sensor_lib.c.
uint8_t GetNumberOfKnownSensors | ( | ) |
Returns number of known sensors. With GetKnownSensors() users an pointer to an array containing the ID's of the sensors.
Definition at line 799 of file sensor_lib.c.
uint8_t GetParameterADCFixedFrameRate_u8 | ( | ) |
Blocking Request to read the current set ADC-Framerate from current sensor.
Definition at line 2953 of file sensor_lib.c.
bool GetParameterADCUseFixedFrameRate_b | ( | ) |
Blocking Request to read the "Use fixed framerate" value from current sensor.
Definition at line 2939 of file sensor_lib.c.
bool GetParameterSignalProcessingEnableAutoGain_b | ( | ) |
Blocking Request to read whether auto gain is enabled in the current sensor.
Definition at line 3087 of file sensor_lib.c.
bool GetParameterSignalProcessingEnableMultipathFilter_b | ( | ) |
Blocking Request to read whether the multipath filter is enabled in the current sensor.
Definition at line 3073 of file sensor_lib.c.
bool GetParameterSignalProcessingEnableNearFieldDetection_b | ( | ) |
Blocking Request to read whether near field detection is enabled in the current sensor.
Definition at line 3059 of file sensor_lib.c.
uint8_t GetParameterSignalProcessingHumidity_u8 | ( | ) |
Blocking Request to read the current Transducer Humidity setting from current sensor.
Definition at line 3015 of file sensor_lib.c.
float GetParameterSignalProcessingNoiseLevelThresholdFactor_f | ( | ) |
Blocking Request to read the current Noise Level Threshold Factor from current sensor.
Definition at line 3029 of file sensor_lib.c.
uint8_t GetParameterSignalProcessingNoiseRatioThreshold_u8 | ( | ) |
Blocking Request to read the current Noise Ratio Threshold from current sensor.
Definition at line 3045 of file sensor_lib.c.
float GetParameterSignalProcessingTemperature_f | ( | ) |
Blocking Request to read the current Transducer Temperature setting from current sensor.
Definition at line 2997 of file sensor_lib.c.
bool GetParameterSystemCalibrationState_b | ( | ) |
Blocking Request to read whether the current sensor has been calibrated.
Definition at line 3231 of file sensor_lib.c.
LogLevel_t GetParameterSystemLogLevel_t | ( | ) |
Blocking Request to read the current System Log Level from current sensor.
Definition at line 3156 of file sensor_lib.c.
float GetParameterSystemMCUTemperature_f | ( | ) |
Blocking Request to read the current MCU Temperature from current sensor.
Definition at line 3138 of file sensor_lib.c.
uint16_t GetParameterSystemNodeID_u16 | ( | ) |
Blocking Request to read the current NodeID setting from current sensor.
Definition at line 3103 of file sensor_lib.c.
ResetReason_t GetParameterSystemResetReason_t | ( | ) |
Blocking Request to read the last Reset Reason from current sensor.
Definition at line 3170 of file sensor_lib.c.
SensorMode_t GetParameterSystemSensorMode_t | ( | ) |
Blocking Request to read the Sensor Mode from current sensor.
Definition at line 3217 of file sensor_lib.c.
SensorState_t GetParameterSystemSensorState_t | ( | ) |
Blocking Request to read the Sensor State from current sensor.
Definition at line 3184 of file sensor_lib.c.
UID_t GetParameterSystemUniqueID_t | ( | uint8_t | Index_u8 | ) |
Blocking Request to read the Unique ID from current sensor.
Definition at line 3198 of file sensor_lib.c.
uint8_t GetParameterTransducerNumOfPulses_u8 | ( | ) |
Blocking Request to read the current Transducer Number of Pulses from current sensor.
Definition at line 2983 of file sensor_lib.c.
uint8_t GetParameterTransducerVolume_u8 | ( | ) |
Blocking Request to read the current Transducer Volume from current sensor.
Definition at line 2969 of file sensor_lib.c.
uint8_t* GetResponsePayloadFromACKStatus | ( | ACK_Status_t * | ackstatus | ) |
Is called internally to extract the payload of a response.
[in] | *ackstatus |
Definition at line 988 of file sensor_lib.c.
bool GetSessionComplete_b | ( | uint16_t | TargetSensorId_u16 | ) |
Sensor_Session_t* GetSessionData | ( | uint16_t | Sender_u16 | ) |
Interface function to query current session-data (ongoing and closed session)
[in] | Sender_u16 | Sender-Id the suer wants to get current session-data from |
Definition at line 3422 of file sensor_lib.c.
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.
[in] | *Payload_pu8 |
Definition at line 2878 of file sensor_lib.c.
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.
[in] | *Payload_pu8 |
Definition at line 2894 of file sensor_lib.c.
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.
[in] | *Payload_pu8 |
Definition at line 2856 of file sensor_lib.c.
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.
[in] | *Payload_pu8 |
Definition at line 2867 of file sensor_lib.c.
|
static |
|
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.
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.
[in] | *InterfaceName | name of the linux /dev/ device that should be used for communication |
[in] | DataRate_u32 | Datarate the device should use. 1000000 for example on CAN Bus |
[in] | Interface_t | The 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.
|
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.
[in] | SenderId_u16 | |
[in] | *ReceivedPayload_pu8 |
Definition at line 1763 of file sensor_lib.c.
|
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.
[in] | SenderId_u16 | |
[in] | *ReceivedPayload_pu8 |
Definition at line 1808 of file sensor_lib.c.
|
static |
Validates whether the received message contains an ACK message. No more feature atm.
[in] | *ReceivedPayload_pu8 |
Definition at line 1369 of file sensor_lib.c.
|
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.
[in] | SenderId_u16 | |
[in] | *ReceivedPayload_pu8 | |
[in] | len |
Definition at line 1974 of file sensor_lib.c.
|
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.
[in] | SenderId_u16 | |
[in] | *ReceivedPayload_pu8 |
Definition at line 1929 of file sensor_lib.c.
|
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.
[in] | SenderId_u16 | |
[in] | *ReceivedPayload_pu8 |
Definition at line 1911 of file sensor_lib.c.
|
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.
[in] | SenderId_u16 | |
[in] | *ReceivedPayload_pu8 |
Definition at line 1723 of file sensor_lib.c.
|
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.
[in] | SenderId_u16 | |
[in] | *ReceivedPayload_pu8 |
Definition at line 1741 of file sensor_lib.c.
|
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.
[in] | SenderId_u16 | |
[in] | *ReceivedPayload_pu8 |
Definition at line 1877 of file sensor_lib.c.
|
static |
Validates whether the received payload represents a Session-Data-Information.
[in] | SenderId_u16 | |
[in] | *ReceivedPayload_pu8 |
Definition at line 1903 of file sensor_lib.c.
|
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.
[in] | SenderId_u16 | |
[in] | *ReceivedPayload_pu8 |
Definition at line 1647 of file sensor_lib.c.
|
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.
[in] | SenderId_u16 | |
[in] | *ReceivedPayload_pu8 |
Definition at line 1415 of file sensor_lib.c.
void ParseBootloaderLogMessageToText | ( | char * | Output_p8, |
const uint8_t * | ReceivedPayload_pu8 | ||
) |
Parses Bootloader specific log messages into human readable text.
[out] | *Output_p8 | |
[in] | *ReceivedPayload_pu8 |
Definition at line 3599 of file sensor_lib.c.
void ParseCalibrationLogMessageToText | ( | char * | Output_p8, |
const uint8_t * | ReceivedPayload_pu8 | ||
) |
Parses calibration related log messages into human readable text.
[out] | *Output_p8 | |
[in] | *ReceivedPayload_pu8 |
Definition at line 3763 of file sensor_lib.c.
void ParseLogMessageToText | ( | char * | Output_p8, |
uint16_t | SenderId_u16, | ||
const uint8_t * | ReceivedPayload_pu8 | ||
) |
Parses log messages into human readable text.
[out] | *Output_p8 | |
[in] | SenderId_u16 | |
[in] | *ReceivedPayload_pu8 |
Definition at line 3521 of file sensor_lib.c.
|
static |
Iterates the payload over all known message types, which in turn trigger their actions. Aborts when the payload corresponds to a known message.
[in] | SenderId_u16 | |
[in] | *msg | |
[in] | len |
Definition at line 2010 of file sensor_lib.c.
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.
[out] | *Output_p8 | |
[in] | *ReceivedPayload_pu8 |
Definition at line 3660 of file sensor_lib.c.
void ParseSignalProcessingLogMessageToText | ( | char * | Output_p8, |
const uint8_t * | ReceivedPayload_pu8 | ||
) |
Parses signal processing specific log messages into human readable text.
[out] | *Output_p8 | |
[in] | *ReceivedPayload_pu8 |
Definition at line 3691 of file sensor_lib.c.
void ParseSoftwareLogMessageToText | ( | char * | Output_p8, |
const uint8_t * | ReceivedPayload_pu8 | ||
) |
Parses software-issue specific log messages into human readable text.
[out] | *Output_p8 | |
[in] | *ReceivedPayload_pu8 |
Definition at line 3731 of file sensor_lib.c.
void ParseStringLogMessageToText | ( | char * | Output_p8, |
const uint8_t * | ReceivedPayload_pu8 | ||
) |
Parses string log messages into human readable text.
[out] | *Output_p8 | |
[in] | *ReceivedPayload_pu8 |
Definition at line 3756 of file sensor_lib.c.
|
static |
|
static |
Only for debugging - print the content of payload to stdout.
[in] | *payload | pointer to payload that should be printed |
Definition at line 1147 of file sensor_lib.c.
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.
[in] | Callback | function pointer |
Definition at line 3364 of file sensor_lib.c.
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.
[in] | Callback | function pointer |
Definition at line 3415 of file sensor_lib.c.
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.
[in] | Callback | function pointer |
Definition at line 3409 of file sensor_lib.c.
void RegisterPointSessionEndCallback | ( | void(*)(uint16_t Sender_u16) | Callback | ) |
Interface function to register a callback function that is called whenever an SessionEnd Payload is received.
[in] | Callback | function pointer |
Definition at line 3358 of file sensor_lib.c.
void RegisterRdyCallback | ( | void(*)(uint16_t Sender_u16) | Callback | ) |
Interface function to register a callback function that is called whenever an Ready Payload is received.
[in] | Callback | function pointer |
Definition at line 3403 of file sensor_lib.c.
void RegisterSessionStartCallback | ( | void(*)(uint16_t Sender_u16) | Callback | ) |
Interface function to register a callback function that is called whenever an SessionStart Payload is received.
[in] | Callback | function pointer |
Definition at line 3309 of file sensor_lib.c.
|
static |
Will remove Sender_u16 from list of known sensors.
[in] | Sender_u16 |
Definition at line 3484 of file sensor_lib.c.
|
static |
Replaces one known sensor-id with another. Called if Change-Node-Id Request is executed.
[in] | OldId_u16 | |
[in] | NewId_u16 |
Definition at line 3463 of file sensor_lib.c.
bool RequestADCDump | ( | ) |
Request selected sensor to create an ADC-Dump.
Definition at line 2559 of file sensor_lib.c.
bool RequestFactoryReset | ( | ) |
Request selected sensor to reset to factory defaults.
Definition at line 2361 of file sensor_lib.c.
bool RequestLoadSettings | ( | ) |
Request selected sensor to load saved settings.
Definition at line 2391 of file sensor_lib.c.
bool RequestMeasurement | ( | ) |
Send's a request to start a new measurement.
Definition at line 2348 of file sensor_lib.c.
bool RequestReboot | ( | ) |
Request selected sensor to reboot.
Definition at line 2330 of file sensor_lib.c.
bool RequestStoreSettings | ( | ) |
Request selected sensor to store current settings.
Definition at line 2379 of file sensor_lib.c.
Version_t RequestVersion_t | ( | VersionByte_t | TargetComponent_t | ) |
Blocking - Request transmition of the current version of selected component from selected sensor.
[in] | TargetComponent_t | Component whose version number is required |
Definition at line 2193 of file sensor_lib.c.
bool RequestWasSuccessful_b | ( | ) |
|
static |
|
static |
Generic Send-Function. Takes Payload, length and interface as arguments. Atm. only CAN-Bus is implemented.
[in] | *payload | pointer to payload |
[in] | length | The number of bytes the payload is long |
Definition at line 1105 of file sensor_lib.c.
|
static |
|
static |
void SetADCSessionStateExpected | ( | uint16_t | TargetSensorId_u16 | ) |
bool SetParameterADCFixedFrameRate | ( | uint8_t | FrameRate_u8 | ) |
Blocking Request to set the fixed framerate for current target sensor.
[in] | FrameRate_u8 |
Definition at line 2615 of file sensor_lib.c.
bool SetParameterADCUseFixedFrameRate | ( | bool | UseFixedFrameRate_b | ) |
Blocking Request to use the fixed framerate for current target sensor.
[in] | UseFixedFrameRate_b |
Definition at line 2601 of file sensor_lib.c.
bool SetParameterSignalProcessingEnableAutoGain | ( | bool | Enable_b | ) |
Blocking Request to enable auto gain for current target sensor.
[in] | Enable_b |
Definition at line 2749 of file sensor_lib.c.
bool SetParameterSignalProcessingEnableMultipathFilter | ( | bool | Enable_b | ) |
Blocking Request to enable near the multipath filter for current target sensor.
[in] | Enable_b |
Definition at line 2735 of file sensor_lib.c.
bool SetParameterSignalProcessingEnableNearFieldDetection | ( | bool | Enable_b | ) |
Blocking Request to enable near field detection for current target sensor.
[in] | Enable_b |
Definition at line 2721 of file sensor_lib.c.
bool SetParameterSignalProcessingHumidity | ( | uint8_t | Humidity_u8 | ) |
Blocking Request to set the Humidity for current target sensor.
[in] | Humidity_u8 |
Definition at line 2676 of file sensor_lib.c.
bool SetParameterSignalProcessingNoiseLevelThresholdFactor | ( | float | Factor_f | ) |
Blocking Request to set the Noise Level Threshold Factor for current target sensor.
[in] | Factor_f |
Definition at line 2690 of file sensor_lib.c.
bool SetParameterSignalProcessingNoiseRatioThreshold | ( | uint8_t | Threshold_u8 | ) |
Blocking Request to set the Noise Ratio Threshold for current target sensor.
[in] | Threshold_u8 |
Definition at line 2707 of file sensor_lib.c.
bool SetParameterSignalProcessingTemperature | ( | float | Temperature_f | ) |
Blocking Request to set the Temperature for current target sensor.
[in] | Temperature_f |
Definition at line 2659 of file sensor_lib.c.
|
static |
Compares request and response payload and validates if the response indicates a success when setting the parameter.
[in] | *request | |
[in] | *response |
Definition at line 2574 of file sensor_lib.c.
bool SetParameterSystemLogLevel | ( | LogLevel_t | LogLevel_t | ) |
Blocking Request to set the Loglevel for current target sensor.
[in] | LogLevel_t | LogLevel_t |
Definition at line 2798 of file sensor_lib.c.
bool SetParameterSystemNodeID | ( | uint16_t | NodeID_u16 | ) |
Blocking Request to set a new NodeID for current target sensor.
[in] | NodeID_u16 |
Definition at line 2765 of file sensor_lib.c.
bool SetParameterSystemSensorMode | ( | SensorMode_t | Mode_t | ) |
Blocking Request to set the Sensor Mode for current target sensor.
[in] | Mode_t |
Definition at line 2812 of file sensor_lib.c.
bool SetParameterTransducerNumOfPulses | ( | uint8_t | NumOfPulses_u8 | ) |
Blocking Request to set the Number of Transducer Pulses for current target sensor.
[in] | NumOfPulses_u8 |
Definition at line 2645 of file sensor_lib.c.
bool SetParameterTransducerVolume | ( | uint8_t | Volume_u8 | ) |
Blocking Request to set the Transducer Volume for current target sensor.
[in] | Volume_u8 |
Definition at line 2631 of file sensor_lib.c.
void SetSessionStateExpected | ( | uint16_t | TargetSensorId_u16 | ) |
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.
[in] | TargetSensor_u16 | Target Id |
With this function, the user can set the current target-id, all comming messages will be send to.
Definition at line 35 of file lib_utils.cpp.
|
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)
[in] | SenderId_u16 | |
[in] | *ReceivedPayload_pu8 |
Definition at line 1378 of file sensor_lib.c.
|
static |
This function can be registered in uart-interfaces as callback to be called if a uart message is received.
[in] | *ReceivedUARTMsg_pu8 | |
[in] | UARTMsgLength_u16 | |
[in] | InterfaceId_u8 |
Definition at line 2060 of file sensor_lib.c.
|
static |
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.
[in] | *payload | The 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.
void * WaitForACKTimeout | ( | void * | vargp | ) |
uint16_t WaitForADCSessionEnd | ( | ) |
Blocking Function call to wait for SessionEnd Payload.
Definition at line 3384 of file sensor_lib.c.
uint16_t WaitForReady | ( | ) |
Blocking Function call to wait for Ready Payload.
Definition at line 3395 of file sensor_lib.c.
uint16_t WaitForSessionEnd | ( | ) |
Blocking Function call to wait for SessionEnd Payload.
Definition at line 3370 of file sensor_lib.c.
void * WaitForSessionEndTimeout | ( | void * | vargp | ) |
uint16_t WaitForSessionStart | ( | ) |
Blocking Function call to wait for SessionStart Payload.
Definition at line 3342 of file sensor_lib.c.
void * WaitForSessionStartTimeout | ( | void * | vargp | ) |