Classes | Macros | Typedefs | Enumerations | Functions | Variables
sensor_lib.c File Reference

This file contains the highlevel interface function code and the links to the low-level Protocol. More...

#include "toposens/sensor_lib.h"
#include "toposens/uart_wrapper.h"
#include <endian.h>
#include <pthread.h>
#include <semaphore.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <unistd.h>
Include dependency graph for sensor_lib.c:

Go to the source code of this file.

Classes

struct  ADCDump_Data_t
 
struct  Interface_t
 
struct  Session_Data_t
 
struct  UART_Msg_t
 

Macros

#define FLOAT_CONVERSION_FACTOR   1000.0
 Sensor delivers data in 0.001 degree. This factor is usesed do calculate from and to degree. More...
 
#define MULTICAST_ID   0x00
 CAN-ID used if commands shall be send to all Sensors for example, to determine active sensors in the bus. More...
 
#define NUMBER_OF_ADC_DUMP_DATAPOINTS_PER_LINE   8
 Maximum Number of Datapoints copied from a ADC-Dump Data-Frame. More...
 
#define PARAM_BYTE_5_IDX   6
 Offset of 6'th parameter in Payload. More...
 
#define PARAM_BYTE_6_IDX   7
 Offset of 7'th parameter in Payload. More...
 
#define REQUEST_RESPONSE_INDEX   0
 If a Getter-Function is called while current sender is multicast id, this index of CurrentACKStatus.ResponsePayload_pu8 is used for return value evaluation. More...
 
#define SET_U16_LEN   5
 Number of Bytes that needs to be transmitted if 1 U16 value is set via a set-parameter function. More...
 
#define SET_U32_LEN   7
 Number of Bytes that needs to be transmitted if 1 U32 value is set via a set-parameter function. More...
 
#define SET_U8_LEN   4
 Number of Bytes that needs to be transmitted if 1 U8 value is set via a set-parameter function. More...
 
#define SET_U8_U16_LEN   6
 Number of Bytes that needs to be transmitted if 1U8 and 1 U16 value is set via a set-parameter function. More...
 
#define SET_U8_U8_LEN   5
 Number of Bytes that needs to be transmitted if 2 U8 values are set via a set-parameter function. More...
 
#define UART_CHECKSUM_TARGET   256
 
#define UART_DUMMY_ID   0x01
 

Typedefs

typedef struct ADCDump_Data_t ADCDump_Data_t
 
typedef struct Interface_t Interface_t
 
typedef struct Session_Data_t Session_Data_t
 
typedef struct UART_Msg_t UART_Msg_t
 
typedef enum UARTMessageState_t UARTMessageState_t
 

Enumerations

enum  UARTMessageState_t {
  UART_MESSAGE_STATE_UNKNOWN, UART_MESSAGE_STATE_IN_TRANSMIT_SIZE_UNKNOWN, UART_MESSAGE_STATE_IN_TRANSMIT_READ_PAYLOAD, UART_MESSAGE_STATE_TRANSMIT_COMPLETE,
  UART_MESSAGE_STATE_READ_CHECKSUM, UART_MESSAGE_STATE_VALIDATE_MSG_END
}
 

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...
 
static bool GetACKFromACKStatus (ACK_Status_t *ackstatus)
 
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...
 
static bool GetConnectedToCANBus ()
 
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)
 
static Sensor_Session_tGetCurrentSessionsActiveSessions (uint8_t index)
 
static uint8_t GetCurrentSessionsNumberOfActiveSessions_u8 ()
 
static uint16_t GetCurrentStatusInformant_u16 ()
 
static uint16_t GetCurrentTarget_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)
 
static uint16_t GetInterfaceSensorIdFromSensor (Sensor_t *sensor)
 
static Sensor_tGetKnownSensor (uint8_t index)
 
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...
 
static uint8_t GetNumberOfSensorsACKIsExpectedFrom ()
 
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...
 
static uint16_t GetSenderIdFromACKStatus (ACK_Status_t *ackstatus)
 
static uint16_t GetSenderIdFromSensorSession (Sensor_Session_t *session)
 
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)
 
static SessionState_t GetSessionStateFromSensorSession (Sensor_Session_t *session)
 
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 uint8_t * GetWaitACKPayload ()
 
