第一版代码,为了在EEPROM保存参数的时候走STM32的CRC,让Codex修改了一下,现在的效果是无法存储,codex表示原因是CRC方法不同,修改到一半今天的额度使用完了,有待后续解决CRC的bug

This commit is contained in:
2026-02-28 17:36:05 +08:00
commit b2fedd58b2
212 changed files with 208290 additions and 0 deletions

View File

@@ -0,0 +1,274 @@
/*
* CANopen main program file.
*
* This file is a template for other microcontrollers.
*
* @file main_generic.c
* @author Hamed Jafarzadeh 2022
* Janez Paternoster 2021
* @copyright 2021 Janez Paternoster
*
* This file is part of CANopenNode, an opensource CANopen Stack.
* Project home page is <https://github.com/CANopenNode/CANopenNode>.
* For more information on CANopen see <http://www.can-cia.org/>.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include "CO_app_STM32.h"
#include "CANopen.h"
#include "main.h"
#include <stdio.h>
#include "CO_storageBlank.h"
#include "OD.h"
CANopenNodeSTM32 *
canopenNodeSTM32; // It will be set by canopen_app_init and will be used across app to get access to CANOpen objects
/* Printf function of CanOpen app */
#define log_printf(macropar_message, ...) printf(macropar_message, ##__VA_ARGS__)
/* default values for CO_CANopenInit() */
#define NMT_CONTROL \
CO_NMT_STARTUP_TO_OPERATIONAL \
| CO_NMT_ERR_ON_ERR_REG | CO_ERR_REG_GENERIC_ERR | CO_ERR_REG_COMMUNICATION
#define FIRST_HB_TIME 500
#define SDO_SRV_TIMEOUT_TIME 1000
#define SDO_CLI_TIMEOUT_TIME 500
#define SDO_CLI_BLOCK false
#define OD_STATUS_BITS NULL
/* Global variables and objects */
CO_t *CO = NULL; /* CANopen object */
// Global variables
uint32_t time_old, time_current;
CO_ReturnError_t err;
/* This function will basically setup the CANopen node */
int canopen_app_init(CANopenNodeSTM32 *_canopenNodeSTM32)
{
// Keep a copy global reference of canOpenSTM32 Object
canopenNodeSTM32 = _canopenNodeSTM32;
#if (CO_CONFIG_STORAGE) & CO_CONFIG_STORAGE_ENABLE
static CO_storage_t storage;
static CO_storage_entry_t storageEntries[] = {{.addr = &OD_PERSIST_COMM,
.len = sizeof(OD_PERSIST_COMM),
.subIndexOD = 2,
.attr = CO_storage_cmd | CO_storage_restore,
.addrNV = NULL}};
uint8_t storageEntriesCount = sizeof(storageEntries) / sizeof(storageEntries[0]);
uint32_t storageInitError = 0;
#endif
/* Allocate memory */
CO_config_t *config_ptr = NULL;
#ifdef CO_MULTIPLE_OD
/* example usage of CO_MULTIPLE_OD (but still single OD here) */
CO_config_t co_config = {0};
OD_INIT_CONFIG(co_config); /* helper macro from OD.h */
co_config.CNT_LEDS = 1;
co_config.CNT_LSS_SLV = 1;
config_ptr = &co_config;
#endif /* CO_MULTIPLE_OD */
uint32_t heapMemoryUsed;
CO = CO_new(config_ptr, &heapMemoryUsed);
if (CO == NULL)
{
log_printf("Error: Can't allocate memory\n");
return 1;
}
else
{
log_printf("Allocated %u bytes for CANopen objects\n", heapMemoryUsed);
}
canopenNodeSTM32->canOpenStack = CO;
#if (CO_CONFIG_STORAGE) & CO_CONFIG_STORAGE_ENABLE
err = CO_storageBlank_init(&storage, CO->CANmodule, OD_ENTRY_H1010_storeParameters,
OD_ENTRY_H1011_restoreDefaultParameters, storageEntries, storageEntriesCount,
&storageInitError);
if (err != CO_ERROR_NO && err != CO_ERROR_DATA_CORRUPT)
{
log_printf("Error: Storage %d\n", storageInitError);
return 2;
}
#endif
canopen_app_resetCommunication();
return 0;
}
int canopen_app_resetCommunication(void)
{
/* CANopen communication reset - initialize CANopen objects *******************/
log_printf("CANopenNode - Reset communication...\n");
/* Wait rt_thread. */
CO->CANmodule->CANnormal = false;
/* Enter CAN configuration. */
CO_CANsetConfigurationMode((void *)canopenNodeSTM32);
CO_CANmodule_disable(CO->CANmodule);
/* initialize CANopen */
err = CO_CANinit(CO, canopenNodeSTM32, 0); // Bitrate for STM32 microcontroller is being set in MXCube Settings
if (err != CO_ERROR_NO)
{
log_printf("Error: CAN initialization failed: %d\n", err);
return 1;
}
CO_LSS_address_t lssAddress = {.identity = {.vendorID = OD_PERSIST_COMM.x1018_identity.vendor_ID,
.productCode = OD_PERSIST_COMM.x1018_identity.productCode,
.revisionNumber = OD_PERSIST_COMM.x1018_identity.revisionNumber,
.serialNumber = OD_PERSIST_COMM.x1018_identity.serialNumber}};
err = CO_LSSinit(CO, &lssAddress, &canopenNodeSTM32->desiredNodeID, &canopenNodeSTM32->baudrate);
if (err != CO_ERROR_NO)
{
log_printf("Error: LSS slave initialization failed: %d\n", err);
return 2;
}
canopenNodeSTM32->activeNodeID = canopenNodeSTM32->desiredNodeID;
uint32_t errInfo = 0;
err = CO_CANopenInit(CO, /* CANopen object */
NULL, /* alternate NMT */
NULL, /* alternate em */
OD, /* Object dictionary */
OD_STATUS_BITS, /* Optional OD_statusBits */
NMT_CONTROL, /* CO_NMT_control_t */
FIRST_HB_TIME, /* firstHBTime_ms */
SDO_SRV_TIMEOUT_TIME, /* SDOserverTimeoutTime_ms */
SDO_CLI_TIMEOUT_TIME, /* SDOclientTimeoutTime_ms */
SDO_CLI_BLOCK, /* SDOclientBlockTransfer */
canopenNodeSTM32->activeNodeID, &errInfo);
if (err != CO_ERROR_NO && err != CO_ERROR_NODE_ID_UNCONFIGURED_LSS)
{
if (err == CO_ERROR_OD_PARAMETERS)
{
log_printf("Error: Object Dictionary entry 0x%X\n", errInfo);
}
else
{
log_printf("Error: CANopen initialization failed: %d\n", err);
}
return 3;
}
err = CO_CANopenInitPDO(CO, CO->em, OD, canopenNodeSTM32->activeNodeID, &errInfo);
if (err != CO_ERROR_NO && err != CO_ERROR_NODE_ID_UNCONFIGURED_LSS)
{
if (err == CO_ERROR_OD_PARAMETERS)
{
log_printf("Error: Object Dictionary entry 0x%X\n", errInfo);
}
else
{
log_printf("Error: PDO initialization failed: %d\n", err);
}
return 4;
}
/* Configure Timer interrupt function for execution every 1 millisecond */
HAL_TIM_Base_Start_IT(canopenNodeSTM32->timerHandle); // 1ms interrupt
/* Configure CAN transmit and receive interrupt */
/* Configure CANopen callbacks, etc */
if (!CO->nodeIdUnconfigured)
{
#if (CO_CONFIG_STORAGE) & CO_CONFIG_STORAGE_ENABLE
if (storageInitError != 0)
{
CO_errorReport(CO->em, CO_EM_NON_VOLATILE_MEMORY, CO_EMC_HARDWARE, storageInitError);
}
#endif
}
else
{
log_printf("CANopenNode - Node-id not initialized\n");
}
/* start CAN */
CO_CANsetNormalMode(CO->CANmodule);
log_printf("CANopenNode - Running...\n");
fflush(stdout);
time_old = time_current = HAL_GetTick();
return 0;
}
void canopen_app_process(void)
{
/* loop for normal program execution ******************************************/
/* get time difference since last function call */
time_current = HAL_GetTick();
if ((time_current - time_old) > 0)
{ // Make sure more than 1ms elapsed
/* CANopen process */
CO_NMT_reset_cmd_t reset_status;
uint32_t timeDifference_us = (time_current - time_old) * 1000;
time_old = time_current;
reset_status = CO_process(CO, false, timeDifference_us, NULL);
canopenNodeSTM32->outStatusLEDRed = CO_LED_RED(CO->LEDs, CO_LED_CANopen);
canopenNodeSTM32->outStatusLEDGreen = CO_LED_GREEN(CO->LEDs, CO_LED_CANopen);
if (reset_status == CO_RESET_COMM)
{
/* delete objects from memory */
HAL_TIM_Base_Stop_IT(canopenNodeSTM32->timerHandle);
CO_CANsetConfigurationMode((void *)canopenNodeSTM32);
CO_delete(CO);
log_printf("CANopenNode Reset Communication request\n");
canopen_app_init(canopenNodeSTM32); // Reset Communication routine
}
else if (reset_status == CO_RESET_APP)
{
log_printf("CANopenNode Device Reset\n");
HAL_NVIC_SystemReset(); // Reset the STM32 Microcontroller
}
}
}
/* Thread function executes in constant intervals, this function can be called from FreeRTOS tasks or Timers ********/
void canopen_app_interrupt(void)
{
CO_LOCK_OD(CO->CANmodule);
if (!CO->nodeIdUnconfigured && CO->CANmodule->CANnormal)
{
bool_t syncWas = false;
/* get time difference since last function call */
uint32_t timeDifference_us = 1000; // 1ms second
#if (CO_CONFIG_SYNC) & CO_CONFIG_SYNC_ENABLE
syncWas = CO_process_SYNC(CO, timeDifference_us, NULL);
#endif
#if (CO_CONFIG_PDO) & CO_CONFIG_RPDO_ENABLE
CO_process_RPDO(CO, syncWas, timeDifference_us, NULL);
#endif
#if (CO_CONFIG_PDO) & CO_CONFIG_TPDO_ENABLE
CO_process_TPDO(CO, syncWas, timeDifference_us, NULL);
#endif
}
CO_UNLOCK_OD(CO->CANmodule);
}

View File

@@ -0,0 +1,74 @@
/*
* CO_app_STM32.h
*
* Created on: Aug 7, 2022
* Author: hamed
*/
#ifndef CANOPENSTM32_CO_APP_STM32_H_
#define CANOPENSTM32_CO_APP_STM32_H_
#include "CANopen.h"
#include "main.h"
/* CANHandle : Pass in the CAN Handle to this function and it wil be used for all CAN Communications. It can be FDCan or CAN
* and CANOpenSTM32 Driver will take of care of handling that
* HWInitFunction : Pass in the function that initialize the CAN peripheral, usually MX_CAN_Init
* timerHandle : Pass in the timer that is going to be used for generating 1ms interrupt for tmrThread function,
* please note that CANOpenSTM32 Library will override HAL_TIM_PeriodElapsedCallback function, if you also need this function
* in your codes, please take required steps
*/
#ifdef __cplusplus
extern "C" {
#endif
typedef struct {
uint8_t
desiredNodeID; /*This is the Node ID that you ask the CANOpen stack to assign to your device, although it might not always
* be the final NodeID, after calling canopen_app_init() you should check ActiveNodeID of CANopenNodeSTM32 structure for assigned Node ID.
*/
uint8_t activeNodeID; /* Assigned Node ID */
uint16_t baudrate; /* This is the baudrate you've set in your CubeMX Configuration */
TIM_HandleTypeDef*
timerHandle; /*Pass in the timer that is going to be used for generating 1ms interrupt for tmrThread function,
* please note that CANOpenSTM32 Library will override HAL_TIM_PeriodElapsedCallback function, if you also need this function in your codes, please take required steps
*/
/* Pass in the CAN Handle to this function and it wil be used for all CAN Communications. It can be FDCan or CAN
* and CANOpenSTM32 Driver will take of care of handling that*/
#ifdef CO_STM32_FDCAN_Driver
FDCAN_HandleTypeDef* CANHandle;
#else
CAN_HandleTypeDef* CANHandle;
#endif
void (*HWInitFunction)(); /* Pass in the function that initialize the CAN peripheral, usually MX_CAN_Init */
uint8_t outStatusLEDGreen; // This will be updated by the stack - Use them for the LED management
uint8_t outStatusLEDRed; // This will be updated by the stack - Use them for the LED management
CO_t* canOpenStack;
} CANopenNodeSTM32;
// In order to use CANOpenSTM32, you'll have it have a canopenNodeSTM32 structure somewhere in your codes, it is usually residing in CO_app_STM32.c
extern CANopenNodeSTM32* canopenNodeSTM32;
/* This function will initialize the required CANOpen Stack objects, allocate the memory and prepare stack for communication reset*/
int canopen_app_init(CANopenNodeSTM32* canopenSTM32);
/* This function will reset the CAN communication periperhal and also the CANOpen stack variables */
int canopen_app_resetCommunication(void);
/* This function will check the input buffers and any outstanding tasks that are not time critical, this function should be called regurarly from your code (i.e from your while(1))*/
void canopen_app_process(void);
/* Thread function executes in constant intervals, this function can be called from FreeRTOS tasks or Timers ********/
void canopen_app_interrupt(void);
#ifdef __cplusplus
}
#endif /* __cplusplus */
#endif /* CANOPENSTM32_CO_APP_STM32_H_ */

