xsmessage.h
Go to the documentation of this file.
1 
2 // Copyright (c) 2003-2021 Xsens Technologies B.V. or subsidiaries worldwide.
3 // All rights reserved.
4 //
5 // Redistribution and use in source and binary forms, with or without modification,
6 // are permitted provided that the following conditions are met:
7 //
8 // 1. Redistributions of source code must retain the above copyright notice,
9 // this list of conditions, and the following disclaimer.
10 //
11 // 2. Redistributions in binary form must reproduce the above copyright notice,
12 // this list of conditions, and the following disclaimer in the documentation
13 // and/or other materials provided with the distribution.
14 //
15 // 3. Neither the names of the copyright holders nor the names of their contributors
16 // may be used to endorse or promote products derived from this software without
17 // specific prior written permission.
18 //
19 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY
20 // EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
21 // MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL
22 // THE COPYRIGHT HOLDERS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
23 // SPECIAL, EXEMPLARY OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT
24 // OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
25 // HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY OR
26 // TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
27 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.THE LAWS OF THE NETHERLANDS
28 // SHALL BE EXCLUSIVELY APPLICABLE AND ANY DISPUTES SHALL BE FINALLY SETTLED UNDER THE RULES
29 // OF ARBITRATION OF THE INTERNATIONAL CHAMBER OF COMMERCE IN THE HAGUE BY ONE OR MORE
30 // ARBITRATORS APPOINTED IN ACCORDANCE WITH SAID RULES.
31 //
32 
33 
34 // Copyright (c) 2003-2021 Xsens Technologies B.V. or subsidiaries worldwide.
35 // All rights reserved.
36 //
37 // Redistribution and use in source and binary forms, with or without modification,
38 // are permitted provided that the following conditions are met:
39 //
40 // 1. Redistributions of source code must retain the above copyright notice,
41 // this list of conditions, and the following disclaimer.
42 //
43 // 2. Redistributions in binary form must reproduce the above copyright notice,
44 // this list of conditions, and the following disclaimer in the documentation
45 // and/or other materials provided with the distribution.
46 //
47 // 3. Neither the names of the copyright holders nor the names of their contributors
48 // may be used to endorse or promote products derived from this software without
49 // specific prior written permission.
50 //
51 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY
52 // EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
53 // MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL
54 // THE COPYRIGHT HOLDERS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
55 // SPECIAL, EXEMPLARY OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT
56 // OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
57 // HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY OR
58 // TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
59 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.THE LAWS OF THE NETHERLANDS
60 // SHALL BE EXCLUSIVELY APPLICABLE AND ANY DISPUTES SHALL BE FINALLY SETTLED UNDER THE RULES
61 // OF ARBITRATION OF THE INTERNATIONAL CHAMBER OF COMMERCE IN THE HAGUE BY ONE OR MORE
62 // ARBITRATORS APPOINTED IN ACCORDANCE WITH SAID RULES.
63 //
64 
65 #ifndef XSMESSAGE_H
66 #define XSMESSAGE_H
67 
68 #include "xstypesconfig.h"
69 #include "pstdint.h"
70 #include "xsbytearray.h"
71 #include "xsdataidentifier.h"
72 #include "xsxbusmessageid.h"
73 #include "xsstring.h"
74 #include "xsresultvalue.h"
75 #include "xsbusid.h"
76 
77 struct XsMessage;
78 struct XsMessageHeader;
79 
80 #ifdef __cplusplus
81 extern "C" {
82 #endif
83 #ifndef __cplusplus
84 #define XSMESSAGE_INITIALIZER { XSBYTEARRAY_INITIALIZER, 1, 0 }
85 typedef struct XsMessage XsMessage;
87 #endif
88 
92 XSTYPES_DLL_API void XsMessage_assign(XsMessage* thisPtr, XsSize dataSize);
93 XSTYPES_DLL_API void XsMessage_load(XsMessage* thisPtr, XsSize msgSize, unsigned char const* src);
95 XSTYPES_DLL_API void XsMessage_copy(XsMessage* copy, XsMessage const* src);
98 XSTYPES_DLL_API const uint8_t* XsMessage_constData(XsMessage const* thisPtr, XsSize offset);
99 XSTYPES_DLL_API const uint8_t* XsMessage_getMessageStart(XsMessage const* thisPtr);
101 XSTYPES_DLL_API uint8_t XsMessage_getDataByte(XsMessage const* thisPtr, XsSize offset);
102 XSTYPES_DLL_API uint16_t XsMessage_getDataShort(XsMessage const* thisPtr, XsSize offset);
104 XSTYPES_DLL_API uint64_t XsMessage_getDataLongLong(XsMessage const* thisPtr, XsSize offset);
105 XSTYPES_DLL_API float XsMessage_getDataFloat(XsMessage const* thisPtr, XsSize offset);
106 XSTYPES_DLL_API double XsMessage_getDataDouble(XsMessage const* thisPtr, XsSize offset);
107 XSTYPES_DLL_API double XsMessage_getDataF1220(XsMessage const* thisPtr, XsSize offset);
108 XSTYPES_DLL_API double XsMessage_getDataFP1632(XsMessage const* thisPtr, XsSize offset);
109 XSTYPES_DLL_API const uint8_t* XsMessage_getDataBuffer(XsMessage const* thisPtr, XsSize offset);
110 XSTYPES_DLL_API void XsMessage_setDataByte(XsMessage* thisPtr, uint8_t value, XsSize offset);
111 XSTYPES_DLL_API void XsMessage_setDataShort(XsMessage* thisPtr, uint16_t value, XsSize offset);
112 XSTYPES_DLL_API void XsMessage_setDataLong(XsMessage* thisPtr, uint32_t value, XsSize offset);
113 XSTYPES_DLL_API void XsMessage_setDataLongLong(XsMessage* thisPtr, uint64_t value, XsSize offset);
114 XSTYPES_DLL_API void XsMessage_setDataFloat(XsMessage* thisPtr, float value, XsSize offset);
115 XSTYPES_DLL_API void XsMessage_setDataDouble(XsMessage* thisPtr, double value, XsSize offset);
116 XSTYPES_DLL_API void XsMessage_setDataF1220(XsMessage* thisPtr, double value, XsSize offset);
117 XSTYPES_DLL_API void XsMessage_setDataFP1632(XsMessage* thisPtr, double value, XsSize offset);
118 XSTYPES_DLL_API void XsMessage_setDataBuffer(XsMessage* thisPtr, const uint8_t* buffer, XsSize size, XsSize offset);
119 XSTYPES_DLL_API uint8_t XsMessage_computeChecksum(XsMessage const* thisPtr);
124 XSTYPES_DLL_API int XsMessage_empty(XsMessage const* thisPtr);
125 XSTYPES_DLL_API void XsMessage_resizeData(XsMessage* thisPtr, XsSize newSize);
126 XSTYPES_DLL_API void XsMessage_setBusId(XsMessage* thisPtr, uint8_t busId);
128 XSTYPES_DLL_API void XsMessage_insertData(XsMessage* thisPtr, XsSize count, XsSize offset);
129 XSTYPES_DLL_API void XsMessage_deleteData(XsMessage* thisPtr, XsSize count, XsSize offset);
131 XSTYPES_DLL_API void XsMessage_getDataFPValuesById(XsMessage const* thisPtr, XsDataIdentifier dataIdentifier, double* dest, XsSize offset, XsSize numValues);
132 XSTYPES_DLL_API void XsMessage_setDataFPValuesById(XsMessage* thisPtr, XsDataIdentifier dataIdentifier, double const* data, XsSize offset, XsSize numValues);
133 XSTYPES_DLL_API void XsMessage_getDataRealValuesById(XsMessage const* thisPtr, XsDataIdentifier dataIdentifier, XsReal* dest, XsSize offset, XsSize numValues);
134 XSTYPES_DLL_API void XsMessage_setDataRealValuesById(XsMessage* thisPtr, XsDataIdentifier dataIdentifier, XsReal const* data, XsSize offset, XsSize numValues);
135 XSTYPES_DLL_API int XsMessage_compare(XsMessage const* a, XsMessage const* b);
136 XSTYPES_DLL_API void XsMessage_toHexString(XsMessage const* thisPtr, XsSize maxBytes, XsString* resultValue);
137 XSTYPES_DLL_API void XsMessage_getEndianCorrectData(XsMessage const* thisPtr, void* value, XsSize size, XsSize offset);
138 XSTYPES_DLL_API void XsMessage_setEndianCorrectData(XsMessage* thisPtr, void const* value, XsSize size, XsSize offset);
139 
140 #ifdef __cplusplus
141 } // extern "C"
142 #endif
143 
144 #define XS_PREAMBLE 0xFA
145 #define XS_EXTLENCODE 0xFF
146 
147 #define XS_LEN_MSGHEADER 4
148 #define XS_LEN_MSGEXTHEADER 6
149 #define XS_LEN_MSGHEADERCS 5
150 #define XS_LEN_MSGEXTHEADERCS 7
151 #define XS_LEN_CHECKSUM 1
152 #define XS_LEN_UNSIGSHORT 2
153 #define XS_LEN_UNSIGINT 4
154 #define XS_LEN_FLOAT 4
155 
156 // Maximum message/data length
157 #define XS_MAXDATALEN (8192-XS_LEN_MSGEXTHEADERCS)
158 #define XS_MAXSHORTDATALEN 254
159 #define XS_MAXMSGLEN (XS_MAXDATALEN+XS_LEN_MSGEXTHEADERCS)
160 #define XS_MAXSHORTMSGLEN (XS_MAXSHORTDATALEN+XS_LEN_MSGHEADERCS)
161 #define XS_MAXGARBAGE (XS_MAXMSGLEN+1)
162 
164 // different alignment commands for gcc / MSVS, the structure needs to be 1-byte aligned.
170 {
171  uint8_t m_preamble;
172  uint8_t m_busId;
173  uint8_t m_messageId;
174  uint8_t m_length;
175 
178  {
181  {
184  {
185  uint8_t m_high;
186  uint8_t m_low;
187  } m_length;
188  uint8_t m_data[1];
189  } m_extended;
190  uint8_t m_data[1];
191  } m_datlen;
192 #ifdef SWIG
193 };
194 #else
196 #endif
197 
199 
202 struct XsMessage
203 {
204 #ifdef __cplusplus
205 
212  inline explicit XsMessage(XsXbusMessageId msgId = XMID_InvalidMessage, XsSize dataLength = 0)
214  , m_checksum(0)
215  {
216  XsMessage_constructSized(this, dataLength);
217  XsMessage_setMessageId(this, msgId);
218  }
219 
229  inline XsMessage(const uint8_t* source, XsSize size)
231  , m_checksum(0)
232  {
233  XsMessage_load(this, size, source);
234  }
235 
243  inline XsMessage(const XsString& source, bool computeChecksum = true)
245  , m_checksum(0)
246  {
247  XsSize szm = source.size() / 2;
248  XsSize szmcc = szm + (computeChecksum ? 1 : 0);
249  XsByteArray tmp(szmcc);
250  auto tonibble = [](char a) -> uint8_t
251  {
252  if (a >= '0' && a <= '9')
253  return (uint8_t)(a - '0');
254  if (a >= 'a' && a <= 'f')
255  return (uint8_t)(10 + a - 'a');
256  if (a >= 'A' && a <= 'F')
257  return (uint8_t)(10 + a - 'A');
258  return 0;
259  };
260  for (XsSize i = 0; i < szm; ++i)
261  tmp[i] = tonibble(source[i * 2]) * (uint8_t)16 + tonibble(source[i * 2 + 1]); //lint !e734
262  XsMessage_load(this, tmp.size(), tmp.data());
263  if (computeChecksum)
265  }
266 
268  inline XsMessage(const XsMessage& src)
269  : m_message(src.m_message)
271  , m_checksum(0)
272  {
273  updateChecksumPtr();
274  }
275 
277  inline ~XsMessage()
278  {
279  XsMessage_destruct(this);
280  }
281 
283  inline void clear(void)
284  {
285  XsMessage_destruct(this);
286  }
287 
292  inline bool empty(void) const
293  {
294  return 0 != XsMessage_empty(this);
295  }
296 
298  inline uint8_t getBusId(void) const
299  {
300  const XsMessageHeader* hdr = XsMessage_getConstHeader(this);
301  if (!hdr)
302  return 0;
303  return hdr->m_busId;
304  }
305 
308  inline const uint8_t* getDataBuffer(XsSize offset = 0) const
309  {
310  return XsMessage_constData(this, offset);
311  }
312 
315  inline uint8_t getDataByte(XsSize offset = 0) const
316  {
317  return XsMessage_getDataByte(this, offset);
318  }
319 
322  inline double getDataDouble(XsSize offset = 0) const
323  {
324  return XsMessage_getDataDouble(this, offset);
325  }
326 
329  inline float getDataFloat(XsSize offset = 0) const
330  {
331  return XsMessage_getDataFloat(this, offset);
332  }
333 
336  inline double getDataF1220(XsSize offset = 0) const
337  {
338  return XsMessage_getDataF1220(this, offset);
339  }
340 
343  inline double getDataFP1632(XsSize offset = 0) const
344  {
345  return XsMessage_getDataFP1632(this, offset);
346  }
347 
350  inline uint32_t getDataLong(XsSize offset = 0) const
351  {
352  return XsMessage_getDataLong(this, offset);
353  }
354 
357  inline uint64_t getDataLongLong(XsSize offset = 0) const
358  {
359  return XsMessage_getDataLongLong(this, offset);
360  }
361 
364  inline uint16_t getDataShort(XsSize offset = 0) const
365  {
366  return XsMessage_getDataShort(this, offset);
367  }
368 
371  inline XsSize getDataSize(void) const
372  {
373  return XsMessage_dataSize(this);
374  }
375 
377  inline XsXbusMessageId getMessageId(void) const
378  {
379  const XsMessageHeader* hdr = XsMessage_getConstHeader(this);
380  if (!hdr)
381  return XMID_InvalidMessage;
382  return (XsXbusMessageId) hdr->m_messageId;
383  }
384 
386  inline XsResultValue toResultValue(void) const
387  {
388  const XsMessageHeader* hdr = XsMessage_getConstHeader(this);
389  if (!hdr)
390  return XRV_NULLPTR;
391  if (hdr->m_messageId == 0 && hdr->m_busId == XS_BID_MASTER)
392  return XRV_TIMEOUTNODATA; // we assume that an empty message indicates a timeout
393  if ((XsXbusMessageId) hdr->m_messageId != XMID_Error)
394  return XRV_OK;
395  return (XsResultValue) getDataByte();
396  }
397 
400  inline const uint8_t* getMessageStart(void) const
401  {
402  return XsMessage_getMessageStart(this);
403  }
404 
407  inline XsSize getTotalMessageSize(void) const
408  {
409  return XsMessage_getTotalMessageSize(this);
410  }
411 
414  inline bool isChecksumOk(void) const
415  {
416  return 0 != XsMessage_isChecksumOk(this);
417  }
418 
426  inline bool loadFromString(const uint8_t* src, XsSize msgSize)
427  {
429  XsMessage_load(this, msgSize, src);
430  return isChecksumOk();
431  }
432 
435  inline void recomputeChecksum(void)
436  {
438  }
439 
442  inline void resizeData(XsSize newSize)
443  {
444  XsMessage_resizeData(this, newSize);
445  }
446 
449  inline void setBusId(uint8_t busId)
450  {
451  XsMessage_setBusId(this, busId);
452  }
453 
456  inline void setBusId(int busId)
457  {
458  XsMessage_setBusId(this, (uint8_t) busId);
459  }
460 
463  inline void setDataBuffer(const uint8_t* buffer, XsSize size, XsSize offset = 0)
464  {
465  XsMessage_setDataBuffer(this, buffer, size, offset);
466  }
467 
470  inline void setDataByte(const uint8_t value, XsSize offset = 0)
471  {
472  XsMessage_setDataByte(this, value, offset);
473  }
474 
477  inline void setDataDouble(const double value, XsSize offset = 0)
478  {
479  XsMessage_setDataDouble(this, value, offset);
480  }
481 
484  inline void setDataFloat(const float value, XsSize offset = 0)
485  {
486  XsMessage_setDataFloat(this, value, offset);
487  }
488 
491  inline void setDataF1220(const double value, XsSize offset = 0)
492  {
493  XsMessage_setDataF1220(this, value, offset);
494  }
495 
498  inline void setDataFP1632(const double value, XsSize offset = 0)
499  {
500  XsMessage_setDataFP1632(this, value, offset);
501  }
502 
505  inline void setDataLong(const uint32_t value, XsSize offset = 0)
506  {
507  XsMessage_setDataLong(this, value, offset);
508  }
509 
512  inline void setDataLongLong(const uint64_t value, XsSize offset = 0)
513  {
514  XsMessage_setDataLongLong(this, value, offset);
515  }
516 
519  inline void setDataShort(const uint16_t value, XsSize offset = 0)
520  {
521  XsMessage_setDataShort(this, value, offset);
522  }
523 
526  inline void setMessageId(const XsXbusMessageId msgId)
527  {
528  XsMessage_setMessageId(this, msgId);
529  }
530 
532  inline XsMessage& operator = (const XsMessage& src)
533  {
534  if (this != &src)
535  XsMessage_copy(this, &src);
536  return *this;
537  }
538 
540  inline void deleteData(XsSize count, XsSize offset = 0)
541  {
542  XsMessage_deleteData(this, count, offset);
543  }
544 
546  inline void insertData(XsSize count, XsSize offset = 0)
547  {
548  XsMessage_insertData(this, count, offset);
549  }
550 
552  inline static uint8_t getFPValueSize(XsDataIdentifier id)
553  {
554  return XsMessage_getFPValueSize(id);
555  }
556 
558  inline void getDataFPValue(XsDataIdentifier dataIdentifier, double* dest, XsSize offset = 0, XsSize numValues = 1) const
559  {
560  XsMessage_getDataFPValuesById(this, dataIdentifier, dest, offset, numValues);
561  }
562 
570  inline double getDataFPValue(XsDataIdentifier dataIdentifier, XsSize offset = 0) const
571  {
572  double tmp;
573  XsMessage_getDataFPValuesById(this, dataIdentifier, &tmp, offset, 1);
574  return tmp;
575  }
576 
578  inline void setDataFPValue(XsDataIdentifier dataIdentifier, const double* data, XsSize offset = 0, XsSize numValues = 1)
579  {
580  XsMessage_setDataFPValuesById(this, dataIdentifier, data, offset, numValues);
581  }
582 
589  inline void setDataFPValue(XsDataIdentifier dataIdentifier, double data, XsSize offset = 0)
590  {
591  XsMessage_setDataFPValuesById(this, dataIdentifier, &data, offset, 1);
592  }
593 
595  inline bool operator == (const XsMessage& other) const
596  {
597  if (this == &other)
598  return true;
599  return m_message == other.m_message;
600  }
601 
603  inline XsByteArray const& rawMessage() const
604  {
605  return m_message;
606  };
607 
612  inline XsString toHexString(XsSize maxBytes = 0) const
613  {
614  XsString rv;
615  XsMessage_toHexString(this, maxBytes, &rv);
616  return rv;
617  }
618 
626  template <typename T>
627  inline void getData(T* data, XsDataIdentifier id, XsSize offset = 0, int numValues = 1) const
628  {
629  (void) id;
630  for (int i = 0; i < numValues; ++i)
631  XsMessage_getEndianCorrectData(this, &data[i], sizeof(T), offset + ((unsigned int)i)*sizeof(T));
632  }
633 
641  template <typename T>
642  inline void setData(T const* data, XsDataIdentifier id, XsSize offset = 0, int numValues = 1)
643  {
644  (void) id;
645  for (int i = 0; i < numValues; ++i)
646  XsMessage_setEndianCorrectData(this, &data[i], sizeof(T), offset + ((unsigned int)i)*sizeof(T));
647  }
648 
654  template <typename T>
655  inline static int sizeInMsg(XsDataIdentifier id, int numValues = 1)
656  {
657  (void) id;
658  return numValues * (int) sizeof(T);
659  }
660 
661 private:
663  inline void updateChecksumPtr()
664  {
666  if (sz)
667  *const_cast<uint8_t**>(&m_checksum) = &m_message[sz - 1];
668  else
669  *const_cast<uint8_t**>(&m_checksum) = 0;
670  }
671 
672 #endif
673 
676  uint8_t* const m_checksum;
677 };
678 
679 #ifdef __cplusplus
680 
688 template <>
689 inline void XsMessage::getData<double>(double* data, XsDataIdentifier id, XsSize offset, int numValues) const
690 {
691  getDataFPValue(id, data, offset, (XsSize)(ptrdiff_t)numValues);
692 }
693 
702 template <>
703 inline void XsMessage::setData<double>(double const* data, XsDataIdentifier id, XsSize offset, int numValues)
704 {
705  setDataFPValue(id, data, offset, (XsSize)(ptrdiff_t)numValues);
706 }
707 
713 template <>
714 inline int XsMessage::sizeInMsg<XsReal>(XsDataIdentifier id, int numValues)
715 {
716  return XsMessage_getFPValueSize(id) * numValues;
717 }
718 #endif
719 
720 // some macros to help when constructing/parsing messages
721 #define swapEndian16(src) (uint16_t)(((uint16_t)(src) >> 8) | ((uint16_t)(src) << 8))
722 #define swapEndian32(src) (uint32_t)(((uint32_t)(src) >> 24) | (((uint32_t)(src) >> 8) & 0xFF00) | (((uint32_t)(src) << 8) & 0xFF0000) | ((uint32_t)(src) << 24))
723 #define swapEndian64(src) (uint64_t)(((src >> 56) & 0xFFULL) | ((src >> 40) & 0xFF00ULL) | ((src >> 24) & 0xFF0000ULL) | ((src >> 8) & 0xFF000000ULL) | ((src << 8) & 0xFF00000000ULL) | ((src << 24) & 0xFF0000000000ULL) | ((src << 40) & 0xFF000000000000ULL) | ((src << 56)))
724 
725 #endif
XS_BID_MASTER
#define XS_BID_MASTER
The bus identifier of the master device.
Definition: xsbusid.h:73
XsMessage_deleteData
XSTYPES_DLL_API void XsMessage_deleteData(XsMessage *thisPtr, XsSize count, XsSize offset)
Remove count bytes of data from the message at offset.
Definition: xsmessage.c:1189
XsMessage_getDataFPValuesById
XSTYPES_DLL_API void XsMessage_getDataFPValuesById(XsMessage const *thisPtr, XsDataIdentifier dataIdentifier, double *dest, XsSize offset, XsSize numValues)
Return current data values as double, conversion depends on outputSetting.
Definition: xsmessage.c:798
xsstring.h
XsMessage_getEndianCorrectData
XSTYPES_DLL_API void XsMessage_getEndianCorrectData(XsMessage const *thisPtr, void *value, XsSize size, XsSize offset)
Get data of size size at offset, and put it byteswapped into value.
Definition: xsmessage.c:286
XsMessage_setDataFPValuesById
XSTYPES_DLL_API void XsMessage_setDataFPValuesById(XsMessage *thisPtr, XsDataIdentifier dataIdentifier, double const *data, XsSize offset, XsSize numValues)
Write a number of floating/fixed point values into to the data buffer, conversion depends on outputSe...
Definition: xsmessage.c:839
XsMessage_assign
XSTYPES_DLL_API void XsMessage_assign(XsMessage *thisPtr, XsSize dataSize)
This function reinitializes the XsMessage object and reserves dataSize bytes for data.
Definition: xsmessage.c:377
XsMessage_setBusId
XSTYPES_DLL_API void XsMessage_setBusId(XsMessage *thisPtr, uint8_t busId)
Set the bus id for this message to busId.
Definition: xsmessage.c:1088
XsMessage_swap
XSTYPES_DLL_API void XsMessage_swap(XsMessage *a, XsMessage *b)
Swap the contents of a and b.
Definition: xsmessage.c:1248
XsMessageHeader
A message header.
Definition: xsmessage.h:169
XsMessage
struct XsMessage XsMessage
Definition: xsmessage.h:85
XsByteArray
A list of uint8_t values.
XsMessage_getDataFP1632
XSTYPES_DLL_API double XsMessage_getDataFP1632(XsMessage const *thisPtr, XsSize offset)
Returns the F16.32 value at offset in the data of the message.
Definition: xsmessage.c:571
XsArray_destruct
XSTYPES_DLL_API void XsArray_destruct(void *thisPtr)
XMID_InvalidMessage
@ XMID_InvalidMessage
Definition: xsxbusmessageid.h:75
XsMessageHeader::m_busId
uint8_t m_busId
The bus ID.
Definition: xsmessage.h:172
XsMessage_insertData
XSTYPES_DLL_API void XsMessage_insertData(XsMessage *thisPtr, XsSize count, XsSize offset)
Create count bytes of empty space at offset in this message.
Definition: xsmessage.c:1125
XsMessage_constructSized
XSTYPES_DLL_API void XsMessage_constructSized(XsMessage *thisPtr, XsSize dataSize)
This function initializes the XsMessage object and reserves dataSize bytes for data.
Definition: xsmessage.c:311
XRV_NULLPTR
@ XRV_NULLPTR
274: Tried to supply a NULL value where it is not allowed
Definition: xsresultvalue.h:144
XMID_Error
@ XMID_Error
Definition: xsxbusmessageid.h:187
XsMessage_setEndianCorrectData
XSTYPES_DLL_API void XsMessage_setEndianCorrectData(XsMessage *thisPtr, void const *value, XsSize size, XsSize offset)
Set value value of size size byteswapped at offset.
Definition: xsmessage.c:297
XsMessageHeader::LengthData::ExtendedLength::ExtendedParts
Definition: xsmessage.h:183
XsMessageHeader::LengthData::m_extended
struct XsMessageHeader::LengthData::ExtendedLength m_extended
The extended length, only valid if normal length is 255.
XsMessage_getDataLongLong
XSTYPES_DLL_API uint64_t XsMessage_getDataLongLong(XsMessage const *thisPtr, XsSize offset)
Returns the long value at offset in the data of the message.
Definition: xsmessage.c:518
XsMessage_recomputeChecksum
XSTYPES_DLL_API void XsMessage_recomputeChecksum(XsMessage *thisPtr)
Update the checksum for the message.
Definition: xsmessage.c:988
XsMessageHeader::m_length
uint8_t m_length
The length of the message.
Definition: xsmessage.h:174
XS_PACKED_STRUCT_START
#define XS_PACKED_STRUCT_START
Definition: xstypedefs.h:201
XsMessageHeader::LengthData::ExtendedLength::m_length
struct XsMessageHeader::LengthData::ExtendedLength::ExtendedParts m_length
Extended length, only valid if normal length is 255.
XsMessage_setDataFP1632
XSTYPES_DLL_API void XsMessage_setDataFP1632(XsMessage *thisPtr, double value, XsSize offset)
Sets the F16.32 at offset in the message to value.
Definition: xsmessage.c:682
XsMessageHeader::m_preamble
uint8_t m_preamble
The message preamble (always 0xFA)
Definition: xsmessage.h:171
XsMessage_computeChecksum
XSTYPES_DLL_API uint8_t XsMessage_computeChecksum(XsMessage const *thisPtr)
Computes the checksum for the message.
Definition: xsmessage.c:974
XsMessageHeader::LengthData::ExtendedLength::ExtendedParts::m_low
uint8_t m_low
Low byte of extended length.
Definition: xsmessage.h:186
XsMessageHeader::m_datlen
union XsMessageHeader::LengthData m_datlen
Data or length and data.
XRV_TIMEOUTNODATA
@ XRV_TIMEOUTNODATA
259: Operation aborted because of no data read
Definition: xsresultvalue.h:129
XsMessage_getTotalMessageSize
XSTYPES_DLL_API XsSize XsMessage_getTotalMessageSize(XsMessage const *thisPtr)
Return the length of the message buffer.
Definition: xsmessage.c:461
XsMessage_setMessageId
XSTYPES_DLL_API void XsMessage_setMessageId(XsMessage *thisPtr, XsXbusMessageId msgId)
Set the message id for this message to msgId.
Definition: xsmessage.c:1106
XsMessage_getDataRealValuesById
XSTYPES_DLL_API void XsMessage_getDataRealValuesById(XsMessage const *thisPtr, XsDataIdentifier dataIdentifier, XsReal *dest, XsSize offset, XsSize numValues)
Return current data values as XsReal, conversion is done automatically based on data identifier.
Definition: xsmessage.c:881
XsMessage_resizeData
XSTYPES_DLL_API void XsMessage_resizeData(XsMessage *thisPtr, XsSize newSize)
Resize the buffer of message to newSize bytes.
Definition: xsmessage.c:1032
data
data
XsMessage_getDataBuffer
const XSTYPES_DLL_API uint8_t * XsMessage_getDataBuffer(XsMessage const *thisPtr, XsSize offset)
Returns a const pointer to the data buffer of the message.
Definition: xsmessage.c:595
XRV_OK
@ XRV_OK
0: Operation was performed successfully
Definition: xsresultvalue.h:85
XsMessage_getDataByte
XSTYPES_DLL_API uint8_t XsMessage_getDataByte(XsMessage const *thisPtr, XsSize offset)
Returns the byte value at offset in the data of the message.
Definition: xsmessage.c:481
XsMessage_isChecksumOk
XSTYPES_DLL_API int XsMessage_isChecksumOk(XsMessage const *thisPtr)
Returns non-zero if the checksum inside the message is correct for the message, zero otherwise.
Definition: xsmessage.c:997
XsMessage_toHexString
XSTYPES_DLL_API void XsMessage_toHexString(XsMessage const *thisPtr, XsSize maxBytes, XsString *resultValue)
Return a string containing the first maxBytes bytes of the message in hex format.
Definition: xsmessage.c:1278
XsMessage_setDataLongLong
XSTYPES_DLL_API void XsMessage_setDataLongLong(XsMessage *thisPtr, uint64_t value, XsSize offset)
Sets the long at offset in the message to value.
Definition: xsmessage.c:635
XsResultValue
XsResultValue
Xsens result values.
Definition: xsresultvalue.h:82
XsMessage_setDataShort
XSTYPES_DLL_API void XsMessage_setDataShort(XsMessage *thisPtr, uint16_t value, XsSize offset)
Sets the short at offset in the message to value.
Definition: xsmessage.c:615
XsMessage::m_message
XsByteArray m_message
Definition: xsmessage.h:674
operator==
bool operator==(const XsFilterProfile &lhs, const XsFilterProfile &rhs)
Returns true if lhs has the same type as rhs.
Definition: scenariomatchpred.h:81
XsDataIdentifier
XsDataIdentifier
Defines the data identifiers.
Definition: xsdataidentifier.h:84
XS_PACKED_STRUCT_END
#define XS_PACKED_STRUCT_END
Definition: xstypedefs.h:202
XsMessage_copyConstruct
XSTYPES_DLL_API void XsMessage_copyConstruct(XsMessage *thisPtr, XsMessage const *src)
Construct an XsMessage as a copy of XsMessage src.
Definition: xsmessage.c:355
uint32_t
unsigned int uint32_t
Definition: pstdint.h:485
XsMessage_load
XSTYPES_DLL_API void XsMessage_load(XsMessage *thisPtr, XsSize msgSize, unsigned char const *src)
This function initializes the XsMessage object and reserves msgSize bytes for data,...
Definition: xsmessage.c:388
XsMessage_setDataBuffer
XSTYPES_DLL_API void XsMessage_setDataBuffer(XsMessage *thisPtr, const uint8_t *buffer, XsSize size, XsSize offset)
Puts size number of bytes from buffer into the message at offset.
Definition: xsmessage.c:731
XsMessage_dataSize
XSTYPES_DLL_API XsSize XsMessage_dataSize(XsMessage const *thisPtr)
This function returns the datasize of the message in thisptr.
Definition: xsmessage.c:416
XsMessage::m_checksum
uint8_t *const m_checksum
Points to the checksum to speed up automatic checksum updates.
Definition: xsmessage.h:676
XsReal
double XsReal
Defines the floating point type used by the Xsens libraries.
Definition: xstypedefs.h:73
XsMessage_getConstHeader
const XSTYPES_DLL_API XsMessageHeader * XsMessage_getConstHeader(XsMessage const *thisPtr)
Definition: xsmessage.c:1012
xsbusid.h
XsMessage_setDataLong
XSTYPES_DLL_API void XsMessage_setDataLong(XsMessage *thisPtr, uint32_t value, XsSize offset)
Sets the long at offset in the message to value.
Definition: xsmessage.c:625
XsMessage::XsMessage_getFPValueSize
uint8_t XsMessage_getFPValueSize(XsDataIdentifier id)
Returns the byte size of id if the format is a floating point format.
Definition: xsmessage.c:744
XsMessage_copy
XSTYPES_DLL_API void XsMessage_copy(XsMessage *copy, XsMessage const *src)
This function copies from thisPtr to copy.
Definition: xsmessage.c:406
XsSize
size_t XsSize
XsSize must be unsigned number!
Definition: xstypedefs.h:74
XsMessage_setDataF1220
XSTYPES_DLL_API void XsMessage_setDataF1220(XsMessage *thisPtr, double value, XsSize offset)
Sets the F12.20 at offset in the message to value.
Definition: xsmessage.c:666
XsXbusMessageId
XsXbusMessageId
Xsens Xbus Message Identifiers.
Definition: xsxbusmessageid.h:73
XsMessage_empty
XSTYPES_DLL_API int XsMessage_empty(XsMessage const *thisPtr)
Test if this message is empty.
Definition: xsmessage.c:1020
XsMessage_construct
XSTYPES_DLL_API void XsMessage_construct(XsMessage *thisPtr)
This function initializes the XsMessage object.
Definition: xsmessage.c:347
XsMessage
Structure for storing a single message.
Definition: xsmessage.h:202
XsMessage_getDataF1220
XSTYPES_DLL_API double XsMessage_getDataF1220(XsMessage const *thisPtr, XsSize offset)
Returns the F12.20 value at offset in the data of the message.
Definition: xsmessage.c:555
xsdataidentifier.h
XsMessage_setDataDouble
XSTYPES_DLL_API void XsMessage_setDataDouble(XsMessage *thisPtr, double value, XsSize offset)
Sets the double at offset in the message to value.
Definition: xsmessage.c:656
xstypesconfig.h
xsxbusmessageid.h
pstdint.h
XsMessageHeader::LengthData
Definition: xsmessage.h:177
XsMessage_setDataByte
XSTYPES_DLL_API void XsMessage_setDataByte(XsMessage *thisPtr, uint8_t value, XsSize offset)
Set the byte at offset in the message to value.
Definition: xsmessage.c:605
XsMessage_getDataLong
XSTYPES_DLL_API uint32_t XsMessage_getDataLong(XsMessage const *thisPtr, XsSize offset)
Returns the long value at offset in the data of the message.
Definition: xsmessage.c:505
XSTYPES_DLL_API
#define XSTYPES_DLL_API
Definition: xstypesconfig.h:65
XsMessageHeader::LengthData::m_data
uint8_t m_data[1]
The first byte of the data buffer if length < 255, the data buffer is always at least 1 byte since it...
Definition: xsmessage.h:190
XsMessage_destruct
XSTYPES_DLL_API void XsMessage_destruct(XsMessage *thisPtr)
This function clears the data in the message.
Definition: xsmessage.c:397
XsMessage_compare
XSTYPES_DLL_API int XsMessage_compare(XsMessage const *a, XsMessage const *b)
Compare the contents of the messages a and b, returning non-0 if they are different.
Definition: xsmessage.c:1269
XsMessage_getMessageStart
const XSTYPES_DLL_API uint8_t * XsMessage_getMessageStart(XsMessage const *thisPtr)
This function returns a const pointer to the header of the message in thisptr.
Definition: xsmessage.c:448
XS_PACKED_STRUCT
XS_PACKED_STRUCT_START struct XsMessageHeader XS_PACKED_STRUCT
XsMessageHeader::LengthData::ExtendedLength::ExtendedParts::m_high
uint8_t m_high
High byte of extended length.
Definition: xsmessage.h:185
XsMessage::m_autoUpdateChecksum
int m_autoUpdateChecksum
Definition: xsmessage.h:675
XsMessage_getHeader
XSTYPES_DLL_API XsMessageHeader * XsMessage_getHeader(XsMessage *)
Returns a pointer to the message header for this message.
Definition: xsmessage.c:1006
xsbytearray.h
XsMessage_constData
const XSTYPES_DLL_API uint8_t * XsMessage_constData(XsMessage const *thisPtr, XsSize offset)
This function returns a const pointer to the offset in the data of the message in thisptr.
Definition: xsmessage.c:436
XsMessage_getDataFloat
XSTYPES_DLL_API float XsMessage_getDataFloat(XsMessage const *thisPtr, XsSize offset)
Returns the float value at offset in the data of the message.
Definition: xsmessage.c:531
xsresultvalue.h
XsMessageHeader::m_messageId
uint8_t m_messageId
The message ID.
Definition: xsmessage.h:173
XsMessage_getDataDouble
XSTYPES_DLL_API double XsMessage_getDataDouble(XsMessage const *thisPtr, XsSize offset)
Returns the double at offset in the data of the message.
Definition: xsmessage.c:543
XsString
A 0-terminated managed string of characters.
XsMessageHeader::LengthData::ExtendedLength::m_data
uint8_t m_data[1]
The first byte of the data buffer, the data buffer is always at least 1 byte since it has to contain ...
Definition: xsmessage.h:188
XsMessage_setDataRealValuesById
XSTYPES_DLL_API void XsMessage_setDataRealValuesById(XsMessage *thisPtr, XsDataIdentifier dataIdentifier, XsReal const *data, XsSize offset, XsSize numValues)
Write a number of floating/fixed point values into to the data buffer, conversion depends on data ide...
Definition: xsmessage.c:938
XsMessageHeader::LengthData::ExtendedLength
Definition: xsmessage.h:180
XsMessage_setDataFloat
XSTYPES_DLL_API void XsMessage_setDataFloat(XsMessage *thisPtr, float value, XsSize offset)
Sets the float at offset in the message to value.
Definition: xsmessage.c:646
XsMessage_getDataShort
XSTYPES_DLL_API uint16_t XsMessage_getDataShort(XsMessage const *thisPtr, XsSize offset)
Returns the short value at offset in the data of the message.
Definition: xsmessage.c:492


xsens_mti_driver
Author(s):
autogenerated on Sun Sep 3 2023 02:43:20