static bool GetWaitForACKFromACKStatus (ACK_Status_t *ackstatus)
 
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 PrintKnownInterfaces ()
 
static void PrintKnownSensors ()
 
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)
 
static void SetACKForACKStatus (ACK_Status_t *ackstatus, bool ack)
 
void SetADCSessionStateExpected (uint16_t TargetSensorId_u16)
 
static void SetConnectedToCANBus (bool newvalue)
 
static void SetCurrentSessionsNumberOfActiveSessions_u8 (uint8_t newvalue)
 
static void SetCurrentStatusInformant_u16 (uint16_t newvalue)
 
static void SetCurrentTarget_u16 (uint16_t newvalue)
 
static void SetNumberOfKnownSensors (uint8_t newvalue)
 
static void SetNumberOfSensorsACKIsExpectedFrom (uint8_t newvalue)
 
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...
 
static void SetResponsePayloadForACKStatus (ACK_Status_t *ackstatus, uint8_t *payload, uint16_t len)
 
static void SetSenderIdForACKStatus (ACK_Status_t *ackstatus, uint16_t senderId)
 
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 void SetWaitForACKForACKStatus (ACK_Status_t *ackstatus, bool waitforack)
 
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...
 
static void WaitForACKNoSend (uint8_t *payload)
 
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)
 

Variables

static void(* ADCDUmpEndCallback )(uint16_t Sender_u16) = NULL
 
static void(* ADCDumpStartRequestCallback )(uint16_t Sender_u16, uint32_t ADCDumpSize_u32) = NULL
 
static bool ConnectedToCANBus_b = false
 
static bool ConnectedToCUART_b = false
 
static bool ConnectedToUSB_b = false
 
static ACK_Status_t CurrentACKStatus [MAX_NUMBER_OF_SENSORS_ON_BUS] = {0}
 
ADCDump_Data_t CurrentADCSessions = {0}
 
Session_Data_t CurrentSessions = {0}
 
static uint16_t CurrentStatusInformant_u16 = 0
 
static uint16_t CurrentTarget_u16 = MULTICAST_ID
 
static UART_Msg_t CurrentUARTMsg_t [MAX_NUMBER_OF_SENSORS_ON_BUS] = {0}
 
static Interface_t KnownInterfaces_tp [MAX_NUMBER_OF_SENSORS_ON_BUS] = {0}
 
static Sensor_t KnownSensors [MAX_NUMBER_OF_SENSORS_ON_BUS] = {0}
 
static void(* LogMsgCallback )(uint16_t Sender_u16, uint8_t *ReceivedPayload_pu8) = NULL
 
static pthread_mutex_t mutex_connectedtocanbus = PTHREAD_MUTEX_INITIALIZER
 
static pthread_mutex_t mutex_currentackstatus = PTHREAD_MUTEX_INITIALIZER
 
static pthread_mutex_t mutex_currentsessions = PTHREAD_MUTEX_INITIALIZER
 
static pthread_mutex_t mutex_currentstatusinformant = PTHREAD_MUTEX_INITIALIZER
 
static pthread_mutex_t mutex_currenttarget = PTHREAD_MUTEX_INITIALIZER
 
static pthread_mutex_t mutex_getdatafromsensor = PTHREAD_MUTEX_INITIALIZER
 
static pthread_mutex_t mutex_knownsensor = PTHREAD_MUTEX_INITIALIZER
 
static pthread_mutex_t mutex_knownsensors = PTHREAD_MUTEX_INITIALIZER
 
static pthread_mutex_t mutex_numberofknownsensors = PTHREAD_MUTEX_INITIALIZER
 
static pthread_mutex_t mutex_numberofsensorsackisexpectedfrom = PTHREAD_MUTEX_INITIALIZER
 
static pthread_mutex_t mutex_waitackpayload = PTHREAD_MUTEX_INITIALIZER
 
uint8_t NumberOfKnownInterfaces_u8 = 0
 
static uint8_t NumberOfKnownSensors_u8 = 0
 
static uint8_t NumberOfSensorsACKIsExpectedFrom_u8 = 0
 
static uint8_t NumberOfSensorsASessionStartIsExpectedFrom_u8 = 0
 
static void(* RdyCallback )(uint16_t Sender_u16) = NULL
 