View File

@@ -0,0 +1,777 @@
/*
* CAN module object for STM32 (FD)CAN peripheral IP.
*
* This file is a template for other microcontrollers.
*
* @file CO_driver.c
* @ingroup CO_driver
* @author Hamed Jafarzadeh 2022
* Tilen Marjerle 2021
* Janez Paternoster 2020
* @copyright 2004 - 2020 Janez Paternoster
*
* This file is part of CANopenNode, an opensource CANopen Stack.
* Project home page is <https://github.com/CANopenNode/CANopenNode>.
* For more information on CANopen see <http://www.can-cia.org/>.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* Implementation Author: Tilen Majerle <tilen@majerle.eu>
*/
#include "301/CO_driver.h"
#include "CO_app_STM32.h"
#include "stdio.h"
/* Local CAN module object */
static CO_CANmodule_t *CANModule_local = NULL; /* Local instance of global CAN module */
/* CAN masks for identifiers */
#define CANID_MASK 0x07FF /*!< CAN standard ID mask */
#define FLAG_RTR 0x8000 /*!< RTR flag, part of identifier */
/******************************************************************************/
void CO_CANsetConfigurationMode(void *CANptr)
{
/* Put CAN module in configuration mode */
if (CANptr != NULL)
{
#ifdef CO_STM32_FDCAN_Driver
HAL_FDCAN_Stop(((CANopenNodeSTM32 *)CANptr)->CANHandle);
#else
HAL_CAN_Stop(((CANopenNodeSTM32 *)CANptr)->CANHandle);
#endif
}
}
/******************************************************************************/
void CO_CANsetNormalMode(CO_CANmodule_t *CANmodule)
{
/* Put CAN module in normal mode */
if (CANmodule->CANptr != NULL)
{
#ifdef CO_STM32_FDCAN_Driver
if (HAL_FDCAN_Start(((CANopenNodeSTM32 *)CANmodule->CANptr)->CANHandle) == HAL_OK)
#else
if (HAL_CAN_Start(((CANopenNodeSTM32 *)CANmodule->CANptr)->CANHandle) == HAL_OK)
#endif
{
CANmodule->CANnormal = true;
}
}
}
/******************************************************************************/
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)
{
/* verify arguments */
if (CANmodule == NULL || rxArray == NULL || txArray == NULL)
{
return CO_ERROR_ILLEGAL_ARGUMENT;
}
/* Hold CANModule variable */
CANmodule->CANptr = CANptr;
/* Keep a local copy of CANModule */
CANModule_local = CANmodule;
/* Configure object variables */
CANmodule->rxArray = rxArray;
CANmodule->rxSize = rxSize;
CANmodule->txArray = txArray;
CANmodule->txSize = txSize;
CANmodule->CANerrorStatus = 0;
CANmodule->CANnormal = false;
CANmodule->useCANrxFilters = false; /* Do not use HW filters */
CANmodule->bufferInhibitFlag = false;
CANmodule->firstCANtxMessage = true;
CANmodule->CANtxCount = 0U;
CANmodule->errOld = 0U;
/* Reset all variables */
for (uint16_t i = 0U; i < rxSize; i++)
{
rxArray[i].ident = 0U;
rxArray[i].mask = 0xFFFFU;
rxArray[i].object = NULL;
rxArray[i].CANrx_callback = NULL;
}
for (uint16_t i = 0U; i < txSize; i++)
{
txArray[i].bufferFull = false;
}
/***************************************/
/* STM32 related configuration */
/***************************************/
((CANopenNodeSTM32 *)CANptr)->HWInitFunction();
/*
* Configure global filter that is used as last check if message did not pass any of other filters:
*
* We do not rely on hardware filters in this example
* and are performing software filters instead
*
* Accept non-matching standard ID messages
* Reject non-matching extended ID messages
*/
#ifdef CO_STM32_FDCAN_Driver
if (HAL_FDCAN_ConfigGlobalFilter(((CANopenNodeSTM32 *)CANptr)->CANHandle, FDCAN_ACCEPT_IN_RX_FIFO0, FDCAN_REJECT,
FDCAN_FILTER_REMOTE, FDCAN_FILTER_REMOTE) != HAL_OK)
{
return CO_ERROR_ILLEGAL_ARGUMENT;
}
#else
CAN_FilterTypeDef FilterConfig;
#if defined(CAN)
FilterConfig.FilterBank = 0;
#else
if (((CAN_HandleTypeDef *)((CANopenNodeSTM32 *)CANmodule->CANptr)->CANHandle)->Instance == CAN1)
{
FilterConfig.FilterBank = 0;
}
else
{
FilterConfig.FilterBank = 14;
}
#endif
FilterConfig.FilterMode = CAN_FILTERMODE_IDMASK;
FilterConfig.FilterScale = CAN_FILTERSCALE_32BIT;
FilterConfig.FilterIdHigh = 0x0;
FilterConfig.FilterIdLow = 0x0;
FilterConfig.FilterMaskIdHigh = 0x0;
FilterConfig.FilterMaskIdLow = 0x0;
FilterConfig.FilterFIFOAssignment = CAN_RX_FIFO0;
FilterConfig.FilterActivation = ENABLE;
FilterConfig.SlaveStartFilterBank = 14;
if (HAL_CAN_ConfigFilter(((CANopenNodeSTM32 *)CANptr)->CANHandle, &FilterConfig) != HAL_OK)
{
return CO_ERROR_ILLEGAL_ARGUMENT;
}
#endif
/* Enable notifications */
/* Activate the CAN notification interrupts */
#ifdef CO_STM32_FDCAN_Driver
if (HAL_FDCAN_ActivateNotification(((CANopenNodeSTM32 *)CANptr)->CANHandle,
0 | FDCAN_IT_RX_FIFO0_NEW_MESSAGE | FDCAN_IT_RX_FIFO1_NEW_MESSAGE | FDCAN_IT_TX_COMPLETE | FDCAN_IT_TX_FIFO_EMPTY | FDCAN_IT_BUS_OFF | FDCAN_IT_ARB_PROTOCOL_ERROR | FDCAN_IT_DATA_PROTOCOL_ERROR | FDCAN_IT_ERROR_PASSIVE | FDCAN_IT_ERROR_WARNING,
0xFFFFFFFF) != HAL_OK)
{
return CO_ERROR_ILLEGAL_ARGUMENT;
}
#else
if (HAL_CAN_ActivateNotification(((CANopenNodeSTM32 *)CANptr)->CANHandle, CAN_IT_RX_FIFO0_MSG_PENDING | CAN_IT_RX_FIFO1_MSG_PENDING | CAN_IT_TX_MAILBOX_EMPTY) != HAL_OK)
{
return CO_ERROR_ILLEGAL_ARGUMENT;
}
#endif
return CO_ERROR_NO;
}
/******************************************************************************/
void CO_CANmodule_disable(CO_CANmodule_t *CANmodule)
{
if (CANmodule != NULL && CANmodule->CANptr != NULL)
{
#ifdef CO_STM32_FDCAN_Driver
HAL_FDCAN_Stop(((CANopenNodeSTM32 *)CANmodule->CANptr)->CANHandle);
#else
HAL_CAN_Stop(((CANopenNodeSTM32 *)CANmodule->CANptr)->CANHandle);
#endif
}
}
/******************************************************************************/
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))
{
CO_ReturnError_t ret = CO_ERROR_NO;
if (CANmodule != NULL && object != NULL && CANrx_callback != NULL && index < CANmodule->rxSize)
{
CO_CANrx_t *buffer = &CANmodule->rxArray[index];
/* Configure object variables */
buffer->object = object;
buffer->CANrx_callback = CANrx_callback;
/*
* Configure global identifier, including RTR bit
*
* This is later used for RX operation match case
*/
buffer->ident = (ident & CANID_MASK) | (rtr ? FLAG_RTR : 0x00);
buffer->mask = (mask & CANID_MASK) | FLAG_RTR;
/* Set CAN hardware module filter and mask. */
if (CANmodule->useCANrxFilters)
{
__NOP();
}
}
else
{
ret = CO_ERROR_ILLEGAL_ARGUMENT;
}
return ret;
}
/******************************************************************************/
CO_CANtx_t *
CO_CANtxBufferInit(CO_CANmodule_t *CANmodule, uint16_t index, uint16_t ident, bool_t rtr, uint8_t noOfBytes,
bool_t syncFlag)
{
CO_CANtx_t *buffer = NULL;
if (CANmodule != NULL && index < CANmodule->txSize)
{
buffer = &CANmodule->txArray[index];
/* CAN identifier, DLC and rtr, bit aligned with CAN module transmit buffer */
buffer->ident = ((uint32_t)ident & CANID_MASK) | ((uint32_t)(rtr ? FLAG_RTR : 0x00));
buffer->DLC = noOfBytes;
buffer->bufferFull = false;
buffer->syncFlag = syncFlag;
}
return buffer;
}
/**
* \brief Send CAN message to network
* This function must be called with atomic access.
*
* \param[in] CANmodule: CAN module instance
* \param[in] buffer: Pointer to buffer to transmit
*/
static uint8_t
prv_send_can_message(CO_CANmodule_t *CANmodule, CO_CANtx_t *buffer)
{
uint8_t success = 0;
/* Check if TX FIFO is ready to accept more messages */
#ifdef CO_STM32_FDCAN_Driver
static FDCAN_TxHeaderTypeDef tx_hdr;
if (HAL_FDCAN_GetTxFifoFreeLevel(((CANopenNodeSTM32 *)CANmodule->CANptr)->CANHandle) > 0)
{
/*
* RTR flag is part of identifier value
* hence it needs to be properly decoded
*/
tx_hdr.Identifier = buffer->ident & CANID_MASK;
tx_hdr.TxFrameType = (buffer->ident & FLAG_RTR) ? FDCAN_REMOTE_FRAME : FDCAN_DATA_FRAME;
tx_hdr.IdType = FDCAN_STANDARD_ID;
tx_hdr.FDFormat = FDCAN_CLASSIC_CAN;
tx_hdr.BitRateSwitch = FDCAN_BRS_OFF;
tx_hdr.MessageMarker = 0;
tx_hdr.ErrorStateIndicator = FDCAN_ESI_ACTIVE;
tx_hdr.TxEventFifoControl = FDCAN_NO_TX_EVENTS;
switch (buffer->DLC)
{
case 0:
tx_hdr.DataLength = FDCAN_DLC_BYTES_0;
break;
case 1:
tx_hdr.DataLength = FDCAN_DLC_BYTES_1;
break;
case 2:
tx_hdr.DataLength = FDCAN_DLC_BYTES_2;
break;
case 3:
tx_hdr.DataLength = FDCAN_DLC_BYTES_3;
break;
case 4:
tx_hdr.DataLength = FDCAN_DLC_BYTES_4;
break;
case 5:
tx_hdr.DataLength = FDCAN_DLC_BYTES_5;
break;
case 6:
tx_hdr.DataLength = FDCAN_DLC_BYTES_6;
break;
case 7:
tx_hdr.DataLength = FDCAN_DLC_BYTES_7;
break;
case 8:
tx_hdr.DataLength = FDCAN_DLC_BYTES_8;
break;
default: /* Hard error... */
break;
}
/* Now add message to FIFO. Should not fail */
success =
HAL_FDCAN_AddMessageToTxFifoQ(((CANopenNodeSTM32 *)CANmodule->CANptr)->CANHandle, &tx_hdr, buffer->data) == HAL_OK;
}
#else
static CAN_TxHeaderTypeDef tx_hdr;
/* Check if TX FIFO is ready to accept more messages */
if (HAL_CAN_GetTxMailboxesFreeLevel(((CANopenNodeSTM32 *)CANmodule->CANptr)->CANHandle) > 0)
{
/*
* RTR flag is part of identifier value
* hence it needs to be properly decoded
*/
tx_hdr.ExtId = 0u;
tx_hdr.IDE = CAN_ID_STD;
tx_hdr.DLC = buffer->DLC;
tx_hdr.StdId = buffer->ident & CANID_MASK;
tx_hdr.RTR = (buffer->ident & FLAG_RTR) ? CAN_RTR_REMOTE : CAN_RTR_DATA;
uint32_t TxMailboxNum; // Transmission MailBox number
/* Now add message to FIFO. Should not fail */
success = HAL_CAN_AddTxMessage(((CANopenNodeSTM32 *)CANmodule->CANptr)->CANHandle, &tx_hdr, buffer->data,
&TxMailboxNum) == HAL_OK;
}
#endif
return success;
}
/******************************************************************************/
CO_ReturnError_t
CO_CANsend(CO_CANmodule_t *CANmodule, CO_CANtx_t *buffer)
{
CO_ReturnError_t err = CO_ERROR_NO;
/* Verify overflow */
if (buffer->bufferFull)
{
if (!CANmodule->firstCANtxMessage)
{
/* don't set error, if bootup message is still on buffers */
CANmodule->CANerrorStatus |= CO_CAN_ERRTX_OVERFLOW;
}
err = CO_ERROR_TX_OVERFLOW;
}
/*
* Send message to CAN network
*
* Lock interrupts for atomic operation
*/
CO_LOCK_CAN_SEND(CANmodule);
if (prv_send_can_message(CANmodule, buffer))
{
CANmodule->bufferInhibitFlag = buffer->syncFlag;
}
else
{
/* Only increment count if buffer wasn't already full */
if (!buffer->bufferFull)
{
buffer->bufferFull = true;
CANmodule->CANtxCount++;
}
}
CO_UNLOCK_CAN_SEND(CANmodule);
return err;
}
/******************************************************************************/
void CO_CANclearPendingSyncPDOs(CO_CANmodule_t *CANmodule)
{
uint32_t tpdoDeleted = 0U;
CO_LOCK_CAN_SEND(CANmodule);
/* Abort message from CAN module, if there is synchronous TPDO.
* Take special care with this functionality. */
if (/*messageIsOnCanBuffer && */ CANmodule->bufferInhibitFlag)
{
/* clear TXREQ */
CANmodule->bufferInhibitFlag = false;
tpdoDeleted = 1U;
}
/* delete also pending synchronous TPDOs in TX buffers */
if (CANmodule->CANtxCount > 0)
{
for (uint16_t i = CANmodule->txSize; i > 0U; --i)
{
if (CANmodule->txArray[i].bufferFull)
{
if (CANmodule->txArray[i].syncFlag)
{
CANmodule->txArray[i].bufferFull = false;
CANmodule->CANtxCount--;
tpdoDeleted = 2U;
}
}
}
}
CO_UNLOCK_CAN_SEND(CANmodule);
if (tpdoDeleted)
{
CANmodule->CANerrorStatus |= CO_CAN_ERRTX_PDO_LATE;
}
}
/******************************************************************************/
/* Get error counters from the module. If necessary, function may use
* different way to determine errors. */
static uint16_t rxErrors = 0, txErrors = 0, overflow = 0;
void CO_CANmodule_process(CO_CANmodule_t *CANmodule)
{
uint32_t err = 0;
// CANOpen just care about Bus_off, Warning, Passive and Overflow
// I didn't find overflow error register in STM32, if you find it please let me know
#ifdef CO_STM32_FDCAN_Driver
err = ((FDCAN_HandleTypeDef *)((CANopenNodeSTM32 *)CANmodule->CANptr)->CANHandle)->Instance->PSR & (FDCAN_PSR_BO | FDCAN_PSR_EW | FDCAN_PSR_EP);
if (CANmodule->errOld != err)
{
uint16_t status = CANmodule->CANerrorStatus;
CANmodule->errOld = err;
if (err & FDCAN_PSR_BO)
{
status |= CO_CAN_ERRTX_BUS_OFF;
// In this driver we expect that the controller is automatically handling the protocol exceptions.
}
else
{
/* recalculate CANerrorStatus, first clear some flags */
status &= 0xFFFF ^ (CO_CAN_ERRTX_BUS_OFF | CO_CAN_ERRRX_WARNING | CO_CAN_ERRRX_PASSIVE | CO_CAN_ERRTX_WARNING | CO_CAN_ERRTX_PASSIVE);
if (err & FDCAN_PSR_EW)
{
status |= CO_CAN_ERRRX_WARNING | CO_CAN_ERRTX_WARNING;
}
if (err & FDCAN_PSR_EP)
{
status |= CO_CAN_ERRRX_PASSIVE | CO_CAN_ERRTX_PASSIVE;
}
}
CANmodule->CANerrorStatus = status;
}
#else
err = ((CAN_HandleTypeDef *)((CANopenNodeSTM32 *)CANmodule->CANptr)->CANHandle)->Instance->ESR & (CAN_ESR_BOFF | CAN_ESR_EPVF | CAN_ESR_EWGF);
// uint32_t esrVal = ((CAN_HandleTypeDef*)((CANopenNodeSTM32*)CANmodule->CANptr)->CANHandle)->Instance->ESR; Debug purpose
if (CANmodule->errOld != err)
{
uint16_t status = CANmodule->CANerrorStatus;
CANmodule->errOld = err;
if (err & CAN_ESR_BOFF)
{
status |= CO_CAN_ERRTX_BUS_OFF;
// In this driver, we assume that auto bus recovery is activated ! so this error will eventually handled automatically.
}
else
{
/* recalculate CANerrorStatus, first clear some flags */
status &= 0xFFFF ^ (CO_CAN_ERRTX_BUS_OFF | CO_CAN_ERRRX_WARNING | CO_CAN_ERRRX_PASSIVE | CO_CAN_ERRTX_WARNING | CO_CAN_ERRTX_PASSIVE);
if (err & CAN_ESR_EWGF)
{
status |= CO_CAN_ERRRX_WARNING | CO_CAN_ERRTX_WARNING;
}
if (err & CAN_ESR_EPVF)
{
status |= CO_CAN_ERRRX_PASSIVE | CO_CAN_ERRTX_PASSIVE;
}
}
CANmodule->CANerrorStatus = status;
}
#endif
}
/**
* \brief Read message from RX FIFO
* \param hfdcan: pointer to an FDCAN_HandleTypeDef structure that contains
* the configuration information for the specified FDCAN.
* \param[in] fifo: Fifo number to use for read
* \param[in] fifo_isrs: List of interrupts for respected FIFO
*/
#ifdef CO_STM32_FDCAN_Driver
static void
prv_read_can_received_msg(FDCAN_HandleTypeDef *hfdcan, uint32_t fifo, uint32_t fifo_isrs)
#else
static void
prv_read_can_received_msg(CAN_HandleTypeDef *hcan, uint32_t fifo, uint32_t fifo_isrs)
#endif
{
CO_CANrxMsg_t rcvMsg;
CO_CANrx_t *buffer = NULL; /* receive message buffer from CO_CANmodule_t object. */
uint16_t index; /* index of received message */
uint32_t rcvMsgIdent; /* identifier of the received message */
uint8_t messageFound = 0;
#ifdef CO_STM32_FDCAN_Driver
static FDCAN_RxHeaderTypeDef rx_hdr;
/* Read received message from FIFO */
if (HAL_FDCAN_GetRxMessage(hfdcan, fifo, &rx_hdr, rcvMsg.data) != HAL_OK)
{
return;
}
/* Setup identifier (with RTR) and length */
rcvMsg.ident = rx_hdr.Identifier | (rx_hdr.RxFrameType == FDCAN_REMOTE_FRAME ? FLAG_RTR : 0x00);
switch (rx_hdr.DataLength)
{
case FDCAN_DLC_BYTES_0:
rcvMsg.dlc = 0;
break;
case FDCAN_DLC_BYTES_1:
rcvMsg.dlc = 1;
break;
case FDCAN_DLC_BYTES_2:
rcvMsg.dlc = 2;
break;
case FDCAN_DLC_BYTES_3:
rcvMsg.dlc = 3;
break;
case FDCAN_DLC_BYTES_4:
rcvMsg.dlc = 4;
break;
case FDCAN_DLC_BYTES_5:
rcvMsg.dlc = 5;
break;
case FDCAN_DLC_BYTES_6:
rcvMsg.dlc = 6;
break;
case FDCAN_DLC_BYTES_7:
rcvMsg.dlc = 7;
break;
case FDCAN_DLC_BYTES_8:
rcvMsg.dlc = 8;
break;
default:
rcvMsg.dlc = 0;
break; /* Invalid length when more than 8 */
}
rcvMsgIdent = rcvMsg.ident;
#else
static CAN_RxHeaderTypeDef rx_hdr;
/* Read received message from FIFO */
if (HAL_CAN_GetRxMessage(hcan, fifo, &rx_hdr, rcvMsg.data) != HAL_OK)
{
return;
}
/* Setup identifier (with RTR) and length */
rcvMsg.ident = rx_hdr.StdId | (rx_hdr.RTR == CAN_RTR_REMOTE ? FLAG_RTR : 0x00);
rcvMsg.dlc = rx_hdr.DLC;
rcvMsgIdent = rcvMsg.ident;
#endif
/*
* Hardware filters are not used for the moment
* \todo: Implement hardware filters...
*/
if (CANModule_local->useCANrxFilters)
{
__BKPT(0);
}
else
{
/*
* We are not using hardware filters, hence it is necessary
* to manually match received message ID with all buffers
*/
buffer = CANModule_local->rxArray;
for (index = CANModule_local->rxSize; index > 0U; --index, ++buffer)
{
if (((rcvMsgIdent ^ buffer->ident) & buffer->mask) == 0U)
{
messageFound = 1;
break;
}
}
}
/* Call specific function, which will process the message */
if (messageFound && buffer != NULL && buffer->CANrx_callback != NULL)
{
buffer->CANrx_callback(buffer->object, (void *)&rcvMsg);
}
}
#ifdef CO_STM32_FDCAN_Driver
/**
* \brief Rx FIFO 0 callback.
* \param[in] hfdcan: pointer to an FDCAN_HandleTypeDef structure that contains
* the configuration information for the specified FDCAN.
* \param[in] RxFifo0ITs: indicates which Rx FIFO 0 interrupts are signaled.
*/
void HAL_FDCAN_RxFifo0Callback(FDCAN_HandleTypeDef *hfdcan, uint32_t RxFifo0ITs)
{
if (RxFifo0ITs & FDCAN_IT_RX_FIFO0_NEW_MESSAGE)
{
prv_read_can_received_msg(hfdcan, FDCAN_RX_FIFO0, RxFifo0ITs);
}
}
/**
* \brief Rx FIFO 1 callback.
* \param[in] hfdcan: pointer to an FDCAN_HandleTypeDef structure that contains
* the configuration information for the specified FDCAN.
* \param[in] RxFifo1ITs: indicates which Rx FIFO 0 interrupts are signaled.
*/
void HAL_FDCAN_RxFifo1Callback(FDCAN_HandleTypeDef *hfdcan, uint32_t RxFifo1ITs)
{
if (RxFifo1ITs & FDCAN_IT_RX_FIFO1_NEW_MESSAGE)
{
prv_read_can_received_msg(hfdcan, FDCAN_RX_FIFO1, RxFifo1ITs);
}
}
/**
* \brief TX buffer has been well transmitted callback
* \param[in] hfdcan: pointer to an FDCAN_HandleTypeDef structure that contains
* the configuration information for the specified FDCAN.
* \param[in] BufferIndexes: Bits of successfully sent TX buffers
*/
void HAL_FDCAN_TxBufferCompleteCallback(FDCAN_HandleTypeDef *hfdcan, uint32_t BufferIndexes)
{
CANModule_local->firstCANtxMessage = false; /* First CAN message (bootup) was sent successfully */
CANModule_local->bufferInhibitFlag = false; /* Clear flag from previous message */
if (CANModule_local->CANtxCount > 0U)
{ /* Are there any new messages waiting to be send */
CO_CANtx_t *buffer = &CANModule_local->txArray[0]; /* Start with first buffer handle */
uint16_t i;
/*
* Try to send more buffers, process all empty ones
*
* This function is always called from interrupt,
* however to make sure no preemption can happen, interrupts are anyway locked
* (unless you can guarantee no higher priority interrupt will try to access to FDCAN instance and send data,
* then no need to lock interrupts..)
*/
CO_LOCK_CAN_SEND(CANModule_local);
for (i = CANModule_local->txSize; i > 0U; --i, ++buffer)
{
/* Try to send message */
if (buffer->bufferFull)
{
if (prv_send_can_message(CANModule_local, buffer))
{
buffer->bufferFull = false;
CANModule_local->CANtxCount--;
CANModule_local->bufferInhibitFlag = buffer->syncFlag;
}
else
{
break; // if we could not send the message, break out of the loop (the tx buffers are full)
}
}
}
CO_UNLOCK_CAN_SEND(CANModule_local);
}
}
#else
/**
* \brief Rx FIFO 0 callback.
* \param[in] hcan: pointer to an CAN_HandleTypeDef structure that contains
* the configuration information for the specified CAN.
*/
void HAL_CAN_RxFifo0MsgPendingCallback(CAN_HandleTypeDef *hcan)
{
prv_read_can_received_msg(hcan, CAN_RX_FIFO0, 0);
}
/**
* \brief Rx FIFO 1 callback.
* \param[in] hcan: pointer to an CAN_HandleTypeDef structure that contains
* the configuration information for the specified CAN.
*/
void HAL_CAN_RxFifo1MsgPendingCallback(CAN_HandleTypeDef *hcan)
{
prv_read_can_received_msg(hcan, CAN_RX_FIFO1, 0);
}
/**
* \brief TX buffer has been well transmitted callback
* \param[in] hcan: pointer to an CAN_HandleTypeDef structure that contains
* the configuration information for the specified CAN.
* \param[in] MailboxNumber: the mailbox number that has been transmitted
*/
void CO_CANinterrupt_TX(CO_CANmodule_t *CANmodule, uint32_t MailboxNumber)
{
CANmodule->firstCANtxMessage = false; /* First CAN message (bootup) was sent successfully */
CANmodule->bufferInhibitFlag = false; /* Clear flag from previous message */
if (CANmodule->CANtxCount > 0U)
{ /* Are there any new messages waiting to be send */
CO_CANtx_t *buffer = &CANmodule->txArray[0]; /* Start with first buffer handle */
uint16_t i;
/*
* Try to send more buffers, process all empty ones
*
* This function is always called from interrupt,
* however to make sure no preemption can happen, interrupts are anyway locked
* (unless you can guarantee no higher priority interrupt will try to access to CAN instance and send data,
* then no need to lock interrupts..)
*/
CO_LOCK_CAN_SEND(CANmodule);
for (i = CANmodule->txSize; i > 0U; --i, ++buffer)
{
/* Try to send message */
if (buffer->bufferFull)
{
if (prv_send_can_message(CANmodule, buffer))
{
buffer->bufferFull = false;
CANmodule->CANtxCount--;
CANmodule->bufferInhibitFlag = buffer->syncFlag;
}
else
break; // if we could not send the message, break out of the loop (the tx buffers are full)
}
}
CO_UNLOCK_CAN_SEND(CANmodule);
}
}
void HAL_CAN_TxMailbox0CompleteCallback(CAN_HandleTypeDef *hcan)
{
CO_CANinterrupt_TX(CANModule_local, CAN_TX_MAILBOX0);
}
void HAL_CAN_TxMailbox1CompleteCallback(CAN_HandleTypeDef *hcan)
{
CO_CANinterrupt_TX(CANModule_local, CAN_TX_MAILBOX0);
}
void HAL_CAN_TxMailbox2CompleteCallback(CAN_HandleTypeDef *hcan)
{
CO_CANinterrupt_TX(CANModule_local, CAN_TX_MAILBOX0);
}
#endif

