git commit -m "first commit for v2"
This commit is contained in:
5
Devices/Libraries/Systems/CANopenSocket/examples/basicDevice/.gitignore
vendored
Executable file
5
Devices/Libraries/Systems/CANopenSocket/examples/basicDevice/.gitignore
vendored
Executable file
@@ -0,0 +1,5 @@
|
||||
/basicDevice
|
||||
/basicDeviceWithGateway
|
||||
CO_version.h
|
||||
*.persist
|
||||
*.persist.old
|
||||
130
Devices/Libraries/Systems/CANopenSocket/examples/basicDevice/CO_application.c
Executable file
130
Devices/Libraries/Systems/CANopenSocket/examples/basicDevice/CO_application.c
Executable file
@@ -0,0 +1,130 @@
|
||||
/*
|
||||
* Application interface for CANopenNode.
|
||||
*
|
||||
* @file CO_application.c
|
||||
* @author Janez Paternoster
|
||||
* @copyright 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.
|
||||
*/
|
||||
|
||||
|
||||
#include "CO_application.h"
|
||||
#include "CO_version.h"
|
||||
#include "OD.h"
|
||||
#include "testingVariables.h"
|
||||
#include <stdio.h>
|
||||
|
||||
|
||||
/* Define object for testingVariables */
|
||||
testingVariables_t testVar;
|
||||
/* Extension for OD object */
|
||||
OD_extension_t OD_version_extension;
|
||||
|
||||
|
||||
/*
|
||||
* Custom function for reading OD object _Version_
|
||||
*
|
||||
* For more information see file CO_ODinterface.h, OD_IO_t.
|
||||
*/
|
||||
static ODR_t OD_read_version(OD_stream_t *stream, void *buf,
|
||||
OD_size_t count, OD_size_t *countRead)
|
||||
{
|
||||
if (stream == NULL || buf == NULL || countRead == NULL) {
|
||||
return ODR_DEV_INCOMPAT;
|
||||
}
|
||||
|
||||
switch (stream->subIndex) {
|
||||
case 1: {
|
||||
OD_size_t len = strlen(CO_VERSION_CANOPENNODE);
|
||||
if (len > count) len = count;
|
||||
memcpy(buf, CO_VERSION_CANOPENNODE, len);
|
||||
|
||||
*countRead = stream->dataLength = len;
|
||||
return ODR_OK;
|
||||
}
|
||||
case 2: {
|
||||
OD_size_t len = strlen(CO_VERSION_APPLICATION);
|
||||
if (len > count) len = count;
|
||||
memcpy(buf, CO_VERSION_APPLICATION, len);
|
||||
|
||||
*countRead = stream->dataLength = len;
|
||||
return ODR_OK;
|
||||
}
|
||||
default:
|
||||
return OD_readOriginal(stream, buf, count, countRead);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/******************************************************************************/
|
||||
CO_ReturnError_t app_programStart(bool_t CANopenConfigured, uint32_t *errInfo) {
|
||||
(void) CANopenConfigured;
|
||||
CO_ReturnError_t err = CO_ERROR_NO;
|
||||
|
||||
/* increment auto-storage variable */
|
||||
OD_PERSIST_TEST_AUTO.x2106_power_onCounter ++;
|
||||
|
||||
/* Initialize custom read-only OD object "Version" */
|
||||
OD_version_extension.object = NULL;
|
||||
OD_version_extension.read = OD_read_version;
|
||||
OD_version_extension.write = NULL;
|
||||
OD_extension_init(OD_ENTRY_H2105_version, &OD_version_extension);
|
||||
|
||||
/* Initialize more advanced object, which operates with testing variables
|
||||
* OD_ENTRY_H2120_testingVariables is constant defined in OD.h. More
|
||||
* flexible alternative for third argument is 'OD_find(&OD, 0x2120)' */
|
||||
err = testingVariables_init(&testVar,
|
||||
errInfo,
|
||||
OD_ENTRY_H2120_testingVariables);
|
||||
|
||||
return err;
|
||||
}
|
||||
|
||||
|
||||
/******************************************************************************/
|
||||
void app_communicationReset(bool_t CANopenConfigured) {
|
||||
|
||||
/* example printouts */
|
||||
if (CANopenConfigured)
|
||||
printf("CANopen Node-ID is configured and all services will work.\n");
|
||||
else
|
||||
printf("CANopen Node-ID is unconfigured, so only LSS slave will work.\n");
|
||||
|
||||
printf("Printing 'OD_PERSIST_APP.x2120_testingVariables.stringLong':\n%s\n",
|
||||
OD_PERSIST_TEST.x2120_testingVariables.stringLong);
|
||||
|
||||
fflush(stdout);
|
||||
}
|
||||
|
||||
|
||||
/******************************************************************************/
|
||||
void app_programEnd() {
|
||||
|
||||
}
|
||||
|
||||
|
||||
/******************************************************************************/
|
||||
void app_programAsync(bool_t CANopenConfigured, uint32_t timer1usDiff) {
|
||||
(void) CANopenConfigured; (void) timer1usDiff; /* unused */
|
||||
}
|
||||
|
||||
|
||||
/******************************************************************************/
|
||||
void app_program1ms(bool_t CANopenConfigured, uint32_t timer1usDiff) {
|
||||
(void) CANopenConfigured; (void) timer1usDiff; /* unused */
|
||||
}
|
||||
@@ -0,0 +1,88 @@
|
||||
/**
|
||||
* Application interface for CANopenNode.
|
||||
*
|
||||
* @file CO_application.h
|
||||
* @author Janez Paternoster
|
||||
* @copyright 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_APPLICATION_H
|
||||
#define CO_APPLICATION_H
|
||||
|
||||
|
||||
#include "CANopen.h"
|
||||
|
||||
|
||||
/* Optional OD entry for CO_CANopenInit() -> CO_EM_init() */
|
||||
#define OD_STATUS_BITS OD_ENTRY_H2100_errorStatusBits
|
||||
|
||||
|
||||
/**
|
||||
* Function is called on program startup.
|
||||
*
|
||||
* @param CANopenConfigured True, if CANopen Node-Id is known and all CANopen
|
||||
* objects are configured.
|
||||
* @param [out] errInfo Variable may indicate additional information for some
|
||||
* types of errors.
|
||||
*
|
||||
* @return @ref CO_ReturnError_t CO_ERROR_NO in case of success.
|
||||
*/
|
||||
CO_ReturnError_t app_programStart(bool_t CANopenConfigured, uint32_t *errInfo);
|
||||
|
||||
|
||||
/**
|
||||
* Function is called after CANopen communication reset.
|
||||
*
|
||||
* @param CANopenConfigured True, if CANopen Node-Id is known and all CANopen
|
||||
* objects are configured.
|
||||
*/
|
||||
void app_communicationReset(bool_t CANopenConfigured);
|
||||
|
||||
|
||||
/**
|
||||
* Function is called just before program ends.
|
||||
*/
|
||||
void app_programEnd();
|
||||
|
||||
|
||||
/**
|
||||
* Function is called cyclically from main.
|
||||
*
|
||||
* @param CANopenConfigured True, if CANopen Node-Id is known and all CANopen
|
||||
* objects are configured.
|
||||
* @param timer1usDiff Time difference since last call in microseconds
|
||||
*/
|
||||
void app_programAsync(bool_t CANopenConfigured, uint32_t timer1usDiff);
|
||||
|
||||
|
||||
/**
|
||||
* Function is called cyclically from realtime thread at constant intervals.
|
||||
*
|
||||
* Code inside this function must be executed fast. Take care on race conditions
|
||||
* with app_programAsync.
|
||||
*
|
||||
* @param CANopenConfigured True, if CANopen Node-Id is known and all CANopen
|
||||
* objects are configured.
|
||||
* @param timer1usDiff Time difference since last call in microseconds
|
||||
*/
|
||||
void app_program1ms(bool_t CANopenConfigured, uint32_t timer1usDiff);
|
||||
|
||||
|
||||
#endif /* CO_APPLICATION_H */
|
||||
@@ -0,0 +1,78 @@
|
||||
/*
|
||||
* Custom definitions for CANopenNode.
|
||||
*
|
||||
* @file CO_driver_custom.h
|
||||
* @author Janez Paternoster
|
||||
* @copyright 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_CUSTOM_H
|
||||
#define CO_DRIVER_CUSTOM_H
|
||||
|
||||
|
||||
#define CO_USE_APPLICATION
|
||||
|
||||
|
||||
/* Stack configuration override default values.
|
||||
* For more information see file CO_config.h. */
|
||||
|
||||
/* Gateway functions are enabled by default in CO_driver_target.h */
|
||||
#ifndef CO_GATEWAY
|
||||
/* without CO_CONFIG_EM_CONSUMER */
|
||||
#define CO_CONFIG_EM (CO_CONFIG_EM_PRODUCER | \
|
||||
CO_CONFIG_EM_PROD_CONFIGURABLE | \
|
||||
CO_CONFIG_EM_PROD_INHIBIT | \
|
||||
CO_CONFIG_EM_HISTORY | \
|
||||
CO_CONFIG_EM_STATUS_BITS | \
|
||||
CO_CONFIG_FLAG_CALLBACK_PRE | \
|
||||
CO_CONFIG_FLAG_TIMERNEXT)
|
||||
|
||||
/* Gateway command interface, SDO client and LSS master are disabled. */
|
||||
#define CO_CONFIG_SDO_CLI (0)
|
||||
|
||||
/* without CO_CONFIG_LSS_MASTER */
|
||||
#define CO_CONFIG_LSS (CO_CONFIG_LSS_SLAVE | \
|
||||
CO_CONFIG_LSS_SLAVE_FASTSCAN_DIRECT_RESPOND | \
|
||||
CO_CONFIG_FLAG_CALLBACK_PRE)
|
||||
|
||||
#define CO_CONFIG_GTW (0)
|
||||
|
||||
#define CO_CONFIG_FIFO (0)
|
||||
#endif /* CO_GATEWAY */
|
||||
|
||||
#define CO_STORAGE_APPLICATION \
|
||||
{ \
|
||||
.addr = &OD_PERSIST_TEST, \
|
||||
.len = sizeof(OD_PERSIST_TEST), \
|
||||
.subIndexOD = 5, \
|
||||
.attr = CO_storage_cmd | CO_storage_restore, \
|
||||
.filename = {'o','d','_','t','e','s','t', \
|
||||
'.','p','e','r','s','i','s','t','\0'} \
|
||||
}, \
|
||||
{ \
|
||||
.addr = &OD_PERSIST_TEST_AUTO, \
|
||||
.len = sizeof(OD_PERSIST_TEST_AUTO), \
|
||||
.subIndexOD = 6, \
|
||||
.attr = CO_storage_cmd | CO_storage_auto | CO_storage_restore, \
|
||||
.filename = {'o','d','_','t','e','s','t','_','a','u','t','o', \
|
||||
'.','p','e','r','s','i','s','t','\0'} \
|
||||
}
|
||||
|
||||
#endif /* CO_DRIVER_CUSTOM_H */
|
||||
BIN
Devices/Libraries/Systems/CANopenSocket/examples/basicDevice/EDSEditor.png
Executable file
BIN
Devices/Libraries/Systems/CANopenSocket/examples/basicDevice/EDSEditor.png
Executable file
Binary file not shown.
|
After Width: | Height: | Size: 191 KiB |
76
Devices/Libraries/Systems/CANopenSocket/examples/basicDevice/Makefile
Executable file
76
Devices/Libraries/Systems/CANopenSocket/examples/basicDevice/Makefile
Executable file
@@ -0,0 +1,76 @@
|
||||
# Makefile for application with CANopenNode and Linux socketCAN
|
||||
|
||||
|
||||
DRV_SRC = ../../CANopenNode/socketCAN
|
||||
CANOPEN_SRC = ../../CANopenNode
|
||||
APPL_SRC = .
|
||||
|
||||
|
||||
LINK_TARGET = basicDevice
|
||||
VERSION_FILE = CO_version.h
|
||||
|
||||
|
||||
INCLUDE_DIRS = \
|
||||
-I$(DRV_SRC) \
|
||||
-I$(CANOPEN_SRC) \
|
||||
-I$(APPL_SRC)
|
||||
|
||||
|
||||
SOURCES = \
|
||||
$(DRV_SRC)/CO_driver.c \
|
||||
$(DRV_SRC)/CO_error.c \
|
||||
$(DRV_SRC)/CO_epoll_interface.c \
|
||||
$(DRV_SRC)/CO_storageLinux.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)/301/crc16-ccitt.c \
|
||||
$(CANOPEN_SRC)/301/CO_storage.c \
|
||||
$(CANOPEN_SRC)/303/CO_LEDs.c \
|
||||
$(CANOPEN_SRC)/305/CO_LSSslave.c \
|
||||
$(CANOPEN_SRC)/CANopen.c \
|
||||
$(APPL_SRC)/CO_application.c \
|
||||
$(APPL_SRC)/OD.c \
|
||||
$(APPL_SRC)/testingVariables.c \
|
||||
$(DRV_SRC)/CO_main_basic.c
|
||||
|
||||
|
||||
OBJS = $(SOURCES:%.c=%.o)
|
||||
CC ?= gcc
|
||||
OPT =
|
||||
OPT += -g
|
||||
#OPT += -O2
|
||||
#OPT += -DCO_SINGLE_THREAD
|
||||
#OPT += -DCO_CONFIG_DEBUG=0xFFFF
|
||||
#OPT += -Wextra -Wshadow -pedantic -fanalyzer
|
||||
#OPT += -DCO_USE_GLOBALS
|
||||
#OPT += -DCO_MULTIPLE_OD
|
||||
CFLAGS = -Wall -DCO_DRIVER_CUSTOM $(OPT) $(INCLUDE_DIRS)
|
||||
LDFLAGS =
|
||||
LDFLAGS += -g
|
||||
LDFLAGS += -pthread
|
||||
|
||||
#Options can be also passed via make: 'make OPT="-g" LDFLAGS="-pthread"'
|
||||
|
||||
|
||||
.PHONY: all clean
|
||||
|
||||
all: clean version $(LINK_TARGET)
|
||||
|
||||
clean:
|
||||
rm -f $(OBJS) $(LINK_TARGET) $(VERSION_FILE)
|
||||
|
||||
%.o: %.c
|
||||
$(CC) $(CFLAGS) -c $< -o $@
|
||||
|
||||
$(LINK_TARGET): $(OBJS)
|
||||
$(CC) $(LDFLAGS) $^ -o $@
|
||||
|
||||
version:
|
||||
echo "#define CO_VERSION_CANOPENNODE \"$(shell git -C $(CANOPEN_SRC) describe --tags --long --dirty)\"" > $(VERSION_FILE)
|
||||
echo "#define CO_VERSION_APPLICATION \"$(shell git describe --tags --long --dirty)\"" >> $(VERSION_FILE)
|
||||
1390
Devices/Libraries/Systems/CANopenSocket/examples/basicDevice/OD.c
Executable file
1390
Devices/Libraries/Systems/CANopenSocket/examples/basicDevice/OD.c
Executable file
File diff suppressed because it is too large
Load Diff
383
Devices/Libraries/Systems/CANopenSocket/examples/basicDevice/OD.h
Executable file
383
Devices/Libraries/Systems/CANopenSocket/examples/basicDevice/OD.h
Executable file
@@ -0,0 +1,383 @@
|
||||
/*******************************************************************************
|
||||
CANopen Object Dictionary definition for CANopenNode V4
|
||||
|
||||
This file was automatically generated with
|
||||
libedssharp Object Dictionary Editor v0.8-122-g6c02323
|
||||
|
||||
https://github.com/CANopenNode/CANopenNode
|
||||
https://github.com/robincornelius/libedssharp
|
||||
|
||||
DON'T EDIT THIS FILE MANUALLY !!!!
|
||||
********************************************************************************
|
||||
|
||||
File info:
|
||||
File Names: OD.h; OD.c
|
||||
Project File: basicDevice.xdd
|
||||
File Version: 1
|
||||
|
||||
Created: 28. 11. 2020 12:37:54
|
||||
Created By: Janez Paternoster
|
||||
Modified: 16. 03. 2021 19:31:59
|
||||
Modified By: Janez Paternoster
|
||||
|
||||
Device Info:
|
||||
Vendor Name:
|
||||
Vendor ID:
|
||||
Product Name: Basic device
|
||||
Product ID:
|
||||
|
||||
Description: Basic CANopen device with example usage.
|
||||
*******************************************************************************/
|
||||
|
||||
#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
|
||||
|
||||
|
||||
/*******************************************************************************
|
||||
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[8];
|
||||
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 applicationObject_1;
|
||||
uint32_t applicationObject_2;
|
||||
uint32_t applicationObject_3;
|
||||
uint32_t applicationObject_4;
|
||||
uint32_t applicationObject_5;
|
||||
uint32_t applicationObject_6;
|
||||
uint32_t applicationObject_7;
|
||||
uint32_t applicationObject_8;
|
||||
} x1600_RPDOMappingParameter;
|
||||
struct {
|
||||
uint8_t numberOfMappedApplicationObjectsInPDO;
|
||||
uint32_t applicationObject_1;
|
||||
uint32_t applicationObject_2;
|
||||
uint32_t applicationObject_3;
|
||||
uint32_t applicationObject_4;
|
||||
uint32_t applicationObject_5;
|
||||
uint32_t applicationObject_6;
|
||||
uint32_t applicationObject_7;
|
||||
uint32_t applicationObject_8;
|
||||
} x1601_RPDOMappingParameter;
|
||||
struct {
|
||||
uint8_t numberOfMappedApplicationObjectsInPDO;
|
||||
uint32_t applicationObject_1;
|
||||
uint32_t applicationObject_2;
|
||||
uint32_t applicationObject_3;
|
||||
uint32_t applicationObject_4;
|
||||
uint32_t applicationObject_5;
|
||||
uint32_t applicationObject_6;
|
||||
uint32_t applicationObject_7;
|
||||
uint32_t applicationObject_8;
|
||||
} x1602_RPDOMappingParameter;
|
||||
struct {
|
||||
uint8_t numberOfMappedApplicationObjectsInPDO;
|
||||
uint32_t applicationObject_1;
|
||||
uint32_t applicationObject_2;
|
||||
uint32_t applicationObject_3;
|
||||
uint32_t applicationObject_4;
|
||||
uint32_t applicationObject_5;
|
||||
uint32_t applicationObject_6;
|
||||
uint32_t applicationObject_7;
|
||||
uint32_t applicationObject_8;
|
||||
} 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 applicationObject_1;
|
||||
uint32_t applicationObject_2;
|
||||
uint32_t applicationObject_3;
|
||||
uint32_t applicationObject_4;
|
||||
uint32_t applicationObject_5;
|
||||
uint32_t applicationObject_6;
|
||||
uint32_t applicationObject_7;
|
||||
uint32_t applicationObject_8;
|
||||
} x1A00_TPDOMappingParameter;
|
||||
struct {
|
||||
uint8_t numberOfMappedApplicationObjectsInPDO;
|
||||
uint32_t applicationObject_1;
|
||||
uint32_t applicationObject_2;
|
||||
uint32_t applicationObject_3;
|
||||
uint32_t applicationObject_4;
|
||||
uint32_t applicationObject_5;
|
||||
uint32_t applicationObject_6;
|
||||
uint32_t applicationObject_7;
|
||||
uint32_t applicationObject_8;
|
||||
} x1A01_TPDOMappingParameter;
|
||||
struct {
|
||||
uint8_t numberOfMappedApplicationObjectsInPDO;
|
||||
uint32_t applicationObject_1;
|
||||
uint32_t applicationObject_2;
|
||||
uint32_t applicationObject_3;
|
||||
uint32_t applicationObject_4;
|
||||
uint32_t applicationObject_5;
|
||||
uint32_t applicationObject_6;
|
||||
uint32_t applicationObject_7;
|
||||
uint32_t applicationObject_8;
|
||||
} x1A02_TPDOMappingParameter;
|
||||
struct {
|
||||
uint8_t numberOfMappedApplicationObjectsInPDO;
|
||||
uint32_t applicationObject_1;
|
||||
uint32_t applicationObject_2;
|
||||
uint32_t applicationObject_3;
|
||||
uint32_t applicationObject_4;
|
||||
uint32_t applicationObject_5;
|
||||
uint32_t applicationObject_6;
|
||||
uint32_t applicationObject_7;
|
||||
uint32_t applicationObject_8;
|
||||
} x1A03_TPDOMappingParameter;
|
||||
} OD_PERSIST_COMM_t;
|
||||
|
||||
typedef struct {
|
||||
uint8_t x1001_errorRegister;
|
||||
uint8_t x1003_pre_definedErrorField_sub0;
|
||||
uint32_t x1003_pre_definedErrorField[8];
|
||||
uint8_t x1010_storeParameters_sub0;
|
||||
uint32_t x1010_storeParameters[6];
|
||||
uint8_t x1011_restoreDefaultParameters_sub0;
|
||||
uint32_t x1011_restoreDefaultParameters[6];
|
||||
struct {
|
||||
uint8_t highestSub_indexSupported;
|
||||
uint32_t COB_IDClientToServerRx;
|
||||
uint32_t COB_IDServerToClientTx;
|
||||
} x1200_SDOServerParameter;
|
||||
uint8_t x2100_errorStatusBits[10];
|
||||
struct {
|
||||
uint8_t highestSub_indexSupported;
|
||||
} x2105_version;
|
||||
uint8_t x2110_variableInt32_sub0;
|
||||
int32_t x2110_variableInt32[16];
|
||||
uint8_t x6000_readDigitalInput_8_bit_sub0;
|
||||
uint8_t x6000_readDigitalInput_8_bit[8];
|
||||
uint8_t x6200_writeDigitalOutput_8_bit_sub0;
|
||||
uint8_t x6200_writeDigitalOutput_8_bit[8];
|
||||
uint8_t x6401_readAnalogInput_16_bit_sub0;
|
||||
int16_t x6401_readAnalogInput_16_bit[16];
|
||||
uint8_t x6411_writeAnalogOutput_16_bit_sub0;
|
||||
int16_t x6411_writeAnalogOutput_16_bit[8];
|
||||
} OD_RAM_t;
|
||||
|
||||
typedef struct {
|
||||
uint32_t x2106_power_onCounter;
|
||||
uint8_t x2112_variableNV_Int32_autoSave_sub0;
|
||||
int32_t x2112_variableNV_Int32_autoSave[16];
|
||||
} OD_PERSIST_TEST_AUTO_t;
|
||||
|
||||
typedef struct {
|
||||
uint8_t x2111_variableInt32_save_sub0;
|
||||
int32_t x2111_variableInt32_save[16];
|
||||
struct {
|
||||
uint8_t highestSub_indexSupported;
|
||||
int64_t I64;
|
||||
uint64_t U64;
|
||||
float32_t R32;
|
||||
float64_t R64;
|
||||
char stringShort[4];
|
||||
char stringLong[1001];
|
||||
uint8_t octetString[10];
|
||||
uint16_t parameterWithDefaultValue;
|
||||
char domainFileNameRead[101];
|
||||
char domainFileNameWrite[101];
|
||||
} x2120_testingVariables;
|
||||
} OD_PERSIST_TEST_t;
|
||||
|
||||
extern OD_PERSIST_COMM_t OD_PERSIST_COMM;
|
||||
extern OD_RAM_t OD_RAM;
|
||||
extern OD_PERSIST_TEST_AUTO_t OD_PERSIST_TEST_AUTO;
|
||||
extern OD_PERSIST_TEST_t OD_PERSIST_TEST;
|
||||
extern 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_H2100 &OD->list[33]
|
||||
#define OD_ENTRY_H2105 &OD->list[34]
|
||||
#define OD_ENTRY_H2106 &OD->list[35]
|
||||
#define OD_ENTRY_H2110 &OD->list[36]
|
||||
#define OD_ENTRY_H2111 &OD->list[37]
|
||||
#define OD_ENTRY_H2112 &OD->list[38]
|
||||
#define OD_ENTRY_H2120 &OD->list[39]
|
||||
#define OD_ENTRY_H6000 &OD->list[40]
|
||||
#define OD_ENTRY_H6200 &OD->list[41]
|
||||
#define OD_ENTRY_H6401 &OD->list[42]
|
||||
#define OD_ENTRY_H6411 &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_H2100_errorStatusBits &OD->list[33]
|
||||
#define OD_ENTRY_H2105_version &OD->list[34]
|
||||
#define OD_ENTRY_H2106_power_onCounter &OD->list[35]
|
||||
#define OD_ENTRY_H2110_variableInt32 &OD->list[36]
|
||||
#define OD_ENTRY_H2111_variableInt32_save &OD->list[37]
|
||||
#define OD_ENTRY_H2112_variableNV_Int32_autoSave &OD->list[38]
|
||||
#define OD_ENTRY_H2120_testingVariables &OD->list[39]
|
||||
#define OD_ENTRY_H6000_readDigitalInput_8_bit &OD->list[40]
|
||||
#define OD_ENTRY_H6200_writeDigitalOutput_8_bit &OD->list[41]
|
||||
#define OD_ENTRY_H6401_readAnalogInput_16_bit &OD->list[42]
|
||||
#define OD_ENTRY_H6411_writeAnalogOutput_16_bit &OD->list[43]
|
||||
|
||||
#endif /* OD_H */
|
||||
358
Devices/Libraries/Systems/CANopenSocket/examples/basicDevice/README.md
Executable file
358
Devices/Libraries/Systems/CANopenSocket/examples/basicDevice/README.md
Executable file
@@ -0,0 +1,358 @@
|
||||
CANopen basicDevice Example
|
||||
===========================
|
||||
|
||||
Example of basic CANopen device, with quite rich functionality. It is based on [CANopenNode](https://github.com/CANopenNode/CANopenNode), which is free and open source CANopen Stack, based on ([CiA301](http://can-cia.org/standardization/technical-documents)) standard.
|
||||
|
||||
Example contains object dictionary with most common communication parameters and some additional manufacturer specific and device profile parameters. See picture below or complete OD documentation in [basicDevice.md](basicDevice.md). Note also project file `basicDevice.xdd`, which can be opened and edited with EDSEditor.exe (Linux or Windows application). EDSEditor can export other files, including OD.h and OD.c source files for this example. `basicDevice.xdd` and `basicDevice.eds` are standard CANopen device description files and can be opened also with other CANopen tools.
|
||||
|
||||

|
||||
|
||||
|
||||
Example program
|
||||
---------------
|
||||
|
||||
### Makefile
|
||||
It includes most common CANopen files and options for compilation.
|
||||
|
||||
It also generates `CO_version.h` file with information about git version number of CANopenNode and CANopenSocket, for example:
|
||||
|
||||
#define CO_VERSION_CANOPENNODE "v4.0-12-g09bf926-dirty"
|
||||
#define CO_VERSION_APPLICATION "v1.2-20-g94add15-dirty"
|
||||
|
||||
This information is available from OD entry 0x2105, 01:
|
||||
|
||||
./cocomm "4 r 0x2105 1 vs"
|
||||
[1] "v4.0-12-g09bf926-dirty"
|
||||
|
||||
"v4.0" is latest tag name, "12" is number of commits above the tag, "g" is git, "09bf926" is commit number and optional "dirty" means, git repository has uncommited changes.
|
||||
|
||||
Makefile also defines macro `CO_DRIVER_CUSTOM`, which includes `CO_driver_custom.h` into the foundation of all source files.
|
||||
|
||||
#### CANopenNode program flow
|
||||
|
||||
CANopenNode driver for Linux is written in a way, that program execution is triggered by different events, like reception of CAN message, one of the many timers expiration, other file descriptor based events, etc. All CANopenNode functions are non-blocking. After event occurs, all mainline and/or realtime functions are processed. In simpler, microcontroller based applications, mainline functions are executing in infinite loop and realtime functions are executed precisely each timer interval, 1ms typically.
|
||||
|
||||
CANopenNode driver for Linux offers two options, configurable with makefile:
|
||||
1. Whole program runs in single thread. This is default for `canopend`. This uses less system resources.
|
||||
2. Mainline functions are executing in primary thread and realtime functions are executed in own thread, triggered by precise timer. This way it is easier to achieve realtime operation and may be easier to implement a controller with access to peripherals, like digital input/output pins. This is default for `basicDevice`.
|
||||
|
||||
|
||||
### CO_application.h and CO_application.c
|
||||
|
||||
Those files contains five functions, which are called from `main()` function inside `CANopenNode/socketCAN/CO_main_basic.c` file. They are central part of our `basicDevice` application program:
|
||||
|
||||
CO_ReturnError_t app_programStart(bool_t CANopenConfigured, uint16_t *errinfo);
|
||||
void app_communicationReset(bool_t CANopenConfigured);
|
||||
void app_programEnd();
|
||||
void app_programAsync(bool_t CANopenConfigured, uint32_t timer1usDiff);
|
||||
void app_program1ms(bool_t CANopenConfigured, uint32_t timer1usDiff);
|
||||
|
||||
|
||||
### testingVariables.h and testingVariables.c
|
||||
|
||||
Those files contains example usage of OD entry "Testing variables" with multiple different sub entries.
|
||||
|
||||
Entry has IO extension enabled. This means that some entries are accessed with custom read/write functions. See source files and examples below for details.
|
||||
|
||||
|
||||
Testing with Linux
|
||||
------------------
|
||||
|
||||
You should successfully finish `CANopenNode/doc/gettingStarted.md`, before continuing with this example. Here more advanced and more usable command line application, `cocomm`, will be used.
|
||||
|
||||
### Some background about communication paths, when using cocomm
|
||||
|
||||
`cocomm` is a small command line program, which establishes socket connection with `canopend`. It sends standardized CANopen commands (CiA309-3) to gateway and prints the responses to stdout and stderr.
|
||||
|
||||
1. `canopend` serves a socket connection on `/tmp/CO_command_socket` address. This is local Unix socket, TCP socket can be used also. `canopend` is pure CANopen device with commander functionalities and gateway. It listens for socket connections.
|
||||
2. When run, `cocomm` tries to connect to `/tmp/CO_command_socket` address (this is default setting). `canopend` accepts the connection.
|
||||
3. `cocomm` writes the specified ascii command to established socket connection, for example `[1] 4 read 0x1017 0 u16`.
|
||||
4. Gateway in `canopend` receives the command and decodes it. `read` commands goes internally into `CO_SDOclientUploadInitiate()` and then command is processed with multiple `CO_SDOclientUpload()` function calls.
|
||||
5. `CO_SDOclientUpload()` now sends a CAN message to our `basicDevice`. (CAN interface in Linux is implemented with CAN sockets. This is the third type of sockets mentioned here.) However, in our example `basicDevice` receives SDO request, asking the value of the variable, located in Object Dictionary at index 0x1017, subindex 0.
|
||||
6. Our `basicDevice` receives CAN message with CAN ID=0x604. It determines SDO request, so `CO_SDOserver_process()` function gets the message. Function gets the value from internal Object Dictionary and sends the CAN response with CAN ID=0x584. Those messages can be seen in candump terminal. And it is not necessary to understand the details of SDO communication, it may be quite complex.
|
||||
7. `canopend` receives the CAN message, `CO_SDOclientUpload()` decodes it and sends binary value to gateway.
|
||||
8. Gateway in `canopend` translates binary value to asciiValue, unsigned16 in our example. It prepares the response, in our case `[1] ` + asciiValue + `\r\n`. Then writes the response text back to `/tmp/CO_command_socket`.
|
||||
9. `cocomm` reads the response text from local socket and prints it partly to stderr (`[1] \r\n`) and partly to stdout (asciiValue).
|
||||
10. If there are more commands, step 3 is repeated. Otherwise `cocomm` closes the socket connection and exits.
|
||||
|
||||
|
||||
### Testing variables
|
||||
|
||||
#### Prepare the environment
|
||||
We will use four Linux terminals:
|
||||
|
||||
# First terminal: candump
|
||||
sudo modprobe vcan
|
||||
sudo ip link add dev vcan0 type vcan
|
||||
sudo ip link set up vcan0
|
||||
candump -td -a vcan0
|
||||
|
||||
# second terminal: basicDevice
|
||||
cd examples/basicDevice
|
||||
make
|
||||
./basicDevice -i4 vcan0
|
||||
|
||||
# third terminal: canopend (gateway)
|
||||
cd CANopenNode
|
||||
make
|
||||
./canopend vcan0 -i1 -c "local-/tmp/CO_command_socket"
|
||||
|
||||
# fourth terminal: cocomm (connection with gateway)
|
||||
cd cocomm
|
||||
make
|
||||
|
||||
#### basic cocomm usage
|
||||
It is very similar as in `CANopenNode/doc/gettingStarted.md`, but actually easier.
|
||||
|
||||
./cocomm --help
|
||||
./cocomm "help"
|
||||
./cocomm "help datatype"
|
||||
./cocomm "4 r 0x1017 0 u16"
|
||||
./cocomm "1 r 0x1017 0 u16" "4 r 0x1017 0 u16"
|
||||
|
||||
`cocomm` program can be copied to standard location of executables, so we can run it from any directory, without leading `./`:
|
||||
|
||||
sudo cp cocomm /usr/bin/cocomm
|
||||
|
||||
Parameters to program can be set by program arguments, as described in `cocomm --help`, and can also be changed by environmental variables. For example, to change default socket path in for all next `cocomm` commands in current terminal, type:
|
||||
|
||||
export cocomm_socket="some other path than /tmp/CO_command_socket"
|
||||
|
||||
Commands can be also written into a file, for example create a `commands.txt` file, and for its content enter the commands:
|
||||
|
||||
[1] 1 start
|
||||
[2] 4 start
|
||||
|
||||
Then make `cocomm` use that file:
|
||||
|
||||
$ cocomm -f commands.txt
|
||||
[1] OK
|
||||
[2] OK
|
||||
|
||||
#### Advanced variables and strings
|
||||
Type commands and see responses in `cocomm` terminal. Optionally watch CAN communication in `candump` terminal.
|
||||
|
||||
./cocomm "4 r 0x2120 1 i64" "4 r 0x2120 2 x64" "4 r 0x2120 2 u64" "4 r 0x2120 2"
|
||||
[1] -1234567890123456789
|
||||
[2] 0x1234567890ABCDEF
|
||||
[3] 1311768467294899695
|
||||
[4] EF CD AB 90 78 56 34 12
|
||||
|
||||
./cocomm "4 r 0x2120 3 r32" "4 r 0x2120 4 r64"
|
||||
[1] 12.345
|
||||
[2] 456.789
|
||||
|
||||
./cocomm "4 r 0x2120 5 r64 # Custom read function calculates the average."
|
||||
[1] 1.93001e+16
|
||||
|
||||
./cocomm "4 w 0x2120 3 r32 -7.720058e+16" "4 r 0x2120 5 r64"
|
||||
[1] OK
|
||||
[2] 7.8681e+07
|
||||
|
||||
./cocomm "4 w 0x2120 6 vs 12" "4 r 0x2120 6 vs" \
|
||||
"4 w 0x2120 6 vs 1234" "4 r 0x2120 6 vs" \
|
||||
"4 w 0x2120 6 vs \"1 2\"" "4 r 0x2120 6 vs"
|
||||
[1] OK
|
||||
[2] "12"
|
||||
[3] ERROR:0x06070012 #Data type does not match, length of service parameter too high.
|
||||
[4] "12"
|
||||
[5] OK
|
||||
[6] "1 2"
|
||||
|
||||
./cocomm "4 r 0x2120 7 vs"
|
||||
[1] "1000 bytes long string buffer. Visible string may contain UTF-8 characters, like this 3 bytes long '€' Euro symbol. It may contain also control characters like tabs ' ' or newLines '
|
||||
'."
|
||||
|
||||
./cocomm "4 w 0x2120 7 vs \"Writing newLines is not possible as visible string, but exotic \"\"ß\"\" characters works.\""
|
||||
[1] OK
|
||||
|
||||
./cocomm "4 r 0x2120 7 os" | base64 -d
|
||||
[1]
|
||||
Writing newLines is not possible as visible string, but exotic "ß" characters works.
|
||||
|
||||
./cocomm "4 r 0x2120 7 os" | base64 -d | hexdump -C
|
||||
[1]...
|
||||
|
||||
echo -ne "We can encode anything to base64\n\nand transfer data as octet string or domain." | base64 -w0 | ./cocomm -i "4 w 0x2120 7 os"
|
||||
[1] OK
|
||||
|
||||
./cocomm "4 r 0x2120 8 hex" "4 r 0x2120 8 os" "4 r 0x2120 8 vs" "4 r 0x2120 8 d" "4 r 0x2120 8"
|
||||
[1] C8 3D BB 00 00 00 00 00 00 00
|
||||
[2] yD27AAAAAAAAAA==
|
||||
[3] "<22>=<3D>"
|
||||
[4] yD27AAAAAAAAAA==
|
||||
[5] C8 3D BB 00 00 00 00 00 00 00
|
||||
|
||||
./cocomm "4 w 0x2120 8 hex 01 02 03"
|
||||
[1] ERROR:0x06070013 #Data type does not match, length of service parameter too short.
|
||||
|
||||
./cocomm "4 w 0x2120 8 hex 01 2 30 456789 0A b0 0 ff"
|
||||
[1] OK
|
||||
|
||||
#### Parameter with default value
|
||||
|
||||
Value is read from Object Dictionary on program initialization and stored to internal variable. Each SDO read will read this internal variable, incremented by 1, but value in OD location will stay unchanged. SDO write will write to internal variable and to OD location. And subsequent SDO write to index 0x1010 (store parameters) will update the default value, valid at startup. Experiment with `cocomm` and see `testingVariables.c` file for implementation of this behaviour.
|
||||
|
||||
#### Domain
|
||||
Domain enables transfer an arbitrary large block of data in one SDO communication cycle. In our example size is limited only by free space of file system, if we have a 64-bit computer. RAM usage is low. SDO block transfer is used for highest efficiency over CAN. In our example internal virtual CAN network is used, which is very fast. On real CAN networks data transfer rates are significantly lower. However, SDO communication does not disturb higher priority real time data transfer, which is likely present on CAN bus. SDO block transfer is also resistant to disturbances to some degree. If necessary, it re-transmits corrupted data.
|
||||
|
||||
See `testingVariables.c` file for implementation of large data transfer. Our `basicDevice` reads data from file, referenced by Object 0x2120, sub index 11. This is a text file in the same directory as our `basicDevice`. We can safely read the file as visible string. If necessary, transfer can be interrupted by `Ctrl+C`. SDO communication will be closed correctly by abort message.
|
||||
|
||||
./cocomm "set sdo_block 1"
|
||||
[1] OK
|
||||
|
||||
./cocomm "4 r 0x2120 11 vs"
|
||||
[1] "basicDevice.md"
|
||||
|
||||
./cocomm "4 r 0x2120 10 vs"
|
||||
[1] "CANopen documentation
|
||||
=====================
|
||||
**Basic device**
|
||||
....
|
||||
|
||||
Above works, but is not very practical. This is better:
|
||||
|
||||
./cocomm "4 r 0x2120 10 d" | base64 -d | pv > file1
|
||||
[1]
|
||||
...success
|
||||
56,7KiB 0:00:00 [ 600KiB/s] [<=> ]
|
||||
|
||||
cmp file1 ../examples/basicDevice/basicDevice.md
|
||||
rm file1
|
||||
|
||||
If there is no response from `cmp` command, files are identical. `pv` is nice Linux command, which displays progress. Object 0x2120, sub index 11 can be changed to point to any other accessible file.
|
||||
|
||||
When we send data to our `basicDevice`, it stores them to file, referenced by Object 0x2120, sub index 12.
|
||||
|
||||
./cocomm "4 r 0x2120 12 vs"
|
||||
[1] "fileWrittenByDomain"
|
||||
|
||||
pv cocomm.c | base64 -w0 | ./cocomm -i "4 w 0x2120 10 d"
|
||||
18,2KiB 0:00:00 [ 323MiB/s] [========================================>] 100%
|
||||
[1] OK
|
||||
|
||||
cmp cocomm.c ../examples/basicDevice/fileWrittenByDomain
|
||||
|
||||
It is time to transfer something larger, like 100Mb random binary file:
|
||||
|
||||
openssl rand 100000000 > binaryFile
|
||||
pv binaryFile | base64 -w0 | ./cocomm -i "4 w 0x2120 10 d"
|
||||
95,4MiB 0:01:02 [1,52MiB/s] [========================================>] 100%
|
||||
[1] OK
|
||||
|
||||
cmp binaryFile ../examples/basicDevice/fileWrittenByDomain
|
||||
rm binaryFile ../examples/basicDevice/fileWrittenByDomain
|
||||
|
||||
Here is experimental candump output with two independent pairs of `canopend-basicDevice` communicating over one virtual CAN interface (two SDO block transfers interlaced):
|
||||
|
||||
(000.000003) vcan0 604 [8] 6F C3 A9 6E AF 5C 81 32 'o..n.\.2'
|
||||
(000.000010) vcan0 604 [8] 70 B7 32 8A B2 B0 62 27 'p.2...b''
|
||||
(000.000006) vcan0 604 [8] 71 4F 5F 0B F0 40 0B 53 'qO_..@.S'
|
||||
(000.000003) vcan0 604 [8] 72 CE B9 49 D2 80 BD 55 'r..I...U'
|
||||
(000.000010) vcan0 603 [8] A2 7F 7F 00 00 00 00 00 '........' < response
|
||||
(000.000002) vcan0 604 [8] 73 94 A2 9E E2 23 8C 5A 's....#.Z'
|
||||
(000.000005) vcan0 604 [8] 74 13 90 A2 59 C3 9B 1D 't...Y...'
|
||||
(000.000003) vcan0 604 [8] 75 5A F4 85 3A 3E B9 10 'uZ..:>..'
|
||||
(000.000011) vcan0 604 [8] 76 30 81 CC 7D 2E 7E 0F 'v0..}.~.'
|
||||
(000.000000) vcan0 583 [8] 01 FC 80 1C D4 8F 67 A2 '......g.'
|
||||
(000.000006) vcan0 604 [8] 77 9B FA 36 21 0F 09 2E 'w..6!...'
|
||||
(000.000003) vcan0 604 [8] 78 C2 6F 97 DC 1D 97 9E 'x.o.....'
|
||||
(000.000001) vcan0 583 [8] 02 E0 B9 97 47 8D 37 E6 '....G.7.'
|
||||
(000.000008) vcan0 583 [8] 03 07 B6 88 68 0B 6A 8C '....h.j.'
|
||||
(000.000002) vcan0 604 [8] 79 4E 6B 8D 2B 02 F5 9E 'yNk.+...'
|
||||
(000.000005) vcan0 583 [8] 04 AD AC A3 B5 59 4C 30 '.....YL0'
|
||||
(000.000001) vcan0 604 [8] 7A 23 97 5B D6 2A 02 F4 'z#.[.*..'
|
||||
(000.000007) vcan0 583 [8] 05 67 6F 4C 1E AF 18 F3 '.goL....'
|
||||
(000.000007) vcan0 604 [8] 7C 6E 6A 12 FE 5E 0B 5B '|nj..^.['
|
||||
(000.000001) vcan0 583 [8] 06 E0 43 D4 2E D2 98 BA '..C.....'
|
||||
(000.000005) vcan0 604 [8] 7D 4B BF 69 25 43 98 FF '}K.i%C..'
|
||||
(000.000010) vcan0 583 [8] 08 52 16 57 0D 11 72 AE '.R.W..r.'
|
||||
(000.000001) vcan0 604 [8] 7F 63 0C B1 2B 19 72 89 '.c..+.r.'
|
||||
(000.000007) vcan0 583 [8] 09 67 3D EF B9 C1 32 D3 '.g=...2.'
|
||||
(000.000012) vcan0 583 [8] 0A 3D 22 7E 79 5B D5 D4 '.="~y[..'
|
||||
(000.000010) vcan0 584 [8] A2 7F 7F 00 00 00 00 00 '........' < response
|
||||
(000.000001) vcan0 583 [8] 0B EC 91 5C FF 04 0A D7 '...\....'
|
||||
(000.000011) vcan0 583 [8] 0C 25 86 30 DC 44 6B 59 '.%.0.DkY'
|
||||
(000.000006) vcan0 583 [8] 0D 56 8F B0 23 81 41 FF '.V..#.A.'
|
||||
(000.000000) vcan0 604 [8] 01 EF 91 CC EE E8 0D 9C '........'
|
||||
(000.000006) vcan0 604 [8] 02 EA EB 00 A8 34 71 3F '.....4q?'
|
||||
(000.000002) vcan0 583 [8] 0E 03 79 87 32 C6 96 15 '..y.2...'
|
||||
(000.000006) vcan0 604 [8] 03 C2 A9 61 8E 25 3D 0A '...a.%=.'
|
||||
...
|
||||
(000.000003) vcan0 604 [8] 79 16 F1 A6 12 9D 3D B2 'y.....=.'
|
||||
(000.000005) vcan0 604 [8] 7A E2 75 5A 16 18 66 37 'z.uZ..f7'
|
||||
(000.000003) vcan0 583 [8] 6B 72 30 0A 0F C2 2C F9 'kr0...,.'
|
||||
(000.000000) vcan0 604 [8] 7B 82 AE B2 D8 F0 71 32 '{.....q2'
|
||||
(000.000010) vcan0 604 [8] 7C 2A 04 DD BE 30 A4 6E '|*...0.n'
|
||||
(000.000001) vcan0 583 [8] 6C EA 98 F4 F2 DA C6 93 'l.......'
|
||||
(000.000005) vcan0 604 [8] 7D 68 15 72 4D D0 B5 48 '}h.rM..H'
|
||||
(000.000005) vcan0 583 [8] 6D 7B 24 4D 6E 6A C0 71 'm{$Mnj.q'
|
||||
(000.000008) vcan0 604 [8] 7F E3 B8 4A CA BE 20 F1 '...J.. .'
|
||||
(000.000003) vcan0 583 [8] 6E 11 7B 1F DA 9D 2B B3 'n.{...+.'
|
||||
(000.000010) vcan0 583 [8] 6F 0A 1F 8B C4 56 F9 37 'o....V.7'
|
||||
(000.000012) vcan0 583 [8] 70 67 91 36 4F 59 04 C9 'pg.6OY..'
|
||||
(000.000012) vcan0 583 [8] 71 D4 B8 AC D1 06 7F 63 'q......c'
|
||||
(000.000001) vcan0 584 [8] A2 7F 7F 00 00 00 00 00 '........' < response
|
||||
(000.000008) vcan0 583 [8] 72 F3 5A E9 06 B2 A7 42 'r.Z....B'
|
||||
(000.000009) vcan0 583 [8] 73 3D 99 69 35 9D B9 43 's=.i5..C'
|
||||
(000.000000) vcan0 604 [8] 01 3B CB D9 00 E5 6A B7 '.;....j.'
|
||||
(000.000006) vcan0 604 [8] 02 A6 0F 34 3D 07 C1 6A '...4=..j'
|
||||
(000.000002) vcan0 583 [8] 74 72 CE 65 1B 82 0F FC 'tr.e....'
|
||||
(000.000001) vcan0 604 [8] 03 0D 35 70 C2 34 C4 7D '..5p.4.}'
|
||||
(000.000007) vcan0 583 [8] 75 9C 7A 1D 19 FB A0 92 'u.z.....'
|
||||
(000.000007) vcan0 583 [8] 76 3D 9E B8 2F FF 9A 1B 'v=../...'
|
||||
(000.000008) vcan0 583 [8] 77 ED 4E 6D D5 BA E2 D6 'w.Nm....'
|
||||
(000.000008) vcan0 583 [8] 78 BA E2 83 1E 03 03 9B 'x.......'
|
||||
(000.000005) vcan0 604 [8] 04 DD 6B BB FA 9C 67 BF '..k...g.'
|
||||
(000.000002) vcan0 583 [8] 79 B7 2E A5 37 28 1E F6 'y...7(..'
|
||||
(000.000004) vcan0 604 [8] 05 C6 A3 C7 EE 6D 24 C0 '.....m$.'
|
||||
(000.000004) vcan0 604 [8] 06 5F 4E 41 25 BB D9 44 '._NA%..D'
|
||||
(000.000000) vcan0 583 [8] 7A DB 34 D2 46 33 33 AE 'z.4.F33.'
|
||||
(000.000008) vcan0 583 [8] 7B 30 76 56 31 1A A6 5C '{0vV1..\'
|
||||
(000.000007) vcan0 583 [8] 7C 20 42 44 A5 60 AC 77 '| BD.`.w'
|
||||
(000.000004) vcan0 604 [8] 07 42 7F 87 4B A5 ED 0E '.B..K...'
|
||||
(000.000004) vcan0 583 [8] 7D 5D 36 93 F5 27 08 CF '}]6..'..'
|
||||
(000.000002) vcan0 604 [8] 08 C1 17 36 99 9E 5F 17 '...6.._.'
|
||||
(000.000003) vcan0 604 [8] 09 C0 3A 4F AF 7F 92 71 '..:O...q'
|
||||
(000.000006) vcan0 583 [8] 7E 77 05 8E 00 43 29 D3 '~w...C).'
|
||||
(000.000005) vcan0 604 [8] 0A CF 24 64 25 4D 81 30 '..$d%M.0'
|
||||
(000.000004) vcan0 583 [8] 7F 98 C3 03 A3 2E AE E7 '........'
|
||||
(000.000002) vcan0 604 [8] 0B 60 F0 5B 29 3F 69 4B '.`.[)?iK'
|
||||
(000.000007) vcan0 604 [8] 0C E1 02 DA CF 08 34 0E '......4.'
|
||||
(000.000007) vcan0 604 [8] 0D 7F 13 89 DE AB AB 16 '........'
|
||||
(000.000006) vcan0 604 [8] 0E 98 AF 47 B3 30 56 DF '...G.0V.'
|
||||
(000.000003) vcan0 604 [8] 0F 83 FB 95 9F EB E9 12 '........'
|
||||
(000.000010) vcan0 604 [8] 10 F8 09 E9 39 10 CE 0F '....9...'
|
||||
(000.000007) vcan0 604 [8] 11 4C 72 0B DB 34 92 14 '.Lr..4..'
|
||||
(000.000003) vcan0 604 [8] 12 9D 83 1C 07 66 DC 7E '.....f.~'
|
||||
(000.000000) vcan0 603 [8] A2 7F 7F 00 00 00 00 00 '........' < response
|
||||
(000.000008) vcan0 604 [8] 13 DB E4 73 B0 6F 23 CB '...s.o#.'
|
||||
(000.000006) vcan0 604 [8] 14 CE 1C 70 EC C3 57 99 '...p..W.'
|
||||
(000.000006) vcan0 604 [8] 15 7C 33 D5 C7 FC 80 9B '.|3.....'
|
||||
(000.000000) vcan0 583 [8] 01 2D 89 31 D6 1F 36 88 '.-.1..6.'
|
||||
(000.000010) vcan0 583 [8] 02 B6 56 16 06 64 21 69 '..V..d!i'
|
||||
|
||||
|
||||
Create project in your favourite IDE
|
||||
------------------------------------
|
||||
BasicDevice example uses simple `Makefile` to properly compile necessary source files and set correct compile options. This file can be examined, to see, how to configure project files for your favourite IDE. There is also `gateway.Makefile`, which compiles the project with included gateway objects, similar as `canopend`.
|
||||
|
||||
### Create project with [KDevelop](https://www.kdevelop.org/)
|
||||
- `sudo apt install kdevelop breeze`
|
||||
- Run KDevelop, select: Project -> open project
|
||||
- Navigate to directory `examples/basicDevice` and click open.
|
||||
- KDevelop will recognize `Makefile` and will just use it. Click Finish.
|
||||
- Open project settings (right click on project on left panel)
|
||||
- Make: set to 1 thread operation.
|
||||
- Language support, Includes, add paths to directories:
|
||||
- `CANopenNode/socketCAN`
|
||||
- `CANopenNode`
|
||||
- `examples/basicDevice`
|
||||
- Language support, Defines, add:
|
||||
- `CO_DRIVER_CUSTOM`
|
||||
- Run -> Setup launches -> basicDevice:
|
||||
- Add Executable file
|
||||
- Name it `basicDevice_i4_vcan0`, for example.
|
||||
- Executable file: `examples/basicDevice/basicDevice`
|
||||
- Arguments: `-i 4 vcan0`
|
||||
- Build, then Execute or Debug
|
||||
2806
Devices/Libraries/Systems/CANopenSocket/examples/basicDevice/basicDevice.eds
Executable file
2806
Devices/Libraries/Systems/CANopenSocket/examples/basicDevice/basicDevice.eds
Executable file
File diff suppressed because it is too large
Load Diff
1012
Devices/Libraries/Systems/CANopenSocket/examples/basicDevice/basicDevice.md
Executable file
1012
Devices/Libraries/Systems/CANopenSocket/examples/basicDevice/basicDevice.md
Executable file
File diff suppressed because it is too large
Load Diff
2725
Devices/Libraries/Systems/CANopenSocket/examples/basicDevice/basicDevice.xdd
Executable file
2725
Devices/Libraries/Systems/CANopenSocket/examples/basicDevice/basicDevice.xdd
Executable file
File diff suppressed because it is too large
Load Diff
@@ -0,0 +1,81 @@
|
||||
# Makefile for application with CANopenNode and Linux socketCAN
|
||||
# It includes gateway with SDOclient and CO_LSSmaster
|
||||
|
||||
|
||||
DRV_SRC = ../../CANopenNode/socketCAN
|
||||
CANOPEN_SRC = ../../CANopenNode
|
||||
APPL_SRC = .
|
||||
|
||||
|
||||
LINK_TARGET = basicDeviceWithGateway
|
||||
VERSION_FILE = CO_version.h
|
||||
|
||||
|
||||
INCLUDE_DIRS = \
|
||||
-I$(DRV_SRC) \
|
||||
-I$(CANOPEN_SRC) \
|
||||
-I$(APPL_SRC)
|
||||
|
||||
|
||||
SOURCES = \
|
||||
$(DRV_SRC)/CO_driver.c \
|
||||
$(DRV_SRC)/CO_error.c \
|
||||
$(DRV_SRC)/CO_epoll_interface.c \
|
||||
$(DRV_SRC)/CO_storageLinux.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_SDOclient.c \
|
||||
$(CANOPEN_SRC)/301/CO_TIME.c \
|
||||
$(CANOPEN_SRC)/301/CO_SYNC.c \
|
||||
$(CANOPEN_SRC)/301/CO_PDO.c \
|
||||
$(CANOPEN_SRC)/301/crc16-ccitt.c \
|
||||
$(CANOPEN_SRC)/301/CO_fifo.c \
|
||||
$(CANOPEN_SRC)/301/CO_storage.c \
|
||||
$(CANOPEN_SRC)/303/CO_LEDs.c \
|
||||
$(CANOPEN_SRC)/305/CO_LSSslave.c \
|
||||
$(CANOPEN_SRC)/305/CO_LSSmaster.c \
|
||||
$(CANOPEN_SRC)/309/CO_gateway_ascii.c \
|
||||
$(CANOPEN_SRC)/CANopen.c \
|
||||
$(APPL_SRC)/CO_application.c \
|
||||
$(APPL_SRC)/OD.c \
|
||||
$(APPL_SRC)/testingVariables.c \
|
||||
$(DRV_SRC)/CO_main_basic.c
|
||||
|
||||
|
||||
OBJS = $(SOURCES:%.c=%.o)
|
||||
CC ?= gcc
|
||||
OPT =
|
||||
OPT += -g
|
||||
#OPT += -O2
|
||||
#OPT += -DCO_SINGLE_THREAD
|
||||
#OPT += -DCO_CONFIG_DEBUG=0xFFFF
|
||||
#OPT += -Wextra -Wshadow -pedantic -fanalyzer
|
||||
#OPT += -DCO_USE_GLOBALS
|
||||
#OPT += -DCO_MULTIPLE_OD
|
||||
CFLAGS = -Wall -DCO_DRIVER_CUSTOM -DCO_GATEWAY $(OPT) $(INCLUDE_DIRS)
|
||||
LDFLAGS =
|
||||
LDFLAGS += -g
|
||||
LDFLAGS += -pthread
|
||||
|
||||
#Options can be also passed via make: 'make OPT="-g" LDFLAGS="-pthread"'
|
||||
|
||||
|
||||
.PHONY: all clean
|
||||
|
||||
all: clean version $(LINK_TARGET)
|
||||
|
||||
clean:
|
||||
rm -f $(OBJS) $(LINK_TARGET) $(VERSION_FILE)
|
||||
|
||||
%.o: %.c
|
||||
$(CC) $(CFLAGS) -c $< -o $@
|
||||
|
||||
$(LINK_TARGET): $(OBJS)
|
||||
$(CC) $(LDFLAGS) $^ -o $@
|
||||
|
||||
version:
|
||||
echo "#define CO_VERSION_CANOPENNODE \"$(shell git -C $(CANOPEN_SRC) describe --tags --long --dirty)\"" > $(VERSION_FILE)
|
||||
echo "#define CO_VERSION_APPLICATION \"$(shell git describe --tags --long --dirty)\"" >> $(VERSION_FILE)
|
||||
303
Devices/Libraries/Systems/CANopenSocket/examples/basicDevice/testingVariables.c
Executable file
303
Devices/Libraries/Systems/CANopenSocket/examples/basicDevice/testingVariables.c
Executable file
@@ -0,0 +1,303 @@
|
||||
/* Application specific access functions for extended OD objects */
|
||||
|
||||
|
||||
#include "testingVariables.h"
|
||||
#include <string.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
|
||||
#define SUBINDEX_I64 0x01
|
||||
#define SUBINDEX_U64 0x02
|
||||
#define SUBINDEX_R32 0x03
|
||||
#define SUBINDEX_R64 0x04
|
||||
#define SUBINDEX_AVERAGE 0x05
|
||||
#define SUBINDEX_PARAMETER 0x09
|
||||
#define SUBINDEX_DOMAIN 0x0A
|
||||
#define SUBINDEX_DOMAIN_FILE_READ 0x0B
|
||||
#define SUBINDEX_DOMAIN_FILE_WRITE 0x0C
|
||||
|
||||
#ifndef DOMAIN_LENGTH_INDICATE
|
||||
#define DOMAIN_LENGTH_INDICATE 1
|
||||
#endif
|
||||
|
||||
|
||||
/*
|
||||
* Custom function for reading OD object _Testing variables_
|
||||
*
|
||||
* For more information see file CO_ODinterface.h, OD_IO_t.
|
||||
*/
|
||||
static ODR_t OD_read_testVar(OD_stream_t *stream, void *buf,
|
||||
OD_size_t count, OD_size_t *countRead)
|
||||
{
|
||||
if (stream == NULL || buf == NULL || countRead == NULL) {
|
||||
return ODR_DEV_INCOMPAT;
|
||||
}
|
||||
|
||||
/* Object was passed by OD_extensionIO_init, use correct type. */
|
||||
testingVariables_t *testVar = (testingVariables_t *)stream->object;
|
||||
|
||||
switch (stream->subIndex) {
|
||||
case SUBINDEX_AVERAGE: {
|
||||
OD_size_t varSize = sizeof(float64_t);
|
||||
|
||||
if (count < varSize || stream->dataLength != varSize) {
|
||||
return ODR_DEV_INCOMPAT;
|
||||
}
|
||||
|
||||
float64_t average = (float64_t)*testVar->i64;
|
||||
average += (float64_t)*testVar->u64;
|
||||
average += (float64_t)*testVar->r32;
|
||||
average += *testVar->r64;
|
||||
average /= 4;
|
||||
|
||||
memcpy(buf, &average, varSize);
|
||||
|
||||
*countRead = varSize;
|
||||
return ODR_OK;
|
||||
}
|
||||
|
||||
case SUBINDEX_PARAMETER: {
|
||||
OD_size_t varSize = sizeof(testVar->parameterU16);
|
||||
|
||||
if (count < varSize || stream->dataLength != varSize) {
|
||||
return ODR_DEV_INCOMPAT;
|
||||
}
|
||||
|
||||
CO_setUint16(buf, ++testVar->parameterU16);
|
||||
|
||||
*countRead = varSize;
|
||||
return ODR_OK;
|
||||
}
|
||||
|
||||
case SUBINDEX_DOMAIN: {
|
||||
/* Data is read from the file for this example. Data can be much
|
||||
* longer than count (available size of the buffer). So
|
||||
* OD_read_testVar() may be called multiple times. */
|
||||
if (stream->dataOffset == 0) {
|
||||
/* Data offset is 0, so this is the first call of this function
|
||||
* in current SDO communication. Open the file now. But if it
|
||||
* is already open, then previous SDO communication didn't
|
||||
* finish correctly. So close the old file first. */
|
||||
if (testVar->domainReadFileStream != NULL)
|
||||
fclose(testVar->domainReadFileStream);
|
||||
|
||||
/* Get filename from auxiliary OD variable of type
|
||||
* VISIBLE_STRING. This type of variable may have variable
|
||||
* string length and always have null terminating character. */
|
||||
char *fileName = testVar->domainReadFileName;
|
||||
|
||||
/* open the file and verify success */
|
||||
testVar->domainReadFileStream = fopen(fileName, "r");
|
||||
if (testVar->domainReadFileStream == NULL) {
|
||||
return ODR_NO_DATA;
|
||||
}
|
||||
#if DOMAIN_LENGTH_INDICATE
|
||||
/* Indicate dataLength */
|
||||
fseek(testVar->domainReadFileStream, 0L, SEEK_END);
|
||||
size_t dataLen = (size_t)ftell(testVar->domainReadFileStream);
|
||||
stream->dataLength = dataLen <= 0xFFFFFFFF
|
||||
? dataLen : 0;
|
||||
rewind(testVar->domainReadFileStream);
|
||||
#else
|
||||
/* It is not required to indicate data length in SDO transfer */
|
||||
stream->dataLength = 0;
|
||||
#endif
|
||||
}
|
||||
|
||||
/* fill the buffer */
|
||||
size_t len = fread(buf, 1, count, testVar->domainReadFileStream);
|
||||
ODR_t returnCode;
|
||||
|
||||
/* determine, if file read finished or not */
|
||||
if (len != count || feof(testVar->domainReadFileStream)) {
|
||||
fclose(testVar->domainReadFileStream);
|
||||
testVar->domainReadFileStream = 0;
|
||||
returnCode = ODR_OK;
|
||||
stream->dataOffset = 0;
|
||||
}
|
||||
else {
|
||||
returnCode = ODR_PARTIAL;
|
||||
stream->dataOffset += len;
|
||||
}
|
||||
|
||||
/* indicate number of bytes read and return ODR_OK or ODR_PARTIAL */
|
||||
*countRead = len;
|
||||
return returnCode;
|
||||
}
|
||||
|
||||
default: {
|
||||
return OD_readOriginal(stream, buf, count, countRead);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
* Custom function for reading OD object _Testing variables_
|
||||
*
|
||||
* For more information see file CO_ODinterface.h, OD_IO_t.
|
||||
*/
|
||||
static ODR_t OD_write_testVar(OD_stream_t *stream, const void *buf,
|
||||
OD_size_t count, OD_size_t *countWritten)
|
||||
{
|
||||
if (stream == NULL || buf == NULL || countWritten == NULL) {
|
||||
return ODR_DEV_INCOMPAT;
|
||||
}
|
||||
|
||||
/* Object was passed by OD_extensionIO_init, use correct type. */
|
||||
testingVariables_t *testVar = (testingVariables_t *)stream->object;
|
||||
|
||||
switch (stream->subIndex) {
|
||||
case SUBINDEX_PARAMETER: {
|
||||
testVar->parameterU16 = CO_getUint16(buf);
|
||||
/* write value to the original location in the Object Dictionary */
|
||||
return OD_writeOriginal(stream, buf, count, countWritten);
|
||||
}
|
||||
|
||||
case SUBINDEX_DOMAIN: {
|
||||
/* Data will be written to the file for this example. Data can be
|
||||
* much longer than count (current size of data in the buffer). So
|
||||
* OD_write_testVar() may be called multiple times. */
|
||||
if (stream->dataOffset == 0) {
|
||||
/* Data offset is 0, so this is the first call of this function
|
||||
* in current SDO communication. Open the file now. Write data
|
||||
* to temporary file first. When transfer will be finished and
|
||||
* temporary file will be written successfully, the original
|
||||
* file will be replaced by with newly transferred. But if
|
||||
* temporary file is already open in this moment, then previous
|
||||
* SDO communication didn't finish correctly. So close the old
|
||||
* file first. */
|
||||
if (testVar->domainWriteFileStream != NULL)
|
||||
fclose(testVar->domainWriteFileStream);
|
||||
|
||||
/* Get filename from auxiliary OD variable of type
|
||||
* VISIBLE_STRING. This type of variable may have variable
|
||||
* string length and always have null terminating character. */
|
||||
char *fileNameOrig = testVar->domainWriteFileName;
|
||||
|
||||
/* create temporary file and verify success */
|
||||
char *fileName = malloc(strlen(fileNameOrig) + 6);
|
||||
strcpy(fileName, fileNameOrig);
|
||||
strcat(fileName, ".tmp");
|
||||
testVar->domainWriteFileStream = fopen(fileName, "w");
|
||||
free(fileName);
|
||||
if (testVar->domainWriteFileStream == NULL) {
|
||||
return ODR_OUT_OF_MEM;
|
||||
}
|
||||
}
|
||||
|
||||
/* write the data and verify */
|
||||
size_t len = fwrite(buf, 1, count, testVar->domainWriteFileStream);
|
||||
if (testVar->domainWriteFileStream == NULL) {
|
||||
return ODR_GENERAL;
|
||||
}
|
||||
|
||||
/* indicate total length written */
|
||||
stream->dataOffset += len;
|
||||
|
||||
/* determine, if file write finished or not
|
||||
* (dataLength may not yet be indicated) */
|
||||
ODR_t returnCode = ODR_OK;
|
||||
if (stream->dataLength > 0
|
||||
&& stream->dataOffset == stream->dataLength
|
||||
) {
|
||||
fclose(testVar->domainWriteFileStream);
|
||||
testVar->domainWriteFileStream = 0;
|
||||
stream->dataOffset = 0;
|
||||
|
||||
/* replace original file with just downloaded */
|
||||
char *fileNameOrig = testVar->domainWriteFileName;
|
||||
char *fileName = malloc(strlen(fileNameOrig) + 6);
|
||||
strcpy(fileName, fileNameOrig);
|
||||
strcat(fileName, ".tmp");
|
||||
int err = rename(fileName, fileNameOrig);
|
||||
free(fileName);
|
||||
|
||||
if (err != 0) {
|
||||
return ODR_GENERAL;
|
||||
}
|
||||
}
|
||||
else {
|
||||
returnCode = ODR_PARTIAL;
|
||||
}
|
||||
|
||||
/* indicate number of bytes written and return ODR_OK or
|
||||
* ODR_PARTIAL */
|
||||
*countWritten = len;
|
||||
return returnCode;
|
||||
}
|
||||
|
||||
default: {
|
||||
return OD_writeOriginal(stream, buf, count, countWritten);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/******************************************************************************/
|
||||
CO_ReturnError_t testingVariables_init(testingVariables_t *testVar,
|
||||
uint32_t *errInfo,
|
||||
OD_entry_t *OD_testVar)
|
||||
{
|
||||
if (testVar == NULL || errInfo == NULL || OD_testVar == NULL)
|
||||
return CO_ERROR_ILLEGAL_ARGUMENT;
|
||||
|
||||
CO_ReturnError_t err = CO_ERROR_NO;
|
||||
ODR_t odRet;
|
||||
|
||||
/* initialize object variables */
|
||||
memset(testVar, 0, sizeof(testingVariables_t));
|
||||
|
||||
/* Initialize custom OD object "Testing variables" */
|
||||
testVar->OD_testVar_extension.object = testVar;
|
||||
testVar->OD_testVar_extension.read = OD_read_testVar;
|
||||
testVar->OD_testVar_extension.write = OD_write_testVar;
|
||||
odRet = OD_extension_init(OD_testVar, &testVar->OD_testVar_extension);
|
||||
|
||||
/* This is strict behavior and will exit the program on error. Error
|
||||
* checking on all OD functions can also be omitted. In that case program
|
||||
* will run, but specific OD entry may not be accessible. */
|
||||
if (odRet != ODR_OK) {
|
||||
*errInfo = OD_getIndex(OD_testVar);
|
||||
return CO_ERROR_OD_PARAMETERS;
|
||||
}
|
||||
|
||||
/* Get variables from Object dictionary, related to "Average" */
|
||||
testVar->i64 = OD_getPtr(OD_testVar, SUBINDEX_I64, sizeof(int64_t), NULL);
|
||||
testVar->u64 = OD_getPtr(OD_testVar, SUBINDEX_U64, sizeof(uint64_t), NULL);
|
||||
testVar->r32 = OD_getPtr(OD_testVar, SUBINDEX_R32, sizeof(float32_t), NULL);
|
||||
testVar->r64 = OD_getPtr(OD_testVar, SUBINDEX_R64, sizeof(float64_t), NULL);
|
||||
|
||||
if (testVar->i64 == NULL || testVar->u64 == NULL
|
||||
|| testVar->r32 == NULL || testVar->r64 == NULL
|
||||
) {
|
||||
*errInfo = OD_getIndex(OD_testVar);
|
||||
return CO_ERROR_OD_PARAMETERS;
|
||||
}
|
||||
|
||||
/* Get variable 'Parameter with default value' from Object dictionary */
|
||||
odRet = OD_get_u16(OD_testVar, SUBINDEX_PARAMETER,
|
||||
&testVar->parameterU16, true);
|
||||
|
||||
if (odRet != ODR_OK) {
|
||||
*errInfo = OD_getIndex(OD_testVar);
|
||||
return CO_ERROR_OD_PARAMETERS;
|
||||
}
|
||||
|
||||
/* Get variables from Object dictionary, related to "Domain" */
|
||||
testVar->domainReadFileName = OD_getPtr(OD_testVar,
|
||||
SUBINDEX_DOMAIN_FILE_READ,
|
||||
0, NULL);
|
||||
testVar->domainWriteFileName = OD_getPtr(OD_testVar,
|
||||
SUBINDEX_DOMAIN_FILE_WRITE,
|
||||
0, NULL);
|
||||
|
||||
if (testVar->domainReadFileName == NULL
|
||||
|| testVar->domainWriteFileName == NULL
|
||||
) {
|
||||
*errInfo = OD_getIndex(OD_testVar);
|
||||
return CO_ERROR_OD_PARAMETERS;
|
||||
}
|
||||
|
||||
return err;
|
||||
}
|
||||
@@ -0,0 +1,48 @@
|
||||
/** Application specific access functions for extended OD objects */
|
||||
|
||||
|
||||
#ifndef TESTING_VARIABLES_H
|
||||
#define TESTING_VARIABLES_H
|
||||
|
||||
|
||||
#include "301/CO_ODinterface.h"
|
||||
#include <stdio.h>
|
||||
|
||||
|
||||
/**
|
||||
* testingVariables object.
|
||||
*/
|
||||
typedef struct {
|
||||
OD_extension_t OD_testVar_extension; /**< Extension for OD object */
|
||||
int64_t *i64; /**< Pointer to variable in object dictionary */
|
||||
uint64_t *u64; /**< Pointer to variable in object dictionary */
|
||||
float32_t *r32; /**< Pointer to variable in object dictionary */
|
||||
float64_t *r64; /**< Pointer to variable in object dictionary */
|
||||
/** Variable initialised from OD sub-entry 'Parameter with default value' */
|
||||
uint16_t parameterU16;
|
||||
/** domain data type test - stream for reading the file */
|
||||
FILE *domainReadFileStream;
|
||||
/** domain data type test - filename from object dictionary */
|
||||
char *domainReadFileName;
|
||||
/** domain data type test - stream for writing the file */
|
||||
FILE *domainWriteFileStream;
|
||||
/** domain data type test - filename from object dictionary */
|
||||
char *domainWriteFileName;
|
||||
} testingVariables_t;
|
||||
|
||||
|
||||
/**
|
||||
* Initialize testingVariables object.
|
||||
*
|
||||
* @param testVar This object will be initialized.
|
||||
* @param [out] errInfo Variable may indicate additional information for some
|
||||
* types of errors.
|
||||
* @param OD_testVar Object Dictionary entry for Testing variables.
|
||||
*
|
||||
* @return @ref CO_ReturnError_t CO_ERROR_NO in case of success.
|
||||
*/
|
||||
CO_ReturnError_t testingVariables_init(testingVariables_t *testVar,
|
||||
uint32_t *errInfo,
|
||||
OD_entry_t *OD_testVar);
|
||||
|
||||
#endif /* TESTING_VARIABLES_H */
|
||||
Reference in New Issue
Block a user