static bool SemaphoresInit_b = false
 
static void(* SessionEndCallback )(uint16_t Sender_u16) = NULL
 
static void(* SessionStartCallback )(uint16_t Sender_u16) = NULL
 
static pthread_t timeoutID
 
static int timeoutmSeconds = TIMEOUT_M_SECONDS
 
static uint8_t UartPayload_pu8 [UART_MAX_FRAME_LEN] = {0}
 
static uint8_t wait_ack_payload_pu8 [CAN_MAX_FRAME_LEN] = {0}
 
static sem_t wait_ack_sem
 
static sem_t wait_adc_session_end_sem
 
static sem_t wait_ready_sem
 
static sem_t wait_session_end_sem
 
static sem_t wait_session_start_sem
 

Detailed Description

This file contains the highlevel interface function code and the links to the low-level Protocol.


Definition in file sensor_lib.c.

Macro Definition Documentation

◆ FLOAT_CONVERSION_FACTOR

#define FLOAT_CONVERSION_FACTOR   1000.0

Sensor delivers data in 0.001 degree. This factor is usesed do calculate from and to degree.


Definition at line 136 of file sensor_lib.c.

◆ MULTICAST_ID

#define MULTICAST_ID   0x00

CAN-ID used if commands shall be send to all Sensors for example, to determine active sensors in the bus.


Definition at line 93 of file sensor_lib.c.

◆ NUMBER_OF_ADC_DUMP_DATAPOINTS_PER_LINE

#define NUMBER_OF_ADC_DUMP_DATAPOINTS_PER_LINE   8

Maximum Number of Datapoints copied from a ADC-Dump Data-Frame.


Definition at line 131 of file sensor_lib.c.

◆ PARAM_BYTE_5_IDX

#define PARAM_BYTE_5_IDX   6

Offset of 6'th parameter in Payload.


Definition at line 98 of file sensor_lib.c.

◆ PARAM_BYTE_6_IDX

#define PARAM_BYTE_6_IDX   7

Offset of 7'th parameter in Payload.


Definition at line 102 of file sensor_lib.c.

◆ REQUEST_RESPONSE_INDEX

#define REQUEST_RESPONSE_INDEX   0

If a Getter-Function is called while current sender is multicast id, this index of CurrentACKStatus.ResponsePayload_pu8 is used for return value evaluation.


Definition at line 141 of file sensor_lib.c.

◆ SET_U16_LEN

#define SET_U16_LEN   5

Number of Bytes that needs to be transmitted if 1 U16 value is set via a set-parameter function.


Definition at line 122 of file sensor_lib.c.

◆ SET_U32_LEN

#define SET_U32_LEN   7

Number of Bytes that needs to be transmitted if 1 U32 value is set via a set-parameter function.


Definition at line 127 of file sensor_lib.c.

◆ SET_U8_LEN

#define SET_U8_LEN   4

Number of Bytes that needs to be transmitted if 1 U8 value is set via a set-parameter function.


Definition at line 107 of file sensor_lib.c.

◆ SET_U8_U16_LEN

#define SET_U8_U16_LEN   6

Number of Bytes that needs to be transmitted if 1U8 and 1 U16 value is set via a set-parameter function.


Definition at line 117 of file sensor_lib.c.

◆ SET_U8_U8_LEN

#define SET_U8_U8_LEN   5

Number of Bytes that needs to be transmitted if 2 U8 values are set via a set-parameter function.


Definition at line 112 of file sensor_lib.c.

◆ UART_CHECKSUM_TARGET

#define UART_CHECKSUM_TARGET   256

Definition at line 142 of file sensor_lib.c.

◆ UART_DUMMY_ID

#define UART_DUMMY_ID   0x01

Definition at line 94 of file sensor_lib.c.

Typedef Documentation

◆ ADCDump_Data_t

A structure to store ADC-Dump Data

◆ Interface_t

typedef struct Interface_t Interface_t

◆ Session_Data_t

A structure to store Point Session Data

◆ UART_Msg_t

typedef struct UART_Msg_t UART_Msg_t

◆ UARTMessageState_t

Enumeration Type Documentation

◆ UARTMessageState_t