View File

@@ -0,0 +1,183 @@
/*
* Device and application specific definitions for CANopenNode.
*
* @file CO_driver_target.h
* @author Hamed Jafarzadeh 2022
* Tilen Marjerle 2021
* Janez Paternoster 2020
* @copyright 2004 - 2020 Janez Paternoster
*
* This file is part of CANopenNode, an opensource CANopen Stack.
* Project home page is <https://github.com/CANopenNode/CANopenNode>.
* For more information on CANopen see <http://www.can-cia.org/>.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#ifndef CO_DRIVER_TARGET_H
#define CO_DRIVER_TARGET_H
/* This file contains device and application specific definitions.
* It is included from CO_driver.h, which contains documentation
* for common definitions below. */
#include "main.h"
#include <stdbool.h>
#include <stddef.h>
#include <stdint.h>
// Determining the CANOpen Driver
#if defined(FDCAN) || defined(FDCAN1) || defined(FDCAN2) || defined(FDCAN3)
#define CO_STM32_FDCAN_Driver 1
#elif defined(CAN) || defined(CAN1) || defined(CAN2) || defined(CAN3)
#define CO_STM32_CAN_Driver 1
#else
#error This STM32 Do not support CAN or FDCAN
#endif
#undef CO_CONFIG_STORAGE_ENABLE // We don't need Storage option, implement based on your use case and remove this line from here
#ifdef CO_DRIVER_CUSTOM
#include "CO_driver_custom.h"
#endif
#ifdef __cplusplus
extern "C" {
#endif
/* Stack configuration override default values.
* For more information see file CO_config.h. */
/* Basic definitions. If big endian, CO_SWAP_xx macros must swap bytes. */
#define CO_LITTLE_ENDIAN
#define CO_SWAP_16(x) x
#define CO_SWAP_32(x) x
#define CO_SWAP_64(x) x
/* NULL is defined in stddef.h */
/* true and false are defined in stdbool.h */
/* int8_t to uint64_t are defined in stdint.h */
typedef uint_fast8_t bool_t;
typedef float float32_t;
typedef double float64_t;
/**
* \brief CAN RX message for platform
*
* This is platform specific one
*/
typedef struct {
uint32_t ident; /*!< Standard identifier */
uint8_t dlc; /*!< Data length */
uint8_t data[8]; /*!< Received data */
} CO_CANrxMsg_t;
/* Access to received CAN message */
#define CO_CANrxMsg_readIdent(msg) ((uint16_t)(((CO_CANrxMsg_t*)(msg)))->ident)
#define CO_CANrxMsg_readDLC(msg) ((uint8_t)(((CO_CANrxMsg_t*)(msg)))->dlc)
#define CO_CANrxMsg_readData(msg) ((uint8_t*)(((CO_CANrxMsg_t*)(msg)))->data)
/* Received message object */
typedef struct {
uint16_t ident;
uint16_t mask;
void* object;
void (*CANrx_callback)(void* object, void* message);
} CO_CANrx_t;
/* Transmit message object */
typedef struct {
uint32_t ident;
uint8_t DLC;
uint8_t data[8];
volatile bool_t bufferFull;
volatile bool_t syncFlag;
} CO_CANtx_t;
/* CAN module object */
typedef struct {
void* CANptr;
CO_CANrx_t* rxArray;
uint16_t rxSize;
CO_CANtx_t* txArray;
uint16_t txSize;
uint16_t CANerrorStatus;
volatile bool_t CANnormal;
volatile bool_t useCANrxFilters;
volatile bool_t bufferInhibitFlag;
volatile bool_t firstCANtxMessage;
volatile uint16_t CANtxCount;
uint32_t errOld;
/* STM32 specific features */
uint32_t primask_send; /* Primask register for interrupts for send operation */
uint32_t primask_emcy; /* Primask register for interrupts for emergency operation */
uint32_t primask_od; /* Primask register for interrupts for send operation */
} CO_CANmodule_t;
/* Data storage object for one entry */
typedef struct {
void* addr;
size_t len;
uint8_t subIndexOD;
uint8_t attr;
/* Additional variables (target specific) */
void* addrNV;
} CO_storage_entry_t;
/* (un)lock critical section in CO_CANsend() */
// Why disabling the whole Interrupt
#define CO_LOCK_CAN_SEND(CAN_MODULE) \
do { \
(CAN_MODULE)->primask_send = __get_PRIMASK(); \
__disable_irq(); \
} while (0)
#define CO_UNLOCK_CAN_SEND(CAN_MODULE) __set_PRIMASK((CAN_MODULE)->primask_send)
/* (un)lock critical section in CO_errorReport() or CO_errorReset() */
#define CO_LOCK_EMCY(CAN_MODULE) \
do { \
(CAN_MODULE)->primask_emcy = __get_PRIMASK(); \
__disable_irq(); \
} while (0)
#define CO_UNLOCK_EMCY(CAN_MODULE) __set_PRIMASK((CAN_MODULE)->primask_emcy)
/* (un)lock critical section when accessing Object Dictionary */
#define CO_LOCK_OD(CAN_MODULE) \
do { \
(CAN_MODULE)->primask_od = __get_PRIMASK(); \
__disable_irq(); \
} while (0)
#define CO_UNLOCK_OD(CAN_MODULE) __set_PRIMASK((CAN_MODULE)->primask_od)
/* Synchronization between CAN receive and message processing threads. */
#define CO_MemoryBarrier()
#define CO_FLAG_READ(rxNew) ((rxNew) != NULL)
#define CO_FLAG_SET(rxNew) \
do { \
CO_MemoryBarrier(); \
rxNew = (void*)1L; \
} while (0)
#define CO_FLAG_CLEAR(rxNew) \
do { \
CO_MemoryBarrier(); \
rxNew = NULL; \
} while (0)
#ifdef __cplusplus
}
#endif /* __cplusplus */
#endif /* CO_DRIVER_TARGET_H */

