CANopenNode
CO_driver.h
Go to the documentation of this file.
1 
26 #ifndef CO_DRIVER_H
27 #define CO_DRIVER_H
28 
29 #include <string.h>
30 
31 #include "CO_config.h"
32 #include "CO_driver_target.h"
33 
34 #ifdef __cplusplus
35 extern "C" {
36 #endif
37 
38 #ifdef CO_DEBUG_COMMON
39 #if (CO_CONFIG_DEBUG) & CO_CONFIG_DEBUG_SDO_CLIENT
40  #define CO_DEBUG_SDO_CLIENT(msg) CO_DEBUG_COMMON(msg)
41 #endif
42 #if (CO_CONFIG_DEBUG) & CO_CONFIG_DEBUG_SDO_SERVER
43  #define CO_DEBUG_SDO_SERVER(msg) CO_DEBUG_COMMON(msg)
44 #endif
45 #endif
46 
102 #define CO_VERSION_MAJOR 4
103 
104 #define CO_VERSION_MINOR 0
105 
106 
107 /* Macros and declarations in following part are only used for documentation. */
108 #ifdef CO_DOXYGEN
109 
127 #define CO_LITTLE_ENDIAN
128 
129 #define CO_SWAP_16(x) x
130 
131 #define CO_SWAP_32(x) x
132 
133 #define CO_SWAP_64(x) x
134 
135 #define NULL (0)
136 
137 #define true 1
138 
139 #define false 0
140 
141 typedef unsigned char bool_t;
143 typedef signed char int8_t;
145 typedef signed int int16_t;
147 typedef signed long int int32_t;
149 typedef signed long long int int64_t;
151 typedef unsigned char uint8_t;
153 typedef unsigned int uint16_t;
155 typedef unsigned long int uint32_t;
157 typedef unsigned long long int uint64_t;
159 typedef float float32_t;
161 typedef double float64_t;
163 typedef char char_t;
165 typedef unsigned char oChar_t;
167 typedef unsigned char domain_t;
202 void CANrx_callback(void *object, void *rxMsg);
203 
218 static inline uint16_t CO_CANrxMsg_readIdent(void *rxMsg) {
219  return 0;
220 }
221 
230 static inline uint8_t CO_CANrxMsg_readDLC(void *rxMsg) {
231  return 0;
232 }
233 
242 static inline uint8_t *CO_CANrxMsg_readData(void *rxMsg) {
243  return NULL;
244 }
245 
257 typedef struct {
261  void *object;
263  void (*pCANrx_callback)(
264  void *object, void *message);
266 } CO_CANrx_t;
299 typedef struct {
302  uint8_t data[8];
303  volatile bool_t bufferFull;
305  volatile bool_t syncFlag;
307 } CO_CANtx_t;
319 typedef struct {
320  void *CANptr;
327  volatile bool_t CANnormal;
338  volatile uint16_t CANtxCount;
343 
344 
388 #define CO_LOCK_CAN_SEND()
389 
390 #define CO_UNLOCK_CAN_SEND()
391 
392 #define CO_LOCK_EMCY()
393 
394 #define CO_UNLOCK_EMCY()
395 
396 #define CO_LOCK_OD()
397 
398 #define CO_UNLOCK_OD()
399 
401 #define CO_FLAG_READ(rxNew) ((rxNew) != NULL)
402 
403 #define CO_FLAG_SET(rxNew) { __sync_synchronize(); rxNew = (void *)1L; }
404 
405 #define CO_FLAG_CLEAR(rxNew) { __sync_synchronize(); rxNew = NULL; }
406 
408 #endif /* CO_DOXYGEN */
409 
410 
424 #ifndef CO_errinfo
425 #define CO_errinfo(CANmodule, err)
426 #endif
427 
428 
437 typedef enum {
439  CO_CAN_ID_GFC = 0x001,
440  CO_CAN_ID_SYNC = 0x080,
442  CO_CAN_ID_TIME = 0x100,
458 
459 
468 typedef enum {
482 
483 
488 typedef enum {
507  CO_ERROR_CRC = -14,
518 
519 
525 void CO_CANsetConfigurationMode(void *CANptr);
526 
527 
533 void CO_CANsetNormalMode(CO_CANmodule_t *CANmodule);
534 
535 
556  void *CANptr,
557  CO_CANrx_t rxArray[],
558  uint16_t rxSize,
559  CO_CANtx_t txArray[],
560  uint16_t txSize,
561  uint16_t CANbitRate);
562 
563 
569 void CO_CANmodule_disable(CO_CANmodule_t *CANmodule);
570 
571 
598  uint16_t index,
599  uint16_t ident,
600  uint16_t mask,
601  bool_t rtr,
602  void *object,
603  void (*CANrx_callback)(void *object,
604  void *message));
605 
606 
626  uint16_t index,
627  uint16_t ident,
628  bool_t rtr,
629  uint8_t noOfBytes,
630  bool_t syncFlag);
631 
632 
644 
645 
661 
662 
671 void CO_CANmodule_process(CO_CANmodule_t *CANmodule);
672 
673 
681 static inline uint8_t CO_getUint8(const void *buf) {
682  uint8_t value; memmove(&value, buf, sizeof(value)); return value;
683 }
685 static inline uint16_t CO_getUint16(const void *buf) {
686  uint16_t value; memmove(&value, buf, sizeof(value)); return value;
687 }
689 static inline uint32_t CO_getUint32(const void *buf) {
690  uint32_t value; memmove(&value, buf, sizeof(value)); return value;
691 }
692 
701 static inline uint8_t CO_setUint8(void *buf, uint8_t value) {
702  memmove(buf, &value, sizeof(value)); return sizeof(value);
703 }
705 static inline uint8_t CO_setUint16(void *buf, uint16_t value) {
706  memmove(buf, &value, sizeof(value)); return sizeof(value);
707 }
709 static inline uint8_t CO_setUint32(void *buf, uint32_t value) {
710  memmove(buf, &value, sizeof(value)); return sizeof(value);
711 }
712  /* CO_driver */
714 
715 #ifdef __cplusplus
716 }
717 #endif /* __cplusplus */
718 
719 #endif /* CO_DRIVER_H */
uint32_t
unsigned long int uint32_t
UNSIGNED32 in CANopen (0007h), 32-bit unsigned integer.
Definition: CO_driver.h:155
CO_CANmodule_t::firstCANtxMessage
volatile bool_t firstCANtxMessage
Equal to 1, when the first transmitted message (bootup message) is in CAN TX buffers.
Definition: CO_driver.h:336
CO_CAN_ID_TPDO_1
@ CO_CAN_ID_TPDO_1
0x180, Default TPDO1 (+nodeID)
Definition: CO_driver.h:444
CO_ERROR_DATA_CORRUPT
@ CO_ERROR_DATA_CORRUPT
Stored data are corrupt.
Definition: CO_driver.h:506
CO_CAN_ID_GFC
@ CO_CAN_ID_GFC
0x001, Global fail-safe command
Definition: CO_driver.h:439
CO_CANrx_t::mask
uint16_t mask
Standard CAN Identifier mask with the same alignment as ident.
Definition: CO_driver.h:259
CO_CANmodule_t::txArray
CO_CANtx_t * txArray
From CO_CANmodule_init()
Definition: CO_driver.h:323
CO_CANtxBufferInit
CO_CANtx_t * CO_CANtxBufferInit(CO_CANmodule_t *CANmodule, uint16_t index, uint16_t ident, bool_t rtr, uint8_t noOfBytes, bool_t syncFlag)
Configure CAN message transmit buffer.
Definition: CO_driver.c:519
CO_CANclearPendingSyncPDOs
void CO_CANclearPendingSyncPDOs(CO_CANmodule_t *CANmodule)
Clear all synchronous TPDOs from CAN module transmit buffers.
Definition: CO_driver.c:707
CO_CAN_ID_NMT_SERVICE
@ CO_CAN_ID_NMT_SERVICE
0x000, Network management
Definition: CO_driver.h:438
CO_CANrx_t::object
void * object
CANopenNode Object initialized in from CO_CANrxBufferInit()
Definition: CO_driver.h:261
char_t
char char_t
VISIBLE_STRING in CANopen (0009h), string of signed 8-bit values.
Definition: CO_driver.h:163
CO_setUint16
static uint8_t CO_setUint16(void *buf, uint16_t value)
Write uint16_t value into memory buffer, see CO_setUint8.
Definition: CO_driver.h:705
CO_ERROR_NO
@ CO_ERROR_NO
Operation completed successfully.
Definition: CO_driver.h:489
CO_CAN_ID_TPDO_2
@ CO_CAN_ID_TPDO_2
0x280, Default TPDO2 (+nodeID)
Definition: CO_driver.h:446
int64_t
signed long long int int64_t
INTEGER64 in CANopen (0015h), 64-bit signed integer.
Definition: CO_driver.h:149
uint16_t
unsigned int uint16_t
UNSIGNED16 in CANopen (0006h), 16-bit unsigned integer.
Definition: CO_driver.h:153
CO_ERROR_RX_PDO_OVERFLOW
@ CO_ERROR_RX_PDO_OVERFLOW
previous PDO was not processed yet
Definition: CO_driver.h:497
CO_CAN_ID_SRDO_1
@ CO_CAN_ID_SRDO_1
0x0FF, Default SRDO1 (+2*nodeID)
Definition: CO_driver.h:443
CO_ReturnError_t
CO_ReturnError_t
Return values of some CANopen functions.
Definition: CO_driver.h:488
CO_CAN_ERRTX_PASSIVE
@ CO_CAN_ERRTX_PASSIVE
0x0002, CAN transmitter passive
Definition: CO_driver.h:470
CO_CANrxMsg_readDLC
static uint8_t CO_CANrxMsg_readDLC(void *rxMsg)
CANrx_callback() can read Data Length Code from received CAN message.
Definition: CO_driver.h:230
CO_CAN_ID_EMERGENCY
@ CO_CAN_ID_EMERGENCY
0x080, Emergency messages (+nodeID)
Definition: CO_driver.h:441
CO_CAN_ERRTX_BUS_OFF
@ CO_CAN_ERRTX_BUS_OFF
0x0004, CAN transmitter bus off
Definition: CO_driver.h:471
CO_CAN_ERRTX_OVERFLOW
@ CO_CAN_ERRTX_OVERFLOW
0x0008, CAN transmitter overflow
Definition: CO_driver.h:472
bool_t
unsigned char bool_t
Boolean data type for general use.
Definition: CO_driver.h:141
CO_ERROR_TX_UNCONFIGURED
@ CO_ERROR_TX_UNCONFIGURED
Transmit buffer was not configured properly.
Definition: CO_driver.h:503
CANrx_callback
void CANrx_callback(void *object, void *rxMsg)
CAN receive callback function which pre-processes received CAN message.
CO_CANmodule_init
CO_ReturnError_t CO_CANmodule_init(CO_CANmodule_t *CANmodule, void *CANptr, CO_CANrx_t rxArray[], uint16_t rxSize, CO_CANtx_t txArray[], uint16_t txSize, uint16_t CANbitRate)
Initialize CAN module object.
Definition: CO_driver.c:198
CO_setUint8
static uint8_t CO_setUint8(void *buf, uint8_t value)
Write uint8_t value into memory buffer.
Definition: CO_driver.h:701
CO_CAN_ERRRX_PASSIVE
@ CO_CAN_ERRRX_PASSIVE
0x0200, CAN receiver passive
Definition: CO_driver.h:477
CO_CANrxMsg_readData
static uint8_t * CO_CANrxMsg_readData(void *rxMsg)
CANrx_callback() can read pointer to data from received CAN message.
Definition: CO_driver.h:242
CO_CAN_ID_RPDO_2
@ CO_CAN_ID_RPDO_2
0x300, Default RPDO2 (+nodeID)
Definition: CO_driver.h:447
int32_t
signed long int int32_t
INTEGER32 in CANopen (0004h), 32-bit signed integer.
Definition: CO_driver.h:147
CO_CANrxBufferInit
CO_ReturnError_t CO_CANrxBufferInit(CO_CANmodule_t *CANmodule, uint16_t index, uint16_t ident, uint16_t mask, bool_t rtr, void *object, void(*CANrx_callback)(void *object, void *message))
Configure CAN message receive buffer.
Definition: CO_driver.c:428
uint64_t
unsigned long long int uint64_t
UNSIGNED64 in CANopen (001Bh), 64-bit unsigned integer.
Definition: CO_driver.h:157
CO_CANmodule_t::useCANrxFilters
volatile bool_t useCANrxFilters
Value different than zero indicates, that CAN module hardware filters are used for CAN reception.
Definition: CO_driver.h:328
CO_ERROR_RX_OVERFLOW
@ CO_ERROR_RX_OVERFLOW
Previous message was not processed yet.
Definition: CO_driver.h:495
CO_CAN_ERRTX_PDO_LATE
@ CO_CAN_ERRTX_PDO_LATE
0x0080, TPDO is outside sync window
Definition: CO_driver.h:474
CO_CAN_ID_TPDO_3
@ CO_CAN_ID_TPDO_3
0x380, Default TPDO3 (+nodeID)
Definition: CO_driver.h:448
CO_CAN_ID_RPDO_1
@ CO_CAN_ID_RPDO_1
0x200, Default RPDO1 (+nodeID)
Definition: CO_driver.h:445
CO_CAN_ID_HEARTBEAT
@ CO_CAN_ID_HEARTBEAT
0x700, Heartbeat message
Definition: CO_driver.h:454
int8_t
signed char int8_t
INTEGER8 in CANopen (0002h), 8-bit signed integer.
Definition: CO_driver.h:143
CO_getUint16
static uint16_t CO_getUint16(const void *buf)
Get uint16_t value from memory buffer, see CO_getUint8.
Definition: CO_driver.h:685
CO_ERROR_RX_MSG_LENGTH
@ CO_ERROR_RX_MSG_LENGTH
Wrong receive message length.
Definition: CO_driver.h:498
CO_CANrxMsg_readIdent
static uint16_t CO_CANrxMsg_readIdent(void *rxMsg)
CANrx_callback() can read CAN identifier from received CAN message.
Definition: CO_driver.h:218
CO_CANmodule_t::CANptr
void * CANptr
From CO_CANmodule_init()
Definition: CO_driver.h:320
CO_driver_target.h
Linux socketCAN specific definitions for CANopenNode.
CO_CAN_ID_TPDO_4
@ CO_CAN_ID_TPDO_4
0x480, Default TPDO4 (+nodeID)
Definition: CO_driver.h:450
CO_CAN_ID_LSS_MST
@ CO_CAN_ID_LSS_MST
0x7E5, LSS request from master
Definition: CO_driver.h:456
CO_ERROR_TX_OVERFLOW
@ CO_ERROR_TX_OVERFLOW
Previous message is still waiting, buffer full.
Definition: CO_driver.h:500
CO_CAN_ID_SYNC
@ CO_CAN_ID_SYNC
0x080, Synchronous message
Definition: CO_driver.h:440
float64_t
double float64_t
REAL64 in CANopen (0011h), double precision floating point value, 64-bit.
Definition: CO_driver.h:161
CO_CANmodule_disable
void CO_CANmodule_disable(CO_CANmodule_t *CANmodule)
Switch off CANmodule.
Definition: CO_driver.c:392
CO_CANtx_t::ident
uint32_t ident
CAN identifier as aligned in CAN module.
Definition: CO_driver.h:300
CO_config.h
Configuration macros for CANopenNode.
float32_t
float float32_t
REAL32 in CANopen (0008h), single precision floating point value, 32-bit.
Definition: CO_driver.h:159
CO_CANtx_t::bufferFull
volatile bool_t bufferFull
True if previous message is still in the buffer.
Definition: CO_driver.h:303
CO_ERROR_SYSCALL
@ CO_ERROR_SYSCALL
Syscall failed.
Definition: CO_driver.h:512
oChar_t
unsigned char oChar_t
OCTET_STRING in CANopen (000Ah), string of unsigned 8-bit values.
Definition: CO_driver.h:165
CO_ERROR_TX_PDO_WINDOW
@ CO_ERROR_TX_PDO_WINDOW
Synchronous TPDO is outside window.
Definition: CO_driver.h:502
CO_CAN_ID_SDO_CLI
@ CO_CAN_ID_SDO_CLI
0x600, SDO request from client (+nodeID)
Definition: CO_driver.h:453
CO_ERROR_INVALID_STATE
@ CO_ERROR_INVALID_STATE
Driver not ready.
Definition: CO_driver.h:513
CO_CANmodule_t::rxArray
CO_CANrx_t * rxArray
From CO_CANmodule_init()
Definition: CO_driver.h:321
CO_CANmodule_process
void CO_CANmodule_process(CO_CANmodule_t *CANmodule)
Process can module - verify CAN errors.
Definition: CO_driver.c:715
CO_CAN_ID_LSS_SLV
@ CO_CAN_ID_LSS_SLV
0x7E4, LSS response from slave
Definition: CO_driver.h:455
CO_CANmodule_t::rxSize
uint16_t rxSize
From CO_CANmodule_init()
Definition: CO_driver.h:322
CO_ERROR_CRC
@ CO_ERROR_CRC
CRC does not match.
Definition: CO_driver.h:507
CO_ERROR_OD_PARAMETERS
@ CO_ERROR_OD_PARAMETERS
Error in Object Dictionary parameters.
Definition: CO_driver.h:505
CO_ERROR_ILLEGAL_BAUDRATE
@ CO_ERROR_ILLEGAL_BAUDRATE
Illegal baudrate passed to function CO_CANmodule_init()
Definition: CO_driver.h:493
CO_ERROR_ILLEGAL_ARGUMENT
@ CO_ERROR_ILLEGAL_ARGUMENT
Error in function arguments.
Definition: CO_driver.h:490
CO_CANmodule_t::CANerrorStatus
uint16_t CANerrorStatus
CAN error status bitfield, see CO_CAN_ERR_status_t.
Definition: CO_driver.h:325
CO_CAN_ERR_WARN_PASSIVE
@ CO_CAN_ERR_WARN_PASSIVE
0x0303, combination
Definition: CO_driver.h:480
CO_ERROR_TX_BUSY
@ CO_ERROR_TX_BUSY
Sending rejected because driver is busy.
Definition: CO_driver.h:508
CO_ERROR_WRONG_NMT_STATE
@ CO_ERROR_WRONG_NMT_STATE
Command can't be processed in current state.
Definition: CO_driver.h:510
CO_CAN_ID_RPDO_4
@ CO_CAN_ID_RPDO_4
0x500, Default RPDO5 (+nodeID)
Definition: CO_driver.h:451
CO_ERROR_TIMEOUT
@ CO_ERROR_TIMEOUT
Function timeout.
Definition: CO_driver.h:492
CO_ERROR_RX_PDO_LENGTH
@ CO_ERROR_RX_PDO_LENGTH
Wrong receive PDO length.
Definition: CO_driver.h:499
int16_t
signed int int16_t
INTEGER16 in CANopen (0003h), 16-bit signed integer.
Definition: CO_driver.h:145
CO_CANsetConfigurationMode
void CO_CANsetConfigurationMode(void *CANptr)
Request CAN configuration (stopped) mode and wait until it is set.
Definition: CO_driver.c:173
CO_getUint32
static uint32_t CO_getUint32(const void *buf)
Get uint32_t value from memory buffer, see CO_getUint8.
Definition: CO_driver.h:689
CO_CANtx_t::DLC
uint8_t DLC
Length of CAN message.
Definition: CO_driver.h:301
CO_CANmodule_t::txSize
uint16_t txSize
From CO_CANmodule_init()
Definition: CO_driver.h:324
CO_CAN_ERRRX_WARNING
@ CO_CAN_ERRRX_WARNING
0x0100, CAN receiver warning
Definition: CO_driver.h:476
CO_CANmodule_t::errinfo
int32_t errinfo
For use with CO_errinfo()
Definition: CO_driver.h:341
CO_ERROR_NODE_ID_UNCONFIGURED_LSS
@ CO_ERROR_NODE_ID_UNCONFIGURED_LSS
Node-id is in LSS unconfigured state.
Definition: CO_driver.h:514
CO_CANrx_t
Configuration object for CAN received message for specific CANopenNode Object.
Definition: CO_driver.h:257
CO_CAN_ERR_status_t
CO_CAN_ERR_status_t
CAN error status bitmasks.
Definition: CO_driver.h:468
NULL
#define NULL
NULL, for general usage.
Definition: CO_driver.h:135
CO_CAN_ID_RPDO_3
@ CO_CAN_ID_RPDO_3
0x400, Default RPDO3 (+nodeID)
Definition: CO_driver.h:449
CO_Default_CAN_ID_t
CO_Default_CAN_ID_t
Default CANopen identifiers.
Definition: CO_driver.h:437
CO_CANmodule_t
Complete CAN module object.
Definition: CO_driver.h:319
CO_CANrx_t::ident
uint16_t ident
Standard CAN Identifier (bits 0..10) + RTR (bit 11)
Definition: CO_driver.h:258
CO_CANmodule_t::CANtxCount
volatile uint16_t CANtxCount
Number of messages in transmit buffer, which are waiting to be copied to the CAN module.
Definition: CO_driver.h:338
CO_getUint8
static uint8_t CO_getUint8(const void *buf)
Get uint8_t value from memory buffer.
Definition: CO_driver.h:681
CO_CANmodule_t::CANnormal
volatile bool_t CANnormal
CAN module is in normal mode.
Definition: CO_driver.h:327
CO_CANsetNormalMode
void CO_CANsetNormalMode(CO_CANmodule_t *CANmodule)
Request CAN normal (operational) mode and wait until it is set.
Definition: CO_driver.c:181
CO_ERROR_OUT_OF_MEMORY
@ CO_ERROR_OUT_OF_MEMORY
Memory allocation failed.
Definition: CO_driver.h:491
CO_CANmodule_t::errOld
uint32_t errOld
Previous state of CAN errors.
Definition: CO_driver.h:340
domain_t
unsigned char domain_t
DOMAIN in CANopen (000Fh), used to transfer a large block of data.
Definition: CO_driver.h:167
CO_CANmodule_t::bufferInhibitFlag
volatile bool_t bufferInhibitFlag
If flag is true, then message in transmit buffer is synchronous PDO message, which will be aborted,...
Definition: CO_driver.h:332
CO_CAN_ERRRX_OVERFLOW
@ CO_CAN_ERRRX_OVERFLOW
0x0800, CAN receiver overflow
Definition: CO_driver.h:478
CO_CAN_ID_TIME
@ CO_CAN_ID_TIME
0x100, Time message
Definition: CO_driver.h:442
CO_CAN_ID_SDO_SRV
@ CO_CAN_ID_SDO_SRV
0x580, SDO response from server (+nodeID)
Definition: CO_driver.h:452
CO_CAN_ERRTX_WARNING
@ CO_CAN_ERRTX_WARNING
0x0001, CAN transmitter warning
Definition: CO_driver.h:469
CO_CANtx_t
Configuration object for CAN transmit message for specific CANopenNode Object.
Definition: CO_driver.h:299
CO_CANtx_t::syncFlag
volatile bool_t syncFlag
Synchronous PDO messages has this flag set.
Definition: CO_driver.h:305
CO_CANsend
CO_ReturnError_t CO_CANsend(CO_CANmodule_t *CANmodule, CO_CANtx_t *buffer)
Send CAN message.
Definition: CO_driver.c:664
CO_setUint32
static uint8_t CO_setUint32(void *buf, uint32_t value)
Write uint32_t value into memory buffer, see CO_setUint8.
Definition: CO_driver.h:709
uint8_t
unsigned char uint8_t
UNSIGNED8 in CANopen (0005h), 8-bit unsigned integer.
Definition: CO_driver.h:151