Enumerator
UART_MESSAGE_STATE_UNKNOWN 
UART_MESSAGE_STATE_IN_TRANSMIT_SIZE_UNKNOWN 
UART_MESSAGE_STATE_IN_TRANSMIT_READ_PAYLOAD 
UART_MESSAGE_STATE_TRANSMIT_COMPLETE 
UART_MESSAGE_STATE_READ_CHECKSUM 
UART_MESSAGE_STATE_VALIDATE_MSG_END 

Definition at line 163 of file sensor_lib.c.

Function Documentation

◆ GetACKFromACKStatus()

static bool GetACKFromACKStatus ( ACK_Status_t ackstatus)
static

Definition at line 956 of file sensor_lib.c.

◆ GetConnectedToCANBus()

static bool GetConnectedToCANBus ( )
static

Definition at line 972 of file sensor_lib.c.

◆ GetCurrentSessionsActiveSessions()

static Sensor_Session_t* GetCurrentSessionsActiveSessions ( uint8_t  index)
static

Definition at line 847 of file sensor_lib.c.

◆ GetCurrentSessionsNumberOfActiveSessions_u8()

static uint8_t GetCurrentSessionsNumberOfActiveSessions_u8 ( )
static

Definition at line 831 of file sensor_lib.c.

◆ GetCurrentStatusInformant_u16()

static uint16_t GetCurrentStatusInformant_u16 ( )
static

Definition at line 892 of file sensor_lib.c.

◆ GetCurrentTarget_u16()

static uint16_t GetCurrentTarget_u16 ( )
static

Definition at line 815 of file sensor_lib.c.

◆ GetInterfaceSensorIdFromSensor()

static uint16_t GetInterfaceSensorIdFromSensor ( Sensor_t sensor)
static

Definition at line 883 of file sensor_lib.c.

◆ GetKnownSensor()

static Sensor_t* GetKnownSensor ( uint8_t  index)
static

Definition at line 874 of file sensor_lib.c.

◆ GetNumberOfSensorsACKIsExpectedFrom()

static uint8_t GetNumberOfSensorsACKIsExpectedFrom ( )
static

Definition at line 783 of file sensor_lib.c.

◆ GetSenderIdFromACKStatus()

static uint16_t GetSenderIdFromACKStatus ( ACK_Status_t ackstatus)
static

Definition at line 924 of file sensor_lib.c.

◆ GetSenderIdFromSensorSession()

static uint16_t GetSenderIdFromSensorSession ( Sensor_Session_t session)
static

Definition at line 856 of file sensor_lib.c.

◆ GetSessionStateFromSensorSession()

static SessionState_t GetSessionStateFromSensorSession ( Sensor_Session_t session)
static

Definition at line 865 of file sensor_lib.c.

◆ GetWaitACKPayload()

static uint8_t* GetWaitACKPayload ( )
static

Definition at line 774 of file sensor_lib.c.

◆ GetWaitForACKFromACKStatus()

static bool GetWaitForACKFromACKStatus ( ACK_Status_t ackstatus)
static

Definition at line 940 of file sensor_lib.c.

◆ PrintKnownInterfaces()

static void PrintKnownInterfaces ( )
static

Definition at line 1092 of file sensor_lib.c.

◆ PrintKnownSensors()

static void PrintKnownSensors ( )
static

Definition at line 1079 of file sensor_lib.c.

◆ SetACKForACKStatus()

static void SetACKForACKStatus ( ACK_Status_t ackstatus,
bool  ack 
)
static

Definition at line 949 of file sensor_lib.c.

◆ SetConnectedToCANBus()

static void SetConnectedToCANBus ( bool  newvalue)
static

Definition at line 965 of file sensor_lib.c.

◆ SetCurrentSessionsNumberOfActiveSessions_u8()

static void SetCurrentSessionsNumberOfActiveSessions_u8 ( uint8_t  newvalue)
static

Definition at line 840 of file sensor_lib.c.

◆ SetCurrentStatusInformant_u16()

static void SetCurrentStatusInformant_u16 ( uint16_t  newvalue)
static

Definition at line 901 of file sensor_lib.c.

◆ SetCurrentTarget_u16()

static void SetCurrentTarget_u16 ( uint16_t  newvalue)
static

Definition at line 824 of file sensor_lib.c.

◆ SetNumberOfKnownSensors()