View File

@@ -0,0 +1,96 @@
/*
* CANopen Object Dictionary storage object (blank example).
*
* @file CO_storageBlank.c
* @author Janez Paternoster
* @copyright 2021 Janez Paternoster
*
* This file is part of CANopenNode, an opensource CANopen Stack.
* Project home page is <https://github.com/CANopenNode/CANopenNode>.
* For more information on CANopen see <http://www.can-cia.org/>.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include "CO_storageBlank.h"
#if (CO_CONFIG_STORAGE) & CO_CONFIG_STORAGE_ENABLE
/*
* Function for writing data on "Store parameters" command - OD object 1010
*
* For more information see file CO_storage.h, CO_storage_entry_t.
*/
static ODR_t
storeBlank(CO_storage_entry_t* entry, CO_CANmodule_t* CANmodule) {
/* Open a file and write data to it */
/* file = open(entry->pathToFileOrPointerToMemory); */
CO_LOCK_OD(CANmodule);
/* write(entry->addr, entry->len, file); */
CO_UNLOCK_OD(CANmodule);
return ODR_OK;
}
/*
* Function for restoring data on "Restore default parameters" command - OD 1011
*
* For more information see file CO_storage.h, CO_storage_entry_t.
*/
static ODR_t
restoreBlank(CO_storage_entry_t* entry, CO_CANmodule_t* CANmodule) {
/* disable (delete) the file, so default values will stay after startup */
return ODR_OK;
}
CO_ReturnError_t
CO_storageBlank_init(CO_storage_t* storage, CO_CANmodule_t* CANmodule, OD_entry_t* OD_1010_StoreParameters,
OD_entry_t* OD_1011_RestoreDefaultParam, CO_storage_entry_t* entries, uint8_t entriesCount,
uint32_t* storageInitError) {
CO_ReturnError_t ret;
/* verify arguments */
if (storage == NULL || entries == NULL || entriesCount == 0 || storageInitError == NULL) {
return CO_ERROR_ILLEGAL_ARGUMENT;
}
/* initialize storage and OD extensions */
ret = CO_storage_init(storage, CANmodule, OD_1010_StoreParameters, OD_1011_RestoreDefaultParam, storeBlank,
restoreBlank, entries, entriesCount);
if (ret != CO_ERROR_NO) {
return ret;
}
/* initialize entries */
*storageInitError = 0;
for (uint8_t i = 0; i < entriesCount; i++) {
CO_storage_entry_t* entry = &entries[i];
/* verify arguments */
if (entry->addr == NULL || entry->len == 0 || entry->subIndexOD < 2) {
*storageInitError = i;
return CO_ERROR_ILLEGAL_ARGUMENT;
}
/* Open a file and read data from file to entry->addr */
/* file = open(entry->pathToFileOrPointerToMemory); */
/* read(entry->addr, entry->len, file); */
}
return ret;
}
#endif /* (CO_CONFIG_STORAGE) & CO_CONFIG_STORAGE_ENABLE */

View File

