sbgECom.c
Go to the documentation of this file.
1 #include "sbgECom.h"
2 #include "sbgEComVersion.h"
5 
6 //----------------------------------------------------------------------//
7 //- Private methods declarations -//
8 //----------------------------------------------------------------------//
9 
10 //----------------------------------------------------------------------//
11 //- Public methods declarations -//
12 //----------------------------------------------------------------------//
13 
21 {
22  SbgErrorCode errorCode = SBG_NO_ERROR;
23 
24  //
25  // Check input parameters
26  //
27  if ( (pInterface) && (pHandle) )
28  {
29  //
30  // Initialize the sbgECom handle
31  //
32  pHandle->pReceiveCallback = NULL;
33  pHandle->pReceiveLogCallback = NULL;
34  pHandle->pUserArg = NULL;
35 
36  //
37  // Initialize the default number of trials and time out
38  //
39  pHandle->numTrials = 3;
41 
42  //
43  // Initialize the protocol
44  //
45  errorCode = sbgEComProtocolInit(&pHandle->protocolHandle, pInterface);
46  }
47  else
48  {
49  errorCode = SBG_NULL_POINTER;
50  }
51 
52  return errorCode;
53 }
54 
61 {
62  SbgErrorCode errorCode = SBG_NO_ERROR;
63 
64  //
65  // Test that we have a valid protocol handle
66  //
67  if (pHandle)
68  {
69  //
70  // Close the protocol
71  //
72  errorCode = sbgEComProtocolClose(&pHandle->protocolHandle);
73  }
74  else
75  {
76  errorCode = SBG_NULL_POINTER;
77  }
78 
79  return errorCode;
80 }
81 
88 {
89  SbgErrorCode errorCode = SBG_NO_ERROR;
90  SbgBinaryLogData logData;
91  uint8 receivedMsg;
92  uint8 receivedMsgClass;
93  uint16 receivedCmd;
94  size_t payloadSize;
95  uint8 payloadData[SBG_ECOM_MAX_PAYLOAD_SIZE];
96 
97  //
98  // Check input arguments
99  //
100  SBG_ASSERT(pHandle);
101 
102  //
103  // Try to read a received frame
104  //
105  errorCode = sbgEComProtocolReceive(&pHandle->protocolHandle, &receivedMsgClass, &receivedMsg, payloadData, &payloadSize, sizeof(payloadData));
106 
107  //
108  // Test if we have received a valid frame
109  //
110  if (errorCode == SBG_NO_ERROR)
111  {
112  //
113  // Test if the received frame is a binary log
114  //
115  if (sbgEComMsgClassIsALog((SbgEComClass)receivedMsgClass))
116  {
117  //
118  // The received frame is a binary log one
119  //
120  errorCode = sbgEComBinaryLogParse((SbgEComClass)receivedMsgClass, (SbgEComMsgId)receivedMsg, payloadData, payloadSize, &logData);
121 
122  //
123  // Test if the incoming log has been parsed successfully
124  //
125  if (errorCode == SBG_NO_ERROR)
126  {
127  //
128  // Test if we have a valid callback to handle received logs
129  //
130  if (pHandle->pReceiveCallback)
131  {
132  //
133  // Call the binary log callback using the deprecated method
134  //
135  receivedCmd = SBG_ECOM_BUILD_ID(receivedMsgClass, receivedMsg);
136  errorCode = pHandle->pReceiveCallback(pHandle, (SbgEComCmdId)receivedCmd, &logData, pHandle->pUserArg);
137  }
138  else if (pHandle->pReceiveLogCallback)
139  {
140  //
141  // Call the binary log callback using the new method
142  //
143  errorCode = pHandle->pReceiveLogCallback(pHandle, (SbgEComClass)receivedMsgClass, receivedMsg, &logData, pHandle->pUserArg);
144  }
145  }
146  else
147  {
148  //
149  // Call the on error callback
150  //
151  }
152  }
153  else
154  {
155  //
156  // We have received a command, it shouldn't happen
157  //
158  }
159  }
160  else if (errorCode != SBG_NOT_READY)
161  {
162  //
163  // We have received an invalid frame
164  //
165  SBG_LOG_WARNING(errorCode, "Invalid frame received");
166  }
167 
168  return errorCode;
169 }
170 
177 {
178  SbgErrorCode errorCode = SBG_NO_ERROR;
179 
180  //
181  // Check input arguments
182  //
183  SBG_ASSERT(pHandle);
184 
185  //
186  // Try to read all received frames, we thus loop until we get an SBG_NOT_READY error
187  //
188  do
189  {
190  //
191  // Try to read and parse one frame
192  //
193  errorCode = sbgEComHandleOneLog(pHandle);
194  } while (errorCode != SBG_NOT_READY);
195 
196  return errorCode;
197 }
198 
206 SbgErrorCode sbgEComSetReceiveCallback(SbgEComHandle *pHandle, SbgEComReceiveFunc pReceiveCallback, void *pUserArg)
207 {
208  SbgErrorCode errorCode = SBG_NO_ERROR;
209 
210  //
211  // Test that we have a valid protocol handle
212  //
213  if (pHandle)
214  {
215  //
216  // Define the callback and the user argument
217  //
218  pHandle->pReceiveCallback = pReceiveCallback;
219  pHandle->pUserArg = pUserArg;
220  }
221  else
222  {
223  errorCode = SBG_NULL_POINTER;
224  }
225 
226  return errorCode;
227 }
228 
236 SbgErrorCode sbgEComSetReceiveLogCallback(SbgEComHandle *pHandle, SbgEComReceiveLogFunc pReceiveLogCallback, void *pUserArg)
237 {
238  SbgErrorCode errorCode = SBG_NO_ERROR;
239 
240  //
241  // Test that we have a valid protocol handle
242  //
243  if (pHandle)
244  {
245  //
246  // Define the callback and the user argument
247  //
248  pHandle->pReceiveLogCallback = pReceiveLogCallback;
249  pHandle->pUserArg = pUserArg;
250  }
251  else
252  {
253  errorCode = SBG_NULL_POINTER;
254  }
255 
256  return errorCode;
257 }
258 
265 void sbgEComSetCmdTrialsAndTimeOut(SbgEComHandle *pHandle, uint32 numTrials, uint32 cmdDefaultTimeOut)
266 {
267  //
268  // Check input arguments
269  //
270  SBG_ASSERT(pHandle);
271  SBG_ASSERT(numTrials > 0);
272  SBG_ASSERT(cmdDefaultTimeOut > 0);
273 
274  //
275  // Define the new settings
276  //
277  pHandle->numTrials = numTrials;
278  pHandle->cmdDefaultTimeOut = cmdDefaultTimeOut;
279 }
280 
287 {
288  return SBG_E_COM_VERSION;
289 }
290 
295 const char *sbgEComGetVersionAsString(void)
296 {
297  return SBG_E_COM_VERSION_STR;
298 }
299 
305 void sbgEComErrorToString(SbgErrorCode errorCode, char errorMsg[256])
306 {
307  if (errorMsg)
308  {
309  //
310  // For each error code, copy the error msg
311  //
312  switch (errorCode)
313  {
314  case SBG_NO_ERROR:
315  strcpy(errorMsg, "SBG_NO_ERROR: No error.");
316  break;
317  case SBG_ERROR:
318  strcpy(errorMsg, "SBG_ERROR: Generic error.");
319  break;
320  case SBG_NULL_POINTER:
321  strcpy(errorMsg, "SBG_NULL_POINTER: A pointer is null.");
322  break;
323  case SBG_INVALID_CRC:
324  strcpy(errorMsg, "SBG_INVALID_CRC: The received frame has an invalid CRC.");
325  break;
326  case SBG_INVALID_FRAME:
327  strcpy(errorMsg, "SBG_INVALID_FRAME: The received frame is invalid.");
328  break;
329  case SBG_TIME_OUT:
330  strcpy(errorMsg, "SBG_TIME_OUT: We have a time out during frame reception.");
331  break;
332  case SBG_WRITE_ERROR:
333  strcpy(errorMsg, "SBG_WRITE_ERROR: All bytes hasn't been written.");
334  break;
335  case SBG_READ_ERROR:
336  strcpy(errorMsg, "SBG_READ_ERROR: All bytes hasn't been read.");
337  break;
338  case SBG_BUFFER_OVERFLOW:
339  strcpy(errorMsg, "SBG_BUFFER_OVERFLOW: A buffer is too small to contain so much data.");
340  break;
342  strcpy(errorMsg, "SBG_INVALID_PARAMETER: An invalid parameter has been founded.");
343  break;
344  case SBG_NOT_READY:
345  strcpy(errorMsg, "SBG_NOT_READY: A device isn't ready (Rx isn't ready for example).");
346  break;
347  case SBG_MALLOC_FAILED:
348  strcpy(errorMsg, "SBG_MALLOC_FAILED: Failed to allocate a buffer.");
349  break;
351  strcpy(errorMsg, "SGB_CALIB_MAG_NOT_ENOUGH_POINTS: Not enough points were available to perform magnetometers calibration.");
352  break;
354  strcpy(errorMsg, "SBG_CALIB_MAG_INVALID_TAKE: The calibration procedure could not be properly executed due to insufficient precision.");
355  break;
357  strcpy(errorMsg, "SBG_CALIB_MAG_SATURATION: Saturation were detected when attempt to calibrate magnetos.");
358  break;
360  strcpy(errorMsg, "SBG_CALIB_MAG_POINTS_NOT_IN_A_PLANE: 2D calibration procedure could not be performed.");
361  break;
363  strcpy(errorMsg, "SBG_DEVICE_NOT_FOUND: A device couldn't be founded or opened.");
364  break;
366  strcpy(errorMsg, "SBG_OPERATION_CANCELLED: An operation has been cancelled by a user.");
367  break;
369  strcpy(errorMsg, "SBG_NOT_CONTINUOUS_FRAME: We have received a frame that isn't a continuous one.");
370  break;
372  strcpy(errorMsg, "SBG_INCOMPATIBLE_HARDWARE: Hence valid, the configuration cannot be executed because of incompatible hardware.");
373  break;
374  default:
375  sprintf(errorMsg, "Undefined error code: %u", errorCode);
376  break;
377  }
378  }
379 }
Contains main sbgECom methods.
This file groups all common definitions required by all commands.
unsigned int uint32
Definition: sbgTypes.h:58
SbgErrorCode sbgEComHandleOneLog(SbgEComHandle *pHandle)
Definition: sbgECom.c:87
Used to read/write data from/to a memory buffer stream.
SbgErrorCode(* SbgEComReceiveLogFunc)(SbgEComHandle *pHandle, SbgEComClass msgClass, SbgEComMsgId msg, const SbgBinaryLogData *pLogData, void *pUserArg)
Definition: sbgECom.h:71
SbgEComReceiveFunc pReceiveCallback
Definition: sbgECom.h:83
SbgEComProtocol protocolHandle
Definition: sbgECom.h:82
SbgErrorCode sbgEComProtocolInit(SbgEComProtocol *pHandle, SbgInterface *pInterface)
uint16 SbgEComCmdId
Definition: sbgEComIds.h:272
uint32 sbgEComGetVersion(void)
Definition: sbgECom.c:286
SbgErrorCode sbgEComHandle(SbgEComHandle *pHandle)
Definition: sbgECom.c:176
#define SBG_ECOM_BUILD_ID(classId, logId)
Definition: sbgEComIds.h:37
SbgErrorCode sbgEComProtocolReceive(SbgEComProtocol *pHandle, uint8 *pMsgClass, uint8 *pMsg, void *pData, size_t *pSize, size_t maxSize)
uint32 numTrials
Definition: sbgECom.h:86
#define NULL
Definition: sbgDefines.h:43
SbgErrorCode(* SbgEComReceiveFunc)(SbgEComHandle *pHandle, SbgEComCmdId logCmd, const SbgBinaryLogData *pLogData, void *pUserArg)
Definition: sbgECom.h:60
SbgEComReceiveLogFunc pReceiveLogCallback
Definition: sbgECom.h:84
void sbgEComSetCmdTrialsAndTimeOut(SbgEComHandle *pHandle, uint32 numTrials, uint32 cmdDefaultTimeOut)
Definition: sbgECom.c:265
uint32 cmdDefaultTimeOut
Definition: sbgECom.h:87
const char * sbgEComGetVersionAsString(void)
Definition: sbgECom.c:295
#define SBG_ECOM_DEFAULT_CMD_TIME_OUT
SbgErrorCode sbgEComSetReceiveLogCallback(SbgEComHandle *pHandle, SbgEComReceiveLogFunc pReceiveLogCallback, void *pUserArg)
Definition: sbgECom.c:236
#define SBG_LOG_WARNING(errorCode, format,...)
Definition: sbgDebug.h:74
#define SBG_E_COM_VERSION
void * pUserArg
Definition: sbgECom.h:85
uint8 SbgEComMsgId
Definition: sbgEComIds.h:278
SbgErrorCode sbgEComSetReceiveCallback(SbgEComHandle *pHandle, SbgEComReceiveFunc pReceiveCallback, void *pUserArg)
Definition: sbgECom.c:206
unsigned char uint8
Definition: sbgTypes.h:56
#define SBG_ASSERT(expression)
Definition: sbgDebug.h:52
enum _SbgEComClass SbgEComClass
SBG_INLINE bool sbgEComMsgClassIsALog(SbgEComClass msgClass)
Definition: sbgEComIds.h:289
void sbgEComErrorToString(SbgErrorCode errorCode, char errorMsg[256])
Definition: sbgECom.c:305
SbgErrorCode sbgEComProtocolClose(SbgEComProtocol *pHandle)
unsigned short uint16
Definition: sbgTypes.h:57
Header file that contains all versions related information such as change log.
#define SBG_E_COM_VERSION_STR
SbgErrorCode sbgEComInit(SbgEComHandle *pHandle, SbgInterface *pInterface)
Definition: sbgECom.c:20
#define SBG_ECOM_MAX_PAYLOAD_SIZE
enum _SbgErrorCode SbgErrorCode
SbgErrorCode sbgEComClose(SbgEComHandle *pHandle)
Definition: sbgECom.c:60
SbgErrorCode sbgEComBinaryLogParse(SbgEComClass msgClass, SbgEComMsgId msg, const void *pPayload, size_t payloadSize, SbgBinaryLogData *pOutputData)


sbg_driver
Author(s):
autogenerated on Sun Jan 27 2019 03:42:20