static void SetNumberOfKnownSensors ( uint8_t  newvalue)
static

Definition at line 808 of file sensor_lib.c.

◆ SetNumberOfSensorsACKIsExpectedFrom()

static void SetNumberOfSensorsACKIsExpectedFrom ( uint8_t  newvalue)
static

Definition at line 792 of file sensor_lib.c.

◆ SetResponsePayloadForACKStatus()

static void SetResponsePayloadForACKStatus ( ACK_Status_t ackstatus,
uint8_t *  payload,
uint16_t  len 
)
static

Definition at line 981 of file sensor_lib.c.

◆ SetSenderIdForACKStatus()

static void SetSenderIdForACKStatus ( ACK_Status_t ackstatus,
uint16_t  senderId 
)
static

Definition at line 917 of file sensor_lib.c.

◆ SetWaitForACKForACKStatus()

static void SetWaitForACKForACKStatus ( ACK_Status_t ackstatus,
bool  waitforack 
)
static

Definition at line 933 of file sensor_lib.c.

◆ WaitForACKNoSend()

static void WaitForACKNoSend ( uint8_t *  payload)
static

Definition at line 1329 of file sensor_lib.c.

Variable Documentation

◆ ADCDUmpEndCallback

void(* ADCDUmpEndCallback) (uint16_t Sender_u16) = NULL
static

Definition at line 726 of file sensor_lib.c.

◆ ADCDumpStartRequestCallback

void(* ADCDumpStartRequestCallback) (uint16_t Sender_u16, uint32_t ADCDumpSize_u32) = NULL
static

Definition at line 730 of file sensor_lib.c.

◆ ConnectedToCANBus_b

bool ConnectedToCANBus_b = false
static

Definition at line 697 of file sensor_lib.c.

◆ ConnectedToCUART_b

bool ConnectedToCUART_b = false
static

Definition at line 699 of file sensor_lib.c.

◆ ConnectedToUSB_b

bool ConnectedToUSB_b = false
static

Definition at line 701 of file sensor_lib.c.

◆ CurrentACKStatus

ACK_Status_t CurrentACKStatus[MAX_NUMBER_OF_SENSORS_ON_BUS] = {0}
static

Definition at line 714 of file sensor_lib.c.

◆ CurrentADCSessions

ADCDump_Data_t CurrentADCSessions = {0}

Definition at line 719 of file sensor_lib.c.

◆ CurrentSessions

Session_Data_t CurrentSessions = {0}

Definition at line 717 of file sensor_lib.c.

◆ CurrentStatusInformant_u16

uint16_t CurrentStatusInformant_u16 = 0
static

Definition at line 695 of file sensor_lib.c.

◆ CurrentTarget_u16

uint16_t CurrentTarget_u16 = MULTICAST_ID
static

Definition at line 693 of file sensor_lib.c.

◆ CurrentUARTMsg_t

UART_Msg_t CurrentUARTMsg_t[MAX_NUMBER_OF_SENSORS_ON_BUS] = {0}
static

Definition at line 745 of file sensor_lib.c.

◆ KnownInterfaces_tp

Interface_t KnownInterfaces_tp[MAX_NUMBER_OF_SENSORS_ON_BUS] = {0}
static

Definition at line 747 of file sensor_lib.c.

◆ KnownSensors

Sensor_t KnownSensors[MAX_NUMBER_OF_SENSORS_ON_BUS] = {0}
static

Definition at line 703 of file sensor_lib.c.

◆ LogMsgCallback

void(* LogMsgCallback) (uint16_t Sender_u16, uint8_t *ReceivedPayload_pu8) = NULL
static

Definition at line 733 of file sensor_lib.c.

◆ mutex_connectedtocanbus

pthread_mutex_t mutex_connectedtocanbus = PTHREAD_MUTEX_INITIALIZER
static

Definition at line 760 of file sensor_lib.c.

◆ mutex_currentackstatus

pthread_mutex_t mutex_currentackstatus = PTHREAD_MUTEX_INITIALIZER
static

Definition at line 756 of file sensor_lib.c.

◆ mutex_currentsessions

pthread_mutex_t mutex_currentsessions = PTHREAD_MUTEX_INITIALIZER
static

Definition at line 754 of file sensor_lib.c.

