27#include "CO_driver_target.h"
34#ifndef CO_CONFIG_GLOBAL_FLAG_CALLBACK_PRE
35#define CO_CONFIG_GLOBAL_FLAG_CALLBACK_PRE (0)
37#ifndef CO_CONFIG_GLOBAL_RT_FLAG_CALLBACK_PRE
38#define CO_CONFIG_GLOBAL_RT_FLAG_CALLBACK_PRE (0)
40#ifndef CO_CONFIG_GLOBAL_FLAG_TIMERNEXT
41#define CO_CONFIG_GLOBAL_FLAG_TIMERNEXT (0)
43#ifndef CO_CONFIG_GLOBAL_FLAG_OD_DYNAMIC
44#define CO_CONFIG_GLOBAL_FLAG_OD_DYNAMIC CO_CONFIG_FLAG_OD_DYNAMIC
47#if (CO_CONFIG_DEBUG) & CO_CONFIG_DEBUG_SDO_CLIENT
48#define CO_DEBUG_SDO_CLIENT(msg) CO_DEBUG_COMMON(msg)
50#if (CO_CONFIG_DEBUG) & CO_CONFIG_DEBUG_SDO_SERVER
51#define CO_DEBUG_SDO_SERVER(msg) CO_DEBUG_COMMON(msg)
99#define CO_VERSION_MAJOR 4
101#define CO_VERSION_MINOR 0
119#define CO_LITTLE_ENDIAN
120#define CO_SWAP_16(x) x
121#define CO_SWAP_32(x) x
122#define CO_SWAP_64(x) x
222 void (*pCANrx_callback)(
void* object,
358#define CO_LOCK_CAN_SEND(CAN_MODULE)
359#define CO_UNLOCK_CAN_SEND(CAN_MODULE)
360#define CO_LOCK_EMCY(CAN_MODULE)
361#define CO_UNLOCK_EMCY(CAN_MODULE)
362#define CO_LOCK_OD(CAN_MODULE)
363#define CO_UNLOCK_OD(CAN_MODULE)
366#define CO_FLAG_READ(rxNew) ((rxNew) != NULL)
368#define CO_FLAG_SET(rxNew) \
370 __sync_synchronize(); \
374#define CO_FLAG_CLEAR(rxNew) \
376 __sync_synchronize(); \
391#define CO_CAN_ID_NMT_SERVICE 0x000U
392#define CO_CAN_ID_GFC 0x001U
393#define CO_CAN_ID_SYNC 0x080U
394#define CO_CAN_ID_EMERGENCY 0x080U
395#define CO_CAN_ID_TIME 0x100U
396#define CO_CAN_ID_SRDO_1 0x0FFU
397#define CO_CAN_ID_TPDO_1 0x180U
398#define CO_CAN_ID_RPDO_1 0x200U
399#define CO_CAN_ID_TPDO_2 0x280U
400#define CO_CAN_ID_RPDO_2 0x300U
401#define CO_CAN_ID_TPDO_3 0x380U
402#define CO_CAN_ID_RPDO_3 0x400U
403#define CO_CAN_ID_TPDO_4 0x480U
404#define CO_CAN_ID_RPDO_4 0x500U
405#define CO_CAN_ID_SDO_SRV 0x580U
406#define CO_CAN_ID_SDO_CLI 0x600U
407#define CO_CAN_ID_HEARTBEAT 0x700U
408#define CO_CAN_ID_LSS_SLV 0x7E4U
409#define CO_CAN_ID_LSS_MST 0x7E5U
419#ifndef CO_IS_RESTRICTED_CAN_ID
420#define CO_IS_RESTRICTED_CAN_ID(CAN_ID) \
421 (((CAN_ID) <= 0x7FU) || (((CAN_ID) >= 0x101U) && ((CAN_ID) <= 0x180U)) \
422 || (((CAN_ID) >= 0x581U) && ((CAN_ID) <= 0x5FFU)) || (((CAN_ID) >= 0x601U) && ((CAN_ID) <= 0x67FU)) \
423 || (((CAN_ID) >= 0x6E0U) && ((CAN_ID) <= 0x6FFU)) || ((CAN_ID) >= 0x701U))
434#define CO_CAN_ERRTX_WARNING 0x0001U
435#define CO_CAN_ERRTX_PASSIVE 0x0002U
436#define CO_CAN_ERRTX_BUS_OFF 0x0004U
437#define CO_CAN_ERRTX_OVERFLOW 0x0008U
438#define CO_CAN_ERRTX_PDO_LATE 0x0080U
439#define CO_CAN_ERRRX_WARNING 0x0100U
440#define CO_CAN_ERRRX_PASSIVE 0x0200U
441#define CO_CAN_ERRRX_OVERFLOW 0x0800U
442#define CO_CAN_ERR_WARN_PASSIVE 0x0303U
603 (void)memmove((
void*)&value, buf,
sizeof(value));
611 (void)memmove((
void*)&value, buf,
sizeof(value));
619 (void)memmove((
void*)&value, buf,
sizeof(value));
633 (void)memmove(buf, (
const void*)&value,
sizeof(value));
634 return (
uint8_t)(
sizeof(value));
640 (void)memmove(buf, (
const void*)&value,
sizeof(value));
641 return (
uint8_t)(
sizeof(value));
647 (void)memmove(buf, (
const void*)&value,
sizeof(value));
648 return (
uint8_t)(
sizeof(value));
Configuration macros for CANopenNode.
static uint16_t CO_CANrxMsg_readIdent(void *rxMsg)
CANrx_callback() can read CAN identifier from received CAN message.
Definition CO_driver.h:180
void CANrx_callback(void *object, void *rxMsg)
CAN receive callback function which pre-processes received CAN message.
static const uint8_t * CO_CANrxMsg_readData(void *rxMsg)
CANrx_callback() can read pointer to data from received CAN message.
Definition CO_driver.h:206
static uint8_t CO_CANrxMsg_readDLC(void *rxMsg)
CANrx_callback() can read Data Length Code from received CAN message.
Definition CO_driver.h:193
#define NULL
NULL, for general usage.
Definition CO_driver.h:123
unsigned int uint16_t
UNSIGNED16 in CANopen (0006h), 16-bit unsigned integer.
Definition CO_driver.h:132
unsigned long int uint32_t
UNSIGNED32 in CANopen (0007h), 32-bit unsigned integer.
Definition CO_driver.h:133
float float32_t
REAL32 in CANopen (0008h), single precision floating point value, 32-bit.
Definition CO_driver.h:135
uint_fast8_t bool_t
Boolean data type for general use.
Definition CO_driver.h:126
signed long long int int64_t
INTEGER64 in CANopen (0015h), 64-bit signed integer.
Definition CO_driver.h:130
signed int int16_t
INTEGER16 in CANopen (0003h), 16-bit signed integer.
Definition CO_driver.h:128
unsigned char uint8_t
UNSIGNED8 in CANopen (0005h), 8-bit unsigned integer.
Definition CO_driver.h:131
double float64_t
REAL64 in CANopen (0011h), double precision floating point value, 64-bit.
Definition CO_driver.h:136
unsigned long long int uint64_t
UNSIGNED64 in CANopen (001Bh), 64-bit unsigned integer.
Definition CO_driver.h:134
signed long int int32_t
INTEGER32 in CANopen (0004h), 32-bit signed integer.
Definition CO_driver.h:129
signed char int8_t
INTEGER8 in CANopen (0002h), 8-bit signed integer.
Definition CO_driver.h:127
void CO_CANmodule_process(CO_CANmodule_t *CANmodule)
Process can module - verify CAN errors.
CO_ReturnError_t
Return values of some CANopen functions.
Definition CO_driver.h:449
static uint32_t CO_getUint32(const void *buf)
Get uint32_t value from memory buffer, see CO_getUint8.
Definition CO_driver.h:617
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.
static uint8_t CO_getUint8(const void *buf)
Get uint8_t value from memory buffer.
Definition CO_driver.h:601
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.
CO_ReturnError_t CO_CANsend(CO_CANmodule_t *CANmodule, CO_CANtx_t *buffer)
Send CAN message.
static uint8_t CO_setUint8(void *buf, uint8_t value)
Write uint8_t value into memory buffer.
Definition CO_driver.h:632
static uint16_t CO_getUint16(const void *buf)
Get uint16_t value from memory buffer, see CO_getUint8.
Definition CO_driver.h:609
void CO_CANsetConfigurationMode(void *CANptr)
Request CAN configuration (stopped) mode and wait until it is set.
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.
static uint8_t CO_setUint32(void *buf, uint32_t value)
Write uint32_t value into memory buffer, see CO_setUint8.
Definition CO_driver.h:646
void CO_CANclearPendingSyncPDOs(CO_CANmodule_t *CANmodule)
Clear all synchronous TPDOs from CAN module transmit buffers.
void CO_CANmodule_disable(CO_CANmodule_t *CANmodule)
Switch off CANmodule.
void CO_CANsetNormalMode(CO_CANmodule_t *CANmodule)
Request CAN normal (operational) mode and wait until it is set.
static uint8_t CO_setUint16(void *buf, uint16_t value)
Write uint16_t value into memory buffer, see CO_setUint8.
Definition CO_driver.h:639
@ CO_ERROR_ILLEGAL_BAUDRATE
Illegal baudrate passed to function CO_CANmodule_init()
Definition CO_driver.h:454
@ CO_ERROR_WRONG_NMT_STATE
Command can't be processed in current state.
Definition CO_driver.h:466
@ CO_ERROR_TIMEOUT
Function timeout.
Definition CO_driver.h:453
@ CO_ERROR_CRC
CRC does not match.
Definition CO_driver.h:464
@ CO_ERROR_OUT_OF_MEMORY
Memory allocation failed.
Definition CO_driver.h:452
@ CO_ERROR_RX_MSG_LENGTH
Wrong receive message length.
Definition CO_driver.h:457
@ CO_ERROR_ILLEGAL_ARGUMENT
Error in function arguments.
Definition CO_driver.h:451
@ CO_ERROR_SYSCALL
Syscall failed.
Definition CO_driver.h:467
@ CO_ERROR_RX_PDO_LENGTH
Wrong receive PDO length.
Definition CO_driver.h:458
@ CO_ERROR_TX_PDO_WINDOW
Synchronous TPDO is outside window.
Definition CO_driver.h:460
@ CO_ERROR_INVALID_STATE
Driver not ready.
Definition CO_driver.h:468
@ CO_ERROR_TX_UNCONFIGURED
Transmit buffer was not configured properly.
Definition CO_driver.h:461
@ CO_ERROR_OD_PARAMETERS
Error in Object Dictionary parameters.
Definition CO_driver.h:462
@ CO_ERROR_TX_OVERFLOW
Previous message is still waiting, buffer full.
Definition CO_driver.h:459
@ CO_ERROR_RX_PDO_OVERFLOW
previous PDO was not processed yet
Definition CO_driver.h:456
@ CO_ERROR_DATA_CORRUPT
Stored data are corrupt.
Definition CO_driver.h:463
@ CO_ERROR_RX_OVERFLOW
Previous message was not processed yet.
Definition CO_driver.h:455
@ CO_ERROR_TX_BUSY
Sending rejected because driver is busy.
Definition CO_driver.h:465
@ CO_ERROR_NODE_ID_UNCONFIGURED_LSS
Node-id is in LSS unconfigured state.
Definition CO_driver.h:469
@ CO_ERROR_NO
Operation completed successfully.
Definition CO_driver.h:450
Complete CAN module object.
Definition CO_driver.h:268
volatile uint16_t CANtxCount
Number of messages in transmit buffer, which are waiting to be copied to the CAN module.
Definition CO_driver.h:285
volatile bool_t CANnormal
CAN module is in normal mode.
Definition CO_driver.h:275
uint16_t CANerrorStatus
CAN error status bitfield, see CAN error status bitmasks.
Definition CO_driver.h:274
uint16_t txSize
From CO_CANmodule_init()
Definition CO_driver.h:273
CO_CANrx_t * rxArray
From CO_CANmodule_init()
Definition CO_driver.h:270
uint16_t rxSize
From CO_CANmodule_init()
Definition CO_driver.h:271
volatile bool_t useCANrxFilters
Value different than zero indicates, that CAN module hardware filters are used for CAN reception.
Definition CO_driver.h:276
uint32_t errOld
Previous state of CAN errors.
Definition CO_driver.h:286
void * CANptr
From CO_CANmodule_init()
Definition CO_driver.h:269
volatile bool_t firstCANtxMessage
Equal to 1, when the first transmitted message (bootup message) is in CAN TX buffers.
Definition CO_driver.h:283
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:279
CO_CANtx_t * txArray
From CO_CANmodule_init()
Definition CO_driver.h:272
Configuration object for CAN received message for specific CANopenNode Object.
Definition CO_driver.h:218
uint16_t ident
Standard CAN Identifier (bits 0..10) + RTR (bit 11)
Definition CO_driver.h:219
void * object
CANopenNode Object initialized in from CO_CANrxBufferInit()
Definition CO_driver.h:221
uint16_t mask
Standard CAN Identifier mask with the same alignment as ident.
Definition CO_driver.h:220
Configuration object for CAN transmit message for specific CANopenNode Object.
Definition CO_driver.h:250
volatile bool_t bufferFull
True if previous message is still in the buffer.
Definition CO_driver.h:254
volatile bool_t syncFlag
Synchronous PDO messages has this flag set.
Definition CO_driver.h:255
uint8_t DLC
Length of CAN message.
Definition CO_driver.h:252
uint32_t ident
CAN identifier as aligned in CAN module.
Definition CO_driver.h:251
Data storage object for one entry.
Definition CO_driver.h:298
uint8_t attr
Attribute from CO_storage_attributes_t, always required.
Definition CO_driver.h:304
size_t eepromAddr
Address of data inside eeprom, set by init, required with Data storage in eeprom.
Definition CO_driver.h:310
size_t offset
Offset of next byte being updated by automatic storage, required with Data storage in eeprom.
Definition CO_driver.h:311
void * addr
Address of data to store, always required.
Definition CO_driver.h:299
uint8_t subIndexOD
Sub index in OD objects 1010 and 1011, from 2 to 127.
Definition CO_driver.h:301
size_t eepromAddrSignature
Address of entry signature inside eeprom, set by init, required with Data storage in eeprom.
Definition CO_driver.h:308
size_t len
Length of data to store, always required.
Definition CO_driver.h:300
uint16_t crc
CRC checksum of the data stored in eeprom, set on store, required with Data storage in eeprom.
Definition CO_driver.h:307
void * storageModule
Pointer to storage module, target system specific usage, required with Data storage in eeprom.
Definition CO_driver.h:305
void * additionalParameters
Additional target specific parameters, optional.
Definition CO_driver.h:312