@@ -0,0 +1,58 @@
/*
* CANopen data storage object (blank example)
*
* @file CO_storageBlank.h
* @author Janez Paternoster
* @copyright 2021 Janez Paternoster
*
* This file is part of CANopenNode, an opensource CANopen Stack.
* Project home page is <https://github.com/CANopenNode/CANopenNode>.
* For more information on CANopen see <http://www.can-cia.org/>.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#ifndef CO_STORAGE_BLANK_H
#define CO_STORAGE_BLANK_H
#include "storage/CO_storage.h"
#if ((CO_CONFIG_STORAGE)&CO_CONFIG_STORAGE_ENABLE) || defined CO_DOXYGEN
#ifdef __cplusplus
extern "C" {
#endif
/* This is very basic example of implementing (object dictionary) data storage.
* Data storage is target specific. CO_storageBlank.h and .c files only shows
* the basic principle, but does nothing. For complete example of storage see:
* - CANopenPIC/PIC32 uses eeprom with CANopenNode/storage/CO_storage.h/.c,
* CANopenNode/storage/CO_storageEeprom.h/.c, CANopenNode/storage/CO_eeprom.h
* and CANopenPIC/PIC32/CO_eepromPIC32.c files.
* - CANopenLinux uses file system with CANopenNode/storage/CO_storage.h/.c and
* CANopenLinux/CO_storageLinux.h files.
*/
CO_ReturnError_t CO_storageBlank_init(CO_storage_t* storage, CO_CANmodule_t* CANmodule,
OD_entry_t* OD_1010_StoreParameters, OD_entry_t* OD_1011_RestoreDefaultParam,
CO_storage_entry_t* entries, uint8_t entriesCount, uint32_t* storageInitError);
uint32_t CO_storageBlank_auto_process(CO_storage_t* storage, bool_t closeFiles);
#ifdef __cplusplus
}
#endif /* __cplusplus */
#endif /* (CO_CONFIG_STORAGE) & CO_CONFIG_STORAGE_ENABLE */
#endif /* CO_STORAGE_BLANK_H */

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,747 @@
CANopen device documentation
============================
**New Product**
| | |
| ------------ | ------------------------------ |
| Project File | DS301_profile.xpd |
| File Version | 1 |
| Created | 23. 11. 2020 13:00:00 |
| Created By | |
| Modified | 9. 08. 2021 18:39:55 |
| Modified By | |
This file was automatically generated by [CANopenEditor](https://github.com/CANopenNode/CANopenEditor) v4.0-51-g2d9b1ad
[TOC]
Device Information
------------------
| | |
| ------------ | ------------------------------ |
| Vendor Name | |
| Vendor ID | |
| Product Name | New Product |
| Product ID | |
| Granularity | 8 |
| RPDO count | 4 |
| TPDO count | 4 |
| LSS Slave | True |
| LSS Master | False |
#### Supported Baud rates
* [x] 10 kBit/s
* [x] 20 kBit/s
* [x] 50 kBit/s
* [x] 125 kBit/s
* [x] 250 kBit/s
* [x] 500 kBit/s
* [x] 800 kBit/s
* [x] 1000 kBit/s
* [ ] auto
PDO Mapping
-----------
Communication Specific Parameters
---------------------------------
### 0x1000 - Device type
| Object Type | Count Label | Storage Group |
| ----------- | -------------- | -------------- |
| VAR | NMT | PERSIST_COMM |
| Data Type | SDO | PDO | SRDO | Default Value |
| ----------------------- | --- | --- | ---- | ------------------------------- |
| UNSIGNED32 | ro | no | no | 0x00000000 |
* bit 16-31: Additional information
* bit 0-15: Device profile number
### 0x1001 - Error register
| Object Type | Count Label | Storage Group |
| ----------- | -------------- | -------------- |
| VAR | EM | RAM |
| Data Type | SDO | PDO | SRDO | Default Value |
| ----------------------- | --- | --- | ---- | ------------------------------- |
| UNSIGNED8 | ro | t | no | 0x00 |
* bit 7: manufacturer specific
* bit 6: Reserved (always 0)
* bit 5: device profile specific
* bit 4: communication error (overrun, error state)
* bit 3: temperature
* bit 2: voltage
* bit 1: current
* bit 0: generic error
### 0x1003 - Pre-defined error field
| Object Type | Count Label | Storage Group |
| ----------- | -------------- | -------------- |
| ARRAY | | RAM |
| Sub | Name | Data Type | SDO | PDO | SRDO | Default Value |
| ---- | --------------------- | ---------- | --- | --- | ---- | ------------- |
| 0x00 | Number of errors | UNSIGNED8 | rw | no | no | |
| 0x01 | Standard error field | UNSIGNED32 | ro | no | no | |
| 0x02 | Standard error field | UNSIGNED32 | ro | no | no | |
| 0x03 | Standard error field | UNSIGNED32 | ro | no | no | |
| 0x04 | Standard error field | UNSIGNED32 | ro | no | no | |
| 0x05 | Standard error field | UNSIGNED32 | ro | no | no | |
| 0x06 | Standard error field | UNSIGNED32 | ro | no | no | |
| 0x07 | Standard error field | UNSIGNED32 | ro | no | no | |
| 0x08 | Standard error field | UNSIGNED32 | ro | no | no | |
| 0x09 | Standard error field | UNSIGNED32 | ro | no | no | |
| 0x0A | Standard error field | UNSIGNED32 | ro | no | no | |
| 0x0B | Standard error field | UNSIGNED32 | ro | no | no | |
| 0x0C | Standard error field | UNSIGNED32 | ro | no | no | |
| 0x0D | Standard error field | UNSIGNED32 | ro | no | no | |
| 0x0E | Standard error field | UNSIGNED32 | ro | no | no | |
| 0x0F | Standard error field | UNSIGNED32 | ro | no | no | |
| 0x10 | Standard error field | UNSIGNED32 | ro | no | no | |
* Sub Index 0: Contains number of actual errors. 0 can be written to clear error history.
* sub-index 1 and above:
* bit 16-31: Manufacturer specific additional information
* bit 0-15: Error code as transmited in the Emergency object
### 0x1005 - COB-ID SYNC message
| Object Type | Count Label | Storage Group |
| ----------- | -------------- | -------------- |
| VAR | SYNC | PERSIST_COMM |
| Data Type | SDO | PDO | SRDO | Default Value |
| ----------------------- | --- | --- | ---- | ------------------------------- |
| UNSIGNED32 | rw | no | no | 0x00000080 |
* bit 31: set to 0
* bit 30: If set, CANopen device generates SYNC object
* bit 11-29: set to 0
* bit 0-10: 11-bit CAN-ID
### 0x1006 - Communication cycle period
| Object Type | Count Label | Storage Group |
| ----------- | -------------- | -------------- |
| VAR | SYNC_PROD | PERSIST_COMM |
| Data Type | SDO | PDO | SRDO | Default Value |
| ----------------------- | --- | --- | ---- | ------------------------------- |
| UNSIGNED32 | rw | no | no | 0 |
Period of SYNC transmission in µs (0 = transmission disabled).
### 0x1007 - Synchronous window length
| Object Type | Count Label | Storage Group |
| ----------- | -------------- | -------------- |
| VAR | | PERSIST_COMM |
| Data Type | SDO | PDO | SRDO | Default Value |
| ----------------------- | --- | --- | ---- | ------------------------------- |
| UNSIGNED32 | rw | no | no | 0 |
Synchronous window leghth in µs (0 = not used). All synchronous PDOs must be transmitted within this time window.
### 0x1010 - Store parameters
| Object Type | Count Label | Storage Group |
| ----------- | -------------- | -------------- |
| ARRAY | STORAGE | RAM |
| Sub | Name | Data Type | SDO | PDO | SRDO | Default Value |
| ---- | --------------------- | ---------- | --- | --- | ---- | ------------- |
| 0x00 | Highest sub-index supported| UNSIGNED8 | ro | no | no | 0x04 |
| 0x01 | Save all parameters | UNSIGNED32 | rw | no | no | 0x00000001 |
| 0x02 | Save communication parameters| UNSIGNED32 | rw | no | no | 0x00000001 |
| 0x03 | Save application parameters| UNSIGNED32 | rw | no | no | 0x00000001 |
| 0x04 | Save manufacturer defined parameters| UNSIGNED32 | rw | no | no | 0x00000001 |
Sub-indexes 1 and above:
* Reading provides information about its storage functionality:
* bit 1: If set, CANopen device saves parameters autonomously
* bit 0: If set, CANopen device saves parameters on command
* Writing value 0x65766173 ('s','a','v','e' from LSB to MSB) stores corresponding data.
### 0x1011 - Restore default parameters
| Object Type | Count Label | Storage Group |
| ----------- | -------------- | -------------- |
| ARRAY | | RAM |
| Sub | Name | Data Type | SDO | PDO | SRDO | Default Value |
| ---- | --------------------- | ---------- | --- | --- | ---- | ------------- |
| 0x00 | Highest sub-index supported| UNSIGNED8 | ro | no | no | 0x04 |
| 0x01 | Restore all default parameters| UNSIGNED32 | rw | no | no | 0x00000001 |
| 0x02 | Restore communication default parameters| UNSIGNED32 | rw | no | no | 0x00000001 |
| 0x03 | Restore application default parameters| UNSIGNED32 | rw | no | no | 0x00000001 |
| 0x04 | Restore manufacturer defined default parameters| UNSIGNED32 | rw | no | no | 0x00000001 |
Sub-indexes 1 and above:
* Reading provides information about its restoring capability:
* bit 0: If set, CANopen device restores parameters
* Writing value 0x64616F6C ('l','o','a','d' from LSB to MSB) restores corresponding data.
### 0x1012 - COB-ID time stamp object
| Object Type | Count Label | Storage Group |
| ----------- | -------------- | -------------- |
| VAR | TIME | PERSIST_COMM |
| Data Type | SDO | PDO | SRDO | Default Value |
| ----------------------- | --- | --- | ---- | ------------------------------- |
| UNSIGNED32 | rw | no | no | 0x00000100 |
* bit 31: If set, CANopen device consumes TIME message
* bit 30: If set, CANopen device produces TIME message
* bit 11-29: set to 0
* bit 0-10: 11-bit CAN-ID
### 0x1014 - COB-ID EMCY
| Object Type | Count Label | Storage Group |
| ----------- | -------------- | -------------- |
| VAR | EM_PROD | PERSIST_COMM |
| Data Type | SDO | PDO | SRDO | Default Value |
| ----------------------- | --- | --- | ---- | ------------------------------- |
| UNSIGNED32 | rw | no | no | 0x80+$NODEID |
* bit 31: If set, EMCY does NOT exist / is NOT valid
* bit 11-30: set to 0
* bit 0-10: 11-bit CAN-ID
### 0x1015 - Inhibit time EMCY
| Object Type | Count Label | Storage Group |
| ----------- | -------------- | -------------- |
| VAR | | PERSIST_COMM |
| Data Type | SDO | PDO | SRDO | Default Value |
| ----------------------- | --- | --- | ---- | ------------------------------- |
| UNSIGNED16 | rw | no | no | 0 |
Inhibit time of emergency message in multiples of 100µs. The value 0 disables the inhibit time.
### 0x1016 - Consumer heartbeat time
| Object Type | Count Label | Storage Group |
| ----------- | -------------- | -------------- |
| ARRAY | HB_CONS | PERSIST_COMM |
| Sub | Name | Data Type | SDO | PDO | SRDO | Default Value |
| ---- | --------------------- | ---------- | --- | --- | ---- | ------------- |
| 0x00 | Highest sub-index supported| UNSIGNED8 | ro | no | no | 0x08 |
| 0x01 | Consumer heartbeat time| UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x02 | Consumer heartbeat time| UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x03 | Consumer heartbeat time| UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x04 | Consumer heartbeat time| UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x05 | Consumer heartbeat time| UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x06 | Consumer heartbeat time| UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x07 | Consumer heartbeat time| UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x08 | Consumer heartbeat time| UNSIGNED32 | rw | no | no | 0x00000000 |
Consumer Heartbeat Time:
* bit 24-31: set to 0
* bit 16-23: Node ID of the monitored node. If 0 or greater than 127, sub-entry is not used.
* bit 0-15: Heartbeat time in ms (if 0, sub-intry is not used). Value should be higher than the corresponding producer heartbeat time.
### 0x1017 - Producer heartbeat time
| Object Type | Count Label | Storage Group |
| ----------- | -------------- | -------------- |
| VAR | HB_PROD | PERSIST_COMM |
| Data Type | SDO | PDO | SRDO | Default Value |
| ----------------------- | --- | --- | ---- | ------------------------------- |
| UNSIGNED16 | rw | no | no | 0 |
Heartbeat producer time in ms (0 = disable transmission).
### 0x1018 - Identity
| Object Type | Count Label | Storage Group |
| ----------- | -------------- | -------------- |
| RECORD | | PERSIST_COMM |
| Sub | Name | Data Type | SDO | PDO | SRDO | Default Value |
| ---- | --------------------- | ---------- | --- | --- | ---- | ------------- |
| 0x00 | Highest sub-index supported| UNSIGNED8 | ro | no | no | 0x04 |
| 0x01 | Vendor-ID | UNSIGNED32 | ro | no | no | 0x00000000 |
| 0x02 | Product code | UNSIGNED32 | ro | no | no | 0x00000000 |
| 0x03 | Revision number | UNSIGNED32 | ro | no | no | 0x00000000 |
| 0x04 | Serial number | UNSIGNED32 | ro | no | no | 0x00000000 |
* Vendor-ID, assigned by CiA
* Product code, manufacturer specific
* Revision number:
* bit 16-31: Major revision number (CANopen behavior has changed)
* bit 0-15: Minor revision num. (CANopen behavior has not changed)
* Serial number, manufacturer specific
### 0x1019 - Synchronous counter overflow value
| Object Type | Count Label | Storage Group |
| ----------- | -------------- | -------------- |
| VAR | | PERSIST_COMM |
| Data Type | SDO | PDO | SRDO | Default Value |
| ----------------------- | --- | --- | ---- | ------------------------------- |
| UNSIGNED8 | rw | no | no | 0 |
* Value 0: SYNC message is transmitted with data length 0.
* Value 1: reserved.
* Value 2-240: SYNC message has one data byte, which contains the counter.
* Value 241-255: reserved.
### 0x1200 - SDO server parameter
| Object Type | Count Label | Storage Group |
| ----------- | -------------- | -------------- |
| RECORD | SDO_SRV | RAM |
| Sub | Name | Data Type | SDO | PDO | SRDO | Default Value |
| ---- | --------------------- | ---------- | --- | --- | ---- | ------------- |
| 0x00 | Highest sub-index supported| UNSIGNED8 | ro | no | no | 2 |
| 0x01 | COB-ID client to server (rx)| UNSIGNED32 | ro | t | no | 0x600+$NODEID |
| 0x02 | COB-ID server to client (tx)| UNSIGNED32 | ro | t | no | 0x580+$NODEID |
Sub-indexes 1 and 2:
* bit 11-31: set to 0
* bit 0-10: 11-bit CAN-ID
### 0x1280 - SDO client parameter
| Object Type | Count Label | Storage Group |
| ----------- | -------------- | -------------- |
| RECORD | SDO_CLI | PERSIST_COMM |
| Sub | Name | Data Type | SDO | PDO | SRDO | Default Value |
| ---- | --------------------- | ---------- | --- | --- | ---- | ------------- |
| 0x00 | Highest sub-index supported| UNSIGNED8 | ro | no | no | 0x03 |
| 0x01 | COB-ID client to server (tx)| UNSIGNED32 | rw | tr | no | 0x80000000 |
| 0x02 | COB-ID server to client (rx)| UNSIGNED32 | rw | tr | no | 0x80000000 |
| 0x03 | Node-ID of the SDO server| UNSIGNED8 | rw | no | no | 0x01 |
* Sub-indexes 1 and 2:
* bit 31: If set, SDO does NOT exist / is NOT valid
* bit 30: If set, value is assigned dynamically
* bit 11-29: set to 0
* bit 0-10: 11-bit CAN-ID
* Node-ID of the SDO server, 0x01 to 0x7F
### 0x1400 - RPDO communication parameter
| Object Type | Count Label | Storage Group |
| ----------- | -------------- | -------------- |
| RECORD | RPDO | PERSIST_COMM |
| Sub | Name | Data Type | SDO | PDO | SRDO | Default Value |
| ---- | --------------------- | ---------- | --- | --- | ---- | ------------- |
| 0x00 | Highest sub-index supported| UNSIGNED8 | ro | no | no | 0x05 |
| 0x01 | COB-ID used by RPDO | UNSIGNED32 | rw | no | no | 0x80000200+$NODEID|
| 0x02 | Transmission type | UNSIGNED8 | rw | no | no | 254 |
| 0x05 | Event timer | UNSIGNED16 | rw | no | no | 0 |
* COB-ID used by RPDO:
* bit 31: If set, PDO does not exist / is not valid
* bit 11-30: set to 0
* bit 0-10: 11-bit CAN-ID
* Transmission type:
* Value 0-240: synchronous, processed after next reception of SYNC object
* Value 241-253: not used
* Value 254: event-driven (manufacturer-specific)
* Value 255: event-driven (device profile and application profile specific)
* Event timer in ms (0 = disabled) for deadline monitoring.
### 0x1401 - RPDO communication parameter
| Object Type | Count Label | Storage Group |
| ----------- | -------------- | -------------- |
| RECORD | RPDO | PERSIST_COMM |
| Sub | Name | Data Type | SDO | PDO | SRDO | Default Value |
| ---- | --------------------- | ---------- | --- | --- | ---- | ------------- |
| 0x00 | Highest sub-index supported| UNSIGNED8 | ro | no | no | 0x05 |
| 0x01 | COB-ID used by RPDO | UNSIGNED32 | rw | no | no | 0x80000300+$NODEID|
| 0x02 | Transmission type | UNSIGNED8 | rw | no | no | 254 |
| 0x05 | Event timer | UNSIGNED16 | rw | no | no | 0 |
* COB-ID used by RPDO:
* bit 31: If set, PDO does not exist / is not valid
* bit 11-30: set to 0
* bit 0-10: 11-bit CAN-ID
* Transmission type:
* Value 0-240: synchronous, processed after next reception of SYNC object
* Value 241-253: not used
* Value 254: event-driven (manufacturer-specific)
* Value 255: event-driven (device profile and application profile specific)
* Event timer in ms (0 = disabled) for deadline monitoring.
### 0x1402 - RPDO communication parameter
| Object Type | Count Label | Storage Group |
| ----------- | -------------- | -------------- |
| RECORD | RPDO | PERSIST_COMM |
| Sub | Name | Data Type | SDO | PDO | SRDO | Default Value |
| ---- | --------------------- | ---------- | --- | --- | ---- | ------------- |
| 0x00 | Highest sub-index supported| UNSIGNED8 | ro | no | no | 0x05 |
| 0x01 | COB-ID used by RPDO | UNSIGNED32 | rw | no | no | 0x80000400+$NODEID|
| 0x02 | Transmission type | UNSIGNED8 | rw | no | no | 254 |
| 0x05 | Event timer | UNSIGNED16 | rw | no | no | 0 |
* COB-ID used by RPDO:
* bit 31: If set, PDO does not exist / is not valid
* bit 11-30: set to 0
* bit 0-10: 11-bit CAN-ID
* Transmission type:
* Value 0-240: synchronous, processed after next reception of SYNC object
* Value 241-253: not used
* Value 254: event-driven (manufacturer-specific)
* Value 255: event-driven (device profile and application profile specific)
* Event timer in ms (0 = disabled) for deadline monitoring.
### 0x1403 - RPDO communication parameter
| Object Type | Count Label | Storage Group |
| ----------- | -------------- | -------------- |
| RECORD | RPDO | PERSIST_COMM |
| Sub | Name | Data Type | SDO | PDO | SRDO | Default Value |
| ---- | --------------------- | ---------- | --- | --- | ---- | ------------- |
| 0x00 | Highest sub-index supported| UNSIGNED8 | ro | no | no | 0x05 |
| 0x01 | COB-ID used by RPDO | UNSIGNED32 | rw | no | no | 0x80000500+$NODEID|
| 0x02 | Transmission type | UNSIGNED8 | rw | no | no | 254 |
| 0x05 | Event timer | UNSIGNED16 | rw | no | no | 0 |
* COB-ID used by RPDO:
* bit 31: If set, PDO does not exist / is not valid
* bit 11-30: set to 0
* bit 0-10: 11-bit CAN-ID
* Transmission type:
* Value 0-240: synchronous, processed after next reception of SYNC object
* Value 241-253: not used
* Value 254: event-driven (manufacturer-specific)
* Value 255: event-driven (device profile and application profile specific)
* Event timer in ms (0 = disabled) for deadline monitoring.
### 0x1600 - RPDO mapping parameter
| Object Type | Count Label | Storage Group |
| ----------- | -------------- | -------------- |
| RECORD | | PERSIST_COMM |
| Sub | Name | Data Type | SDO | PDO | SRDO | Default Value |
| ---- | --------------------- | ---------- | --- | --- | ---- | ------------- |
| 0x00 | Number of mapped application objects in PDO| UNSIGNED8 | rw | no | no | 0 |
| 0x01 | Application object 1 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x02 | Application object 2 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x03 | Application object 3 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x04 | Application object 4 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x05 | Application object 5 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x06 | Application object 6 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x07 | Application object 7 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x08 | Application object 8 | UNSIGNED32 | rw | no | no | 0x00000000 |
* Number of mapped application objects in PDO:
* Value 0: mapping is disabled.
* Value 1: sub-index 0x01 is valid.
* Value 2-8: sub-indexes 0x01 to (0x02 to 0x08) are valid.
* Application object 1-8:
* bit 16-31: index
* bit 8-15: sub-index
* bit 0-7: data length in bits
### 0x1601 - RPDO mapping parameter
| Object Type | Count Label | Storage Group |
| ----------- | -------------- | -------------- |
| RECORD | | PERSIST_COMM |
| Sub | Name | Data Type | SDO | PDO | SRDO | Default Value |
| ---- | --------------------- | ---------- | --- | --- | ---- | ------------- |
| 0x00 | Number of mapped application objects in PDO| UNSIGNED8 | rw | no | no | 0 |
| 0x01 | Application object 1 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x02 | Application object 2 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x03 | Application object 3 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x04 | Application object 4 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x05 | Application object 5 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x06 | Application object 6 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x07 | Application object 7 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x08 | Application object 8 | UNSIGNED32 | rw | no | no | 0x00000000 |
* Number of mapped application objects in PDO:
* Value 0: mapping is disabled.
* Value 1: sub-index 0x01 is valid.
* Value 2-8: sub-indexes 0x01 to (0x02 to 0x08) are valid.
* Application object 1-8:
* bit 16-31: index
* bit 8-15: sub-index
* bit 0-7: data length in bits
### 0x1602 - RPDO mapping parameter
| Object Type | Count Label | Storage Group |
| ----------- | -------------- | -------------- |
| RECORD | | PERSIST_COMM |
| Sub | Name | Data Type | SDO | PDO | SRDO | Default Value |
| ---- | --------------------- | ---------- | --- | --- | ---- | ------------- |
| 0x00 | Number of mapped application objects in PDO| UNSIGNED8 | rw | no | no | 0 |
| 0x01 | Application object 1 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x02 | Application object 2 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x03 | Application object 3 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x04 | Application object 4 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x05 | Application object 5 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x06 | Application object 6 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x07 | Application object 7 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x08 | Application object 8 | UNSIGNED32 | rw | no | no | 0x00000000 |
* Number of mapped application objects in PDO:
* Value 0: mapping is disabled.
* Value 1: sub-index 0x01 is valid.
* Value 2-8: sub-indexes 0x01 to (0x02 to 0x08) are valid.
* Application object 1-8:
* bit 16-31: index
* bit 8-15: sub-index
* bit 0-7: data length in bits
### 0x1603 - RPDO mapping parameter
| Object Type | Count Label | Storage Group |
| ----------- | -------------- | -------------- |
| RECORD | | PERSIST_COMM |
| Sub | Name | Data Type | SDO | PDO | SRDO | Default Value |
| ---- | --------------------- | ---------- | --- | --- | ---- | ------------- |
| 0x00 | Number of mapped application objects in PDO| UNSIGNED8 | rw | no | no | 0 |
| 0x01 | Application object 1 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x02 | Application object 2 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x03 | Application object 3 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x04 | Application object 4 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x05 | Application object 5 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x06 | Application object 6 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x07 | Application object 7 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x08 | Application object 8 | UNSIGNED32 | rw | no | no | 0x00000000 |
* Number of mapped application objects in PDO:
* Value 0: mapping is disabled.
* Value 1: sub-index 0x01 is valid.
* Value 2-8: sub-indexes 0x01 to (0x02 to 0x08) are valid.
* Application object 1-8:
* bit 16-31: index
* bit 8-15: sub-index
* bit 0-7: data length in bits
### 0x1800 - TPDO communication parameter
| Object Type | Count Label | Storage Group |
| ----------- | -------------- | -------------- |
| RECORD | TPDO | PERSIST_COMM |
| Sub | Name | Data Type | SDO | PDO | SRDO | Default Value |
| ---- | --------------------- | ---------- | --- | --- | ---- | ------------- |
| 0x00 | Highest sub-index supported| UNSIGNED8 | ro | no | no | 0x06 |
| 0x01 | COB-ID used by TPDO | UNSIGNED32 | rw | no | no | 0xC0000180+$NODEID|
| 0x02 | Transmission type | UNSIGNED8 | rw | no | no | 254 |
| 0x03 | Inhibit time | UNSIGNED16 | rw | no | no | 0 |
| 0x05 | Event timer | UNSIGNED16 | rw | no | no | 0 |
| 0x06 | SYNC start value | UNSIGNED8 | rw | no | no | 0 |
* COB-ID used by RPDO:
* bit 31: If set, PDO does not exist / is not valid
* bit 30: If set, NO RTR is allowed on this PDO
* bit 11-29: set to 0
* bit 0-10: 11-bit CAN-ID
* Transmission type:
* Value 0: synchronous (acyclic)
* Value 1-240: synchronous (cyclic every (1-240)-th sync)
* Value 241-253: not used
* Value 254: event-driven (manufacturer-specific)
* Value 255: event-driven (device profile and application profile specific)
* Inhibit time in multiple of 100µs, if the transmission type is set to 254 or 255 (0 = disabled).
* Event timer interval in ms, if the transmission type is set to 254 or 255 (0 = disabled).
* SYNC start value
* Value 0: Counter of the SYNC message shall not be processed.
* Value 1-240: The SYNC message with the counter value equal to this value shall be regarded as the first received SYNC message.
### 0x1801 - TPDO communication parameter
| Object Type | Count Label | Storage Group |
| ----------- | -------------- | -------------- |
| RECORD | TPDO | PERSIST_COMM |
| Sub | Name | Data Type | SDO | PDO | SRDO | Default Value |
| ---- | --------------------- | ---------- | --- | --- | ---- | ------------- |
| 0x00 | Highest sub-index supported| UNSIGNED8 | ro | no | no | 0x06 |
| 0x01 | COB-ID used by TPDO | UNSIGNED32 | rw | no | no | 0xC0000280+$NODEID|
| 0x02 | Transmission type | UNSIGNED8 | rw | no | no | 254 |
| 0x03 | Inhibit time | UNSIGNED16 | rw | no | no | 0 |
| 0x05 | Event timer | UNSIGNED16 | rw | no | no | 0 |
| 0x06 | SYNC start value | UNSIGNED8 | rw | no | no | 0 |
* COB-ID used by RPDO:
* bit 31: If set, PDO does not exist / is not valid
* bit 30: If set, NO RTR is allowed on this PDO
* bit 11-29: set to 0
* bit 0-10: 11-bit CAN-ID
* Transmission type:
* Value 0: synchronous (acyclic)
* Value 1-240: synchronous (cyclic every (1-240)-th sync)
* Value 241-253: not used
* Value 254: event-driven (manufacturer-specific)
* Value 255: event-driven (device profile and application profile specific)
* Inhibit time in multiple of 100µs, if the transmission type is set to 254 or 255 (0 = disabled).
* Event timer interval in ms, if the transmission type is set to 254 or 255 (0 = disabled).
* SYNC start value
* Value 0: Counter of the SYNC message shall not be processed.
* Value 1-240: The SYNC message with the counter value equal to this value shall be regarded as the first received SYNC message.
### 0x1802 - TPDO communication parameter
| Object Type | Count Label | Storage Group |
| ----------- | -------------- | -------------- |
| RECORD | TPDO | PERSIST_COMM |
| Sub | Name | Data Type | SDO | PDO | SRDO | Default Value |
| ---- | --------------------- | ---------- | --- | --- | ---- | ------------- |
| 0x00 | Highest sub-index supported| UNSIGNED8 | ro | no | no | 0x06 |
| 0x01 | COB-ID used by TPDO | UNSIGNED32 | rw | no | no | 0xC0000380+$NODEID|
| 0x02 | Transmission type | UNSIGNED8 | rw | no | no | 254 |
| 0x03 | Inhibit time | UNSIGNED16 | rw | no | no | 0 |
| 0x05 | Event timer | UNSIGNED16 | rw | no | no | 0 |
| 0x06 | SYNC start value | UNSIGNED8 | rw | no | no | 0 |
* COB-ID used by RPDO:
* bit 31: If set, PDO does not exist / is not valid
* bit 30: If set, NO RTR is allowed on this PDO
* bit 11-29: set to 0
* bit 0-10: 11-bit CAN-ID
* Transmission type:
* Value 0: synchronous (acyclic)
* Value 1-240: synchronous (cyclic every (1-240)-th sync)
* Value 241-253: not used
* Value 254: event-driven (manufacturer-specific)
* Value 255: event-driven (device profile and application profile specific)
* Inhibit time in multiple of 100µs, if the transmission type is set to 254 or 255 (0 = disabled).
* Event timer interval in ms, if the transmission type is set to 254 or 255 (0 = disabled).
* SYNC start value
* Value 0: Counter of the SYNC message shall not be processed.
* Value 1-240: The SYNC message with the counter value equal to this value shall be regarded as the first received SYNC message.
### 0x1803 - TPDO communication parameter
| Object Type | Count Label | Storage Group |
| ----------- | -------------- | -------------- |
| RECORD | TPDO | PERSIST_COMM |
| Sub | Name | Data Type | SDO | PDO | SRDO | Default Value |
| ---- | --------------------- | ---------- | --- | --- | ---- | ------------- |
| 0x00 | Highest sub-index supported| UNSIGNED8 | ro | no | no | 0x06 |
| 0x01 | COB-ID used by TPDO | UNSIGNED32 | rw | no | no | 0xC0000480+$NODEID|
| 0x02 | Transmission type | UNSIGNED8 | rw | no | no | 254 |
| 0x03 | Inhibit time | UNSIGNED16 | rw | no | no | 0 |
| 0x05 | Event timer | UNSIGNED16 | rw | no | no | 0 |
| 0x06 | SYNC start value | UNSIGNED8 | rw | no | no | 0 |
* COB-ID used by RPDO:
* bit 31: If set, PDO does not exist / is not valid
* bit 30: If set, NO RTR is allowed on this PDO
* bit 11-29: set to 0
* bit 0-10: 11-bit CAN-ID
* Transmission type:
* Value 0: synchronous (acyclic)
* Value 1-240: synchronous (cyclic every (1-240)-th sync)
* Value 241-253: not used
* Value 254: event-driven (manufacturer-specific)
* Value 255: event-driven (device profile and application profile specific)
* Inhibit time in multiple of 100µs, if the transmission type is set to 254 or 255 (0 = disabled).
* Event timer interval in ms, if the transmission type is set to 254 or 255 (0 = disabled).
* SYNC start value
* Value 0: Counter of the SYNC message shall not be processed.
* Value 1-240: The SYNC message with the counter value equal to this value shall be regarded as the first received SYNC message.
### 0x1A00 - TPDO mapping parameter
| Object Type | Count Label | Storage Group |
| ----------- | -------------- | -------------- |
| RECORD | | PERSIST_COMM |
| Sub | Name | Data Type | SDO | PDO | SRDO | Default Value |
| ---- | --------------------- | ---------- | --- | --- | ---- | ------------- |
| 0x00 | Number of mapped application objects in PDO| UNSIGNED8 | rw | no | no | 0 |
| 0x01 | Application object 1 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x02 | Application object 2 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x03 | Application object 3 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x04 | Application object 4 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x05 | Application object 5 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x06 | Application object 6 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x07 | Application object 7 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x08 | Application object 8 | UNSIGNED32 | rw | no | no | 0x00000000 |
* Number of mapped application objects in PDO:
* Value 0: mapping is disabled.
* Value 1: sub-index 0x01 is valid.
* Value 2-8: sub-indexes 0x01 to (0x02 to 0x08) are valid.
* Application object 1-8:
* bit 16-31: index
* bit 8-15: sub-index
* bit 0-7: data length in bits
### 0x1A01 - TPDO mapping parameter
| Object Type | Count Label | Storage Group |
| ----------- | -------------- | -------------- |
| RECORD | | PERSIST_COMM |
| Sub | Name | Data Type | SDO | PDO | SRDO | Default Value |
| ---- | --------------------- | ---------- | --- | --- | ---- | ------------- |
| 0x00 | Number of mapped application objects in PDO| UNSIGNED8 | rw | no | no | 0 |
| 0x01 | Application object 1 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x02 | Application object 2 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x03 | Application object 3 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x04 | Application object 4 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x05 | Application object 5 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x06 | Application object 6 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x07 | Application object 7 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x08 | Application object 8 | UNSIGNED32 | rw | no | no | 0x00000000 |
* Number of mapped application objects in PDO:
* Value 0: mapping is disabled.
* Value 1: sub-index 0x01 is valid.
* Value 2-8: sub-indexes 0x01 to (0x02 to 0x08) are valid.
* Application object 1-8:
* bit 16-31: index
* bit 8-15: sub-index
* bit 0-7: data length in bits
### 0x1A02 - TPDO mapping parameter
| Object Type | Count Label | Storage Group |
| ----------- | -------------- | -------------- |
| RECORD | | PERSIST_COMM |
| Sub | Name | Data Type | SDO | PDO | SRDO | Default Value |
| ---- | --------------------- | ---------- | --- | --- | ---- | ------------- |
| 0x00 | Number of mapped application objects in PDO| UNSIGNED8 | rw | no | no | 0 |
| 0x01 | Application object 1 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x02 | Application object 2 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x03 | Application object 3 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x04 | Application object 4 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x05 | Application object 5 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x06 | Application object 6 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x07 | Application object 7 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x08 | Application object 8 | UNSIGNED32 | rw | no | no | 0x00000000 |
* Number of mapped application objects in PDO:
* Value 0: mapping is disabled.
* Value 1: sub-index 0x01 is valid.
* Value 2-8: sub-indexes 0x01 to (0x02 to 0x08) are valid.
* Application object 1-8:
* bit 16-31: index
* bit 8-15: sub-index
* bit 0-7: data length in bits
### 0x1A03 - TPDO mapping parameter
| Object Type | Count Label | Storage Group |
| ----------- | -------------- | -------------- |
| RECORD | | PERSIST_COMM |
| Sub | Name | Data Type | SDO | PDO | SRDO | Default Value |
| ---- | --------------------- | ---------- | --- | --- | ---- | ------------- |
| 0x00 | Number of mapped application objects in PDO| UNSIGNED8 | rw | no | no | 0 |
| 0x01 | Application object 1 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x02 | Application object 2 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x03 | Application object 3 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x04 | Application object 4 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x05 | Application object 5 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x06 | Application object 6 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x07 | Application object 7 | UNSIGNED32 | rw | no | no | 0x00000000 |
| 0x08 | Application object 8 | UNSIGNED32 | rw | no | no | 0x00000000 |
* Number of mapped application objects in PDO:
* Value 0: mapping is disabled.
* Value 1: sub-index 0x01 is valid.
* Value 2-8: sub-indexes 0x01 to (0x02 to 0x08) are valid.
* Application object 1-8:
* bit 16-31: index
* bit 8-15: sub-index
* bit 0-7: data length in bits

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,58 @@
# Makefile for CANopenNode, basic compile with blank CAN device
DRV_SRC = .
CANOPEN_SRC = ..
APPL_SRC = .
LINK_TARGET = canopennode_blank
INCLUDE_DIRS = \
-I$(DRV_SRC) \
-I$(CANOPEN_SRC) \
-I$(APPL_SRC)
SOURCES = \
$(DRV_SRC)/CO_driver_blank.c \
$(DRV_SRC)/CO_storageBlank.c \
$(CANOPEN_SRC)/301/CO_ODinterface.c \
$(CANOPEN_SRC)/301/CO_NMT_Heartbeat.c \
$(CANOPEN_SRC)/301/CO_HBconsumer.c \
$(CANOPEN_SRC)/301/CO_Emergency.c \
$(CANOPEN_SRC)/301/CO_SDOserver.c \
$(CANOPEN_SRC)/301/CO_TIME.c \
$(CANOPEN_SRC)/301/CO_SYNC.c \
$(CANOPEN_SRC)/301/CO_PDO.c \
$(CANOPEN_SRC)/303/CO_LEDs.c \
$(CANOPEN_SRC)/305/CO_LSSslave.c \
$(CANOPEN_SRC)/storage/CO_storage.c \
$(CANOPEN_SRC)/CANopen.c \
$(APPL_SRC)/OD.c \
$(DRV_SRC)/main_blank.c
OBJS = $(SOURCES:%.c=%.o)
CC ?= gcc
OPT =
OPT += -g
#OPT += -DCO_USE_GLOBALS
#OPT += -DCO_MULTIPLE_OD
CFLAGS = -Wall $(OPT) $(INCLUDE_DIRS)
LDFLAGS =
.PHONY: all clean
all: clean $(LINK_TARGET)
clean:
rm -f $(OBJS) $(LINK_TARGET)
%.o: %.c
$(CC) $(CFLAGS) -c $< -o $@
$(LINK_TARGET): $(OBJS)
$(CC) $(LDFLAGS) $^ -o $@

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,420 @@
/*******************************************************************************
CANopen Object Dictionary definition for CANopenNode V4
This file was automatically generated by CANopenEditor v4.2.3-0-gc1071ab+c1071ab3197f9bbf718123ec5bbabf449b2f7bab
https://github.com/CANopenNode/CANopenNode
https://github.com/CANopenNode/CANopenEditor
DON'T EDIT THIS FILE MANUALLY !!!!
********************************************************************************
File info:
File Names: OD.h; OD.c
Project File: NodeSlave.xdd
File Version: 1
Created: 2026/1/30 14:35:40
Created By:
Modified: 2026/2/26 17:17:54
Modified By:
Device Info:
Vendor Name:
Vendor ID:
Product Name: NodeSlave
Product ID:
Description:
*******************************************************************************/
#ifndef OD_H
#define OD_H
/*******************************************************************************
Counters of OD objects
*******************************************************************************/
#define OD_CNT_NMT 1
#define OD_CNT_EM 1
#define OD_CNT_SYNC 1
#define OD_CNT_SYNC_PROD 1
#define OD_CNT_STORAGE 1
#define OD_CNT_TIME 1
#define OD_CNT_EM_PROD 1
#define OD_CNT_HB_CONS 1
#define OD_CNT_HB_PROD 1
#define OD_CNT_SDO_SRV 1
#define OD_CNT_SDO_CLI 1
#define OD_CNT_RPDO 4
#define OD_CNT_TPDO 4
/*******************************************************************************
Sizes of OD arrays
*******************************************************************************/
#define OD_CNT_ARR_1003 16
#define OD_CNT_ARR_1010 4
#define OD_CNT_ARR_1011 4
#define OD_CNT_ARR_1016 8
/*******************************************************************************
OD data declaration of all groups
*******************************************************************************/
typedef struct {
uint32_t x1000_deviceType;
uint32_t x1005_COB_ID_SYNCMessage;
uint32_t x1006_communicationCyclePeriod;
uint32_t x1007_synchronousWindowLength;
uint32_t x1012_COB_IDTimeStampObject;
uint32_t x1014_COB_ID_EMCY;
uint16_t x1015_inhibitTimeEMCY;
uint8_t x1016_consumerHeartbeatTime_sub0;
uint32_t x1016_consumerHeartbeatTime[OD_CNT_ARR_1016];
uint16_t x1017_producerHeartbeatTime;
struct {
uint8_t highestSub_indexSupported;
uint32_t vendor_ID;
uint32_t productCode;
uint32_t revisionNumber;
uint32_t serialNumber;
} x1018_identity;
uint8_t x1019_synchronousCounterOverflowValue;
struct {
uint8_t highestSub_indexSupported;
uint32_t COB_IDClientToServerTx;
uint32_t COB_IDServerToClientRx;
uint8_t node_IDOfTheSDOServer;
} x1280_SDOClientParameter;
struct {
uint8_t highestSub_indexSupported;
uint32_t COB_IDUsedByRPDO;
uint8_t transmissionType;
uint16_t eventTimer;
} x1400_RPDOCommunicationParameter;
struct {
uint8_t highestSub_indexSupported;
uint32_t COB_IDUsedByRPDO;
uint8_t transmissionType;
uint16_t eventTimer;
} x1401_RPDOCommunicationParameter;
struct {
uint8_t highestSub_indexSupported;
uint32_t COB_IDUsedByRPDO;
uint8_t transmissionType;
uint16_t eventTimer;
} x1402_RPDOCommunicationParameter;
struct {
uint8_t highestSub_indexSupported;
uint32_t COB_IDUsedByRPDO;
uint8_t transmissionType;
uint16_t eventTimer;
} x1403_RPDOCommunicationParameter;
struct {
uint8_t numberOfMappedApplicationObjectsInPDO;
uint32_t applicationObject1;
uint32_t applicationObject2;
uint32_t applicationObject3;
uint32_t applicationObject4;
uint32_t applicationObject5;
uint32_t applicationObject6;
uint32_t applicationObject7;
uint32_t applicationObject8;
} x1600_RPDOMappingParameter;
struct {
uint8_t numberOfMappedApplicationObjectsInPDO;
uint32_t applicationObject1;
uint32_t applicationObject2;
uint32_t applicationObject3;
uint32_t applicationObject4;
uint32_t applicationObject5;
uint32_t applicationObject6;
uint32_t applicationObject7;
uint32_t applicationObject8;
} x1601_RPDOMappingParameter;
struct {
uint8_t numberOfMappedApplicationObjectsInPDO;
uint32_t applicationObject1;
uint32_t applicationObject2;
uint32_t applicationObject3;
uint32_t applicationObject4;
uint32_t applicationObject5;
uint32_t applicationObject6;
uint32_t applicationObject7;
uint32_t applicationObject8;
} x1602_RPDOMappingParameter;
struct {
uint8_t numberOfMappedApplicationObjectsInPDO;
uint32_t applicationObject1;
uint32_t applicationObject2;
uint32_t applicationObject3;
uint32_t applicationObject4;
uint32_t applicationObject5;
uint32_t applicationObject6;
uint32_t applicationObject7;
uint32_t applicationObject8;
} x1603_RPDOMappingParameter;
struct {
uint8_t highestSub_indexSupported;
uint32_t COB_IDUsedByTPDO;
uint8_t transmissionType;
uint16_t inhibitTime;
uint16_t eventTimer;
uint8_t SYNCStartValue;
} x1800_TPDOCommunicationParameter;
struct {
uint8_t highestSub_indexSupported;
uint32_t COB_IDUsedByTPDO;
uint8_t transmissionType;
uint16_t inhibitTime;
uint16_t eventTimer;
uint8_t SYNCStartValue;
} x1801_TPDOCommunicationParameter;
struct {
uint8_t highestSub_indexSupported;
uint32_t COB_IDUsedByTPDO;
uint8_t transmissionType;
uint16_t inhibitTime;
uint16_t eventTimer;
uint8_t SYNCStartValue;
} x1802_TPDOCommunicationParameter;
struct {
uint8_t highestSub_indexSupported;
uint32_t COB_IDUsedByTPDO;
uint8_t transmissionType;
uint16_t inhibitTime;
uint16_t eventTimer;
uint8_t SYNCStartValue;
} x1803_TPDOCommunicationParameter;
struct {
uint8_t numberOfMappedApplicationObjectsInPDO;
uint32_t applicationObject1;
uint32_t applicationObject2;
uint32_t applicationObject3;
uint32_t applicationObject4;
uint32_t applicationObject5;
uint32_t applicationObject6;
uint32_t applicationObject7;
uint32_t applicationObject8;
} x1A00_TPDOMappingParameter;
struct {
uint8_t numberOfMappedApplicationObjectsInPDO;
uint32_t applicationObject1;
uint32_t applicationObject2;
uint32_t applicationObject3;
uint32_t applicationObject4;
uint32_t applicationObject5;
uint32_t applicationObject6;
uint32_t applicationObject7;
uint32_t applicationObject8;
} x1A01_TPDOMappingParameter;
struct {
uint8_t numberOfMappedApplicationObjectsInPDO;
uint32_t applicationObject1;
uint32_t applicationObject2;
uint32_t applicationObject3;
uint32_t applicationObject4;
uint32_t applicationObject5;
uint32_t applicationObject6;
uint32_t applicationObject7;
uint32_t applicationObject8;
} x1A02_TPDOMappingParameter;
struct {
uint8_t numberOfMappedApplicationObjectsInPDO;
uint32_t applicationObject1;
uint32_t applicationObject2;
uint32_t applicationObject3;
uint32_t applicationObject4;
uint32_t applicationObject5;
uint32_t applicationObject6;
uint32_t applicationObject7;
uint32_t applicationObject8;
} x1A03_TPDOMappingParameter;
} OD_PERSIST_COMM_t;
typedef struct {
uint8_t x1001_errorRegister;
uint8_t x1010_storeParameters_sub0;
uint32_t x1010_storeParameters[OD_CNT_ARR_1010];
uint8_t x1011_restoreDefaultParameters_sub0;
uint32_t x1011_restoreDefaultParameters[OD_CNT_ARR_1011];
struct {
uint8_t highestSub_indexSupported;
uint32_t COB_IDClientToServerRx;
uint32_t COB_IDServerToClientTx;
} x1200_SDOServerParameter;
uint16_t x6040_controlword;
uint16_t x6041_statusword;
int8_t x6060_modesOfOperation;
int8_t x6061_modesOfOperationDisplay;
int32_t x6064_positionActualValue;
float32_t x6065_followingErrorWindow;
int32_t x606C_velocityActualValue;
uint32_t x607A_targetPosition;
uint32_t x6083_acceleration;
uint32_t x6084_deceleration;
int32_t x60FF_targetVelocity;
} OD_RAM_t;
#ifndef OD_ATTR_PERSIST_COMM
#define OD_ATTR_PERSIST_COMM
#endif
extern OD_ATTR_PERSIST_COMM OD_PERSIST_COMM_t OD_PERSIST_COMM;
#ifndef OD_ATTR_RAM
#define OD_ATTR_RAM
#endif
extern OD_ATTR_RAM OD_RAM_t OD_RAM;
#ifndef OD_ATTR_OD
#define OD_ATTR_OD
#endif
extern OD_ATTR_OD OD_t *OD;
/*******************************************************************************
Object dictionary entries - shortcuts
*******************************************************************************/
#define OD_ENTRY_H1000 &OD->list[0]
#define OD_ENTRY_H1001 &OD->list[1]
#define OD_ENTRY_H1003 &OD->list[2]
#define OD_ENTRY_H1005 &OD->list[3]
#define OD_ENTRY_H1006 &OD->list[4]
#define OD_ENTRY_H1007 &OD->list[5]
#define OD_ENTRY_H1010 &OD->list[6]
#define OD_ENTRY_H1011 &OD->list[7]
#define OD_ENTRY_H1012 &OD->list[8]
#define OD_ENTRY_H1014 &OD->list[9]
#define OD_ENTRY_H1015 &OD->list[10]
#define OD_ENTRY_H1016 &OD->list[11]
#define OD_ENTRY_H1017 &OD->list[12]
#define OD_ENTRY_H1018 &OD->list[13]
#define OD_ENTRY_H1019 &OD->list[14]
#define OD_ENTRY_H1200 &OD->list[15]
#define OD_ENTRY_H1280 &OD->list[16]
#define OD_ENTRY_H1400 &OD->list[17]
#define OD_ENTRY_H1401 &OD->list[18]
#define OD_ENTRY_H1402 &OD->list[19]
#define OD_ENTRY_H1403 &OD->list[20]
#define OD_ENTRY_H1600 &OD->list[21]
#define OD_ENTRY_H1601 &OD->list[22]
#define OD_ENTRY_H1602 &OD->list[23]
#define OD_ENTRY_H1603 &OD->list[24]
#define OD_ENTRY_H1800 &OD->list[25]
#define OD_ENTRY_H1801 &OD->list[26]
#define OD_ENTRY_H1802 &OD->list[27]
#define OD_ENTRY_H1803 &OD->list[28]
#define OD_ENTRY_H1A00 &OD->list[29]
#define OD_ENTRY_H1A01 &OD->list[30]
#define OD_ENTRY_H1A02 &OD->list[31]
#define OD_ENTRY_H1A03 &OD->list[32]
#define OD_ENTRY_H6040 &OD->list[33]
#define OD_ENTRY_H6041 &OD->list[34]
#define OD_ENTRY_H6060 &OD->list[35]
#define OD_ENTRY_H6061 &OD->list[36]
#define OD_ENTRY_H6064 &OD->list[37]
#define OD_ENTRY_H6065 &OD->list[38]
#define OD_ENTRY_H606C &OD->list[39]
#define OD_ENTRY_H607A &OD->list[40]
#define OD_ENTRY_H6083 &OD->list[41]
#define OD_ENTRY_H6084 &OD->list[42]
#define OD_ENTRY_H60FF &OD->list[43]
/*******************************************************************************
Object dictionary entries - shortcuts with names
*******************************************************************************/
#define OD_ENTRY_H1000_deviceType &OD->list[0]
#define OD_ENTRY_H1001_errorRegister &OD->list[1]
#define OD_ENTRY_H1003_pre_definedErrorField &OD->list[2]
#define OD_ENTRY_H1005_COB_ID_SYNCMessage &OD->list[3]
#define OD_ENTRY_H1006_communicationCyclePeriod &OD->list[4]
#define OD_ENTRY_H1007_synchronousWindowLength &OD->list[5]
#define OD_ENTRY_H1010_storeParameters &OD->list[6]
#define OD_ENTRY_H1011_restoreDefaultParameters &OD->list[7]
#define OD_ENTRY_H1012_COB_IDTimeStampObject &OD->list[8]
#define OD_ENTRY_H1014_COB_ID_EMCY &OD->list[9]
#define OD_ENTRY_H1015_inhibitTimeEMCY &OD->list[10]
#define OD_ENTRY_H1016_consumerHeartbeatTime &OD->list[11]
#define OD_ENTRY_H1017_producerHeartbeatTime &OD->list[12]
#define OD_ENTRY_H1018_identity &OD->list[13]
#define OD_ENTRY_H1019_synchronousCounterOverflowValue &OD->list[14]
#define OD_ENTRY_H1200_SDOServerParameter &OD->list[15]
#define OD_ENTRY_H1280_SDOClientParameter &OD->list[16]
#define OD_ENTRY_H1400_RPDOCommunicationParameter &OD->list[17]
#define OD_ENTRY_H1401_RPDOCommunicationParameter &OD->list[18]
#define OD_ENTRY_H1402_RPDOCommunicationParameter &OD->list[19]
#define OD_ENTRY_H1403_RPDOCommunicationParameter &OD->list[20]
#define OD_ENTRY_H1600_RPDOMappingParameter &OD->list[21]
#define OD_ENTRY_H1601_RPDOMappingParameter &OD->list[22]
#define OD_ENTRY_H1602_RPDOMappingParameter &OD->list[23]
#define OD_ENTRY_H1603_RPDOMappingParameter &OD->list[24]
#define OD_ENTRY_H1800_TPDOCommunicationParameter &OD->list[25]
#define OD_ENTRY_H1801_TPDOCommunicationParameter &OD->list[26]
#define OD_ENTRY_H1802_TPDOCommunicationParameter &OD->list[27]
#define OD_ENTRY_H1803_TPDOCommunicationParameter &OD->list[28]
#define OD_ENTRY_H1A00_TPDOMappingParameter &OD->list[29]
#define OD_ENTRY_H1A01_TPDOMappingParameter &OD->list[30]
#define OD_ENTRY_H1A02_TPDOMappingParameter &OD->list[31]
#define OD_ENTRY_H1A03_TPDOMappingParameter &OD->list[32]
#define OD_ENTRY_H6040_controlword &OD->list[33]
#define OD_ENTRY_H6041_statusword &OD->list[34]
#define OD_ENTRY_H6060_modesOfOperation &OD->list[35]
#define OD_ENTRY_H6061_modesOfOperationDisplay &OD->list[36]
#define OD_ENTRY_H6064_positionActualValue &OD->list[37]
#define OD_ENTRY_H6065_followingErrorWindow &OD->list[38]
#define OD_ENTRY_H606C_velocityActualValue &OD->list[39]
#define OD_ENTRY_H607A_targetPosition &OD->list[40]
#define OD_ENTRY_H6083_acceleration &OD->list[41]
#define OD_ENTRY_H6084_deceleration &OD->list[42]
#define OD_ENTRY_H60FF_targetVelocity &OD->list[43]
/*******************************************************************************
OD config structure
*******************************************************************************/
#ifdef CO_MULTIPLE_OD
#define OD_INIT_CONFIG(config) {\
(config).CNT_NMT = OD_CNT_NMT;\
(config).ENTRY_H1017 = OD_ENTRY_H1017;\
(config).CNT_HB_CONS = OD_CNT_HB_CONS;\
(config).CNT_ARR_1016 = OD_CNT_ARR_1016;\
(config).ENTRY_H1016 = OD_ENTRY_H1016;\
(config).CNT_EM = OD_CNT_EM;\
(config).ENTRY_H1001 = OD_ENTRY_H1001;\
(config).ENTRY_H1014 = OD_ENTRY_H1014;\
(config).ENTRY_H1015 = OD_ENTRY_H1015;\
(config).CNT_ARR_1003 = OD_CNT_ARR_1003;\
(config).ENTRY_H1003 = OD_ENTRY_H1003;\
(config).CNT_SDO_SRV = OD_CNT_SDO_SRV;\
(config).ENTRY_H1200 = OD_ENTRY_H1200;\
(config).CNT_SDO_CLI = OD_CNT_SDO_CLI;\
(config).ENTRY_H1280 = OD_ENTRY_H1280;\
(config).CNT_TIME = OD_CNT_TIME;\
(config).ENTRY_H1012 = OD_ENTRY_H1012;\
(config).CNT_SYNC = OD_CNT_SYNC;\
(config).ENTRY_H1005 = OD_ENTRY_H1005;\
(config).ENTRY_H1006 = OD_ENTRY_H1006;\
(config).ENTRY_H1007 = OD_ENTRY_H1007;\
(config).ENTRY_H1019 = OD_ENTRY_H1019;\
(config).CNT_RPDO = OD_CNT_RPDO;\
(config).ENTRY_H1400 = OD_ENTRY_H1400;\
(config).ENTRY_H1600 = OD_ENTRY_H1600;\
(config).CNT_TPDO = OD_CNT_TPDO;\
(config).ENTRY_H1800 = OD_ENTRY_H1800;\
(config).ENTRY_H1A00 = OD_ENTRY_H1A00;\
(config).CNT_LEDS = 0;\
(config).CNT_GFC = 0;\
(config).ENTRY_H1300 = NULL;\
(config).CNT_SRDO = 0;\
(config).ENTRY_H1301 = NULL;\
(config).ENTRY_H1381 = NULL;\
(config).ENTRY_H13FE = NULL;\
(config).ENTRY_H13FF = NULL;\
(config).CNT_LSS_SLV = 0;\
(config).CNT_LSS_MST = 0;\
(config).CNT_GTWA = 0;\
(config).CNT_TRACE = 0;\
}
#endif
#endif /* OD_H */