◆ mutex_currentstatusinformant

pthread_mutex_t mutex_currentstatusinformant = PTHREAD_MUTEX_INITIALIZER
static

Definition at line 750 of file sensor_lib.c.

◆ mutex_currenttarget

pthread_mutex_t mutex_currenttarget = PTHREAD_MUTEX_INITIALIZER
static

Definition at line 755 of file sensor_lib.c.

◆ mutex_getdatafromsensor

pthread_mutex_t mutex_getdatafromsensor = PTHREAD_MUTEX_INITIALIZER
static

Definition at line 753 of file sensor_lib.c.

◆ mutex_knownsensor

pthread_mutex_t mutex_knownsensor = PTHREAD_MUTEX_INITIALIZER
static

Definition at line 752 of file sensor_lib.c.

◆ mutex_knownsensors

pthread_mutex_t mutex_knownsensors = PTHREAD_MUTEX_INITIALIZER
static

Definition at line 751 of file sensor_lib.c.

◆ mutex_numberofknownsensors

pthread_mutex_t mutex_numberofknownsensors = PTHREAD_MUTEX_INITIALIZER
static

Definition at line 757 of file sensor_lib.c.

◆ mutex_numberofsensorsackisexpectedfrom

pthread_mutex_t mutex_numberofsensorsackisexpectedfrom = PTHREAD_MUTEX_INITIALIZER
static

Definition at line 758 of file sensor_lib.c.

◆ mutex_waitackpayload

pthread_mutex_t mutex_waitackpayload = PTHREAD_MUTEX_INITIALIZER
static

Definition at line 759 of file sensor_lib.c.

◆ NumberOfKnownInterfaces_u8

uint8_t NumberOfKnownInterfaces_u8 = 0

Definition at line 746 of file sensor_lib.c.

◆ NumberOfKnownSensors_u8

uint8_t NumberOfKnownSensors_u8 = 0
static

Definition at line 705 of file sensor_lib.c.

◆ NumberOfSensorsACKIsExpectedFrom_u8

uint8_t NumberOfSensorsACKIsExpectedFrom_u8 = 0
static

Definition at line 712 of file sensor_lib.c.

◆ NumberOfSensorsASessionStartIsExpectedFrom_u8

uint8_t NumberOfSensorsASessionStartIsExpectedFrom_u8 = 0
static

Definition at line 706 of file sensor_lib.c.

◆ RdyCallback

void(* RdyCallback) (uint16_t Sender_u16) = NULL
static

Definition at line 728 of file sensor_lib.c.

◆ SemaphoresInit_b

bool SemaphoresInit_b = false
static

Definition at line 743 of file sensor_lib.c.

◆ SessionEndCallback

void(* SessionEndCallback) (uint16_t Sender_u16) = NULL
static

Definition at line 724 of file sensor_lib.c.

◆ SessionStartCallback

void(* SessionStartCallback) (uint16_t Sender_u16) = NULL
static

Definition at line 722 of file sensor_lib.c.

◆ timeoutID

pthread_t timeoutID
static

Definition at line 748 of file sensor_lib.c.

◆ timeoutmSeconds

int timeoutmSeconds = TIMEOUT_M_SECONDS
static

Definition at line 749 of file sensor_lib.c.

◆ UartPayload_pu8

uint8_t UartPayload_pu8[UART_MAX_FRAME_LEN] = {0}
static

Definition at line 744 of file sensor_lib.c.

◆ wait_ack_payload_pu8

uint8_t wait_ack_payload_pu8[CAN_MAX_FRAME_LEN] = {0}
static

Definition at line 710 of file sensor_lib.c.

◆ wait_ack_sem

sem_t wait_ack_sem
static

Definition at line 708 of file sensor_lib.c.

◆ wait_adc_session_end_sem

sem_t wait_adc_session_end_sem
static

Definition at line 739 of file sensor_lib.c.

◆ wait_ready_sem

sem_t wait_ready_sem
static

Definition at line 741 of file sensor_lib.c.

◆ wait_session_end_sem

sem_t wait_session_end_sem
static

Definition at line 738 of file sensor_lib.c.

◆ wait_session_start_sem

sem_t wait_session_start_sem
static

Definition at line 736 of file sensor_lib.c.



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