Compare commits
102 Commits
Author | SHA1 | Date |
---|---|---|
nakarlsson | 8f3841e3ce | |
Andreas Karlsson | fcd43fb2e6 | |
nakarlsson | 66111d50fa | |
Andreas Karlsson | 41438c4a33 | |
nakarlsson | 56124c2348 | |
Andreas Karlsson | d04bed4666 | |
nakarlsson | 05bf6c6726 | |
Andreas Karlsson | 9525469a68 | |
nakarlsson | 3fe4511230 | |
Vijay Katoch | e2f3fb7fd2 | |
nakarlsson | 6e70471e1b | |
Andreas Karlsson | 70a1042188 | |
Andreas Karlsson | 2f4afb3230 | |
nakarlsson | 5221cfbe76 | |
Andreas Karlsson | 0d232899bb | |
Andreas Karlsson | 3896a981ce | |
Andreas Karlsson | 45d390a014 | |
Andreas Karlsson | f63bca476d | |
Andreas Karlsson | d22277f4a5 | |
Andreas Karlsson | ac198e05b1 | |
Andreas Karlsson | 60e397aebc | |
Andreas Karlsson | 97472108e3 | |
Andreas Karlsson | fd6dbdf188 | |
Andreas Karlsson | 3bb489469b | |
nakarlsson | 8bb4350cd5 | |
Andreas Karlsson | fff8e22603 | |
nakarlsson | a7a017c26f | |
nakarlsson | ac0031aef5 | |
Andreas Karlsson | 8ebb78ea10 | |
m-dema | 66b040a257 | |
nakarlsson | 8de160a851 | |
Fumihito Sugai | 35288ff3e7 | |
nakarlsson | fc72fbeeec | |
Konrad Hermsdorf | 254a6f807d | |
andreas karlsson | 48c80f5cae | |
nakarlsson | acc59dd6b8 | |
andreas karlsson | 366c07f446 | |
nakarlsson | 6fc395e085 | |
Hans-Erik Floryd | d96f7cefef | |
nakarlsson | fa0d6bf4d6 | |
Lars Danielsson | 69b1049970 | |
Hans-Erik Floryd | 3c5af65be6 | |
andreas karlsson | df0d169eef | |
nakarlsson | 311977e47a | |
Juan Leyva | da33a714a1 | |
Juan Leyva | cd12c0d156 | |
nakarlsson | ff6be22c80 | |
Hans-Erik Floryd | 2808e95668 | |
Hans-Erik Floryd | 097477035d | |
Hans-Erik Floryd | 4d9da268be | |
Juan Leyva | 5e94f0bb81 | |
Hans-Erik Floryd | 4549d0af9a | |
MechaMagpie | 98a90d61ea | |
iwoodsawyer | b3e2a0a2c1 | |
nakarlsson | 2fd5088fea | |
m-dema | c84a3ffb4d | |
nakarlsson | 1f24b72c5c | |
Lars Danielsson | e40d95cc1e | |
nakarlsson | f244ea522d | |
Hans-Erik Floryd | 0d6f7de0e6 | |
Hans-Erik Floryd | 591d08d474 | |
Hans-Erik Floryd | 85319b8524 | |
Hans-Erik Floryd | eb1848a9a3 | |
Lars Danielsson | 8d5afc9b2d | |
Lars Danielsson | 87b2c1eb93 | |
Lars Danielsson | 48772707a6 | |
Lars Danielsson | c814d2dacf | |
Hans-Erik Floryd | 71bb37091f | |
Lars Danielsson | 74d710b8b7 | |
Lars Danielsson | a6f45c308f | |
Hans-Erik Floryd | 9ea52dff56 | |
Lars Danielsson | c0d3e17bcf | |
Lars Danielsson | 177739b02d | |
Hans-Erik Floryd | ed6a6542c8 | |
Lars Danielsson | d9ebdc99fe | |
Lars Danielsson | 59728c994c | |
Lars Danielsson | dd21bd3423 | |
Lars Danielsson | d970d8eb1e | |
Lars Danielsson | 9a430287d1 | |
Lars Danielsson | aee9bf569b | |
Hans-Erik Floryd | 4746f22c78 | |
Hans-Erik Floryd | 09394ecfc8 | |
Lars Danielsson | 32c8901940 | |
Lars Danielsson | 12006a53a5 | |
Lars Danielsson | 86c17dbb14 | |
Lars Danielsson | cde698b1ea | |
Andreas Karlsson | 28e19f4f82 | |
nakarlsson | ba3adf8b74 | |
Lars Danielsson | e428008ea3 | |
Lars Danielsson | b6f4444b9e | |
Lars Danielsson | 78871af81b | |
Lars Danielsson | 6eedcb7cdf | |
Lars Danielsson | bdea958dd5 | |
Andreas Karlsson | 24b700e1c4 | |
Hans-Erik Floryd | 46240450af | |
Lars Danielsson | bb566504de | |
Lars Danielsson | 81ff180e7e | |
Hans-Erik Floryd | 3792b58fea | |
Lars Danielsson | 2296b55812 | |
Hans-Erik Floryd | 0878d71924 | |
Andreas Karlsson | 8ff826c409 | |
Andreas Karlsson | 767c38b0b6 |
|
@ -0,0 +1,23 @@
|
|||
name: build
|
||||
on: [push, pull_request]
|
||||
env:
|
||||
BUILD_TYPE: Release
|
||||
jobs:
|
||||
build:
|
||||
runs-on: ubuntu-20.04
|
||||
steps:
|
||||
- uses: actions/checkout@v2
|
||||
with:
|
||||
submodules: true
|
||||
|
||||
- name: Configure
|
||||
shell: bash
|
||||
run: |
|
||||
cmake -E make_directory $GITHUB_WORKSPACE/build
|
||||
cmake -B $GITHUB_WORKSPACE/build -S $GITHUB_WORKSPACE \
|
||||
-DCMAKE_BUILD_TYPE=$BUILD_TYPE
|
||||
|
||||
- name: Build
|
||||
shell: bash
|
||||
run: |
|
||||
cmake --build $GITHUB_WORKSPACE/build -j4
|
|
@ -1,8 +0,0 @@
|
|||
language: c
|
||||
|
||||
script:
|
||||
- mkdir build
|
||||
- pushd build
|
||||
- cmake .. -DCMAKE_BUILD_TYPE=Release
|
||||
- make
|
||||
- popd
|
|
@ -1,7 +1,7 @@
|
|||
# CMakeLists files in this project can
|
||||
# refer to the root source directory of the project as ${SOES_SOURCE_DIR} and
|
||||
# to the root binary directory of the project as ${SOES_BINARY_DIR}.
|
||||
cmake_minimum_required (VERSION 2.8.4)
|
||||
cmake_minimum_required (VERSION 2.8.12)
|
||||
set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "${CMAKE_SOURCE_DIR}/cmake")
|
||||
project (SOES)
|
||||
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
Simple Open Source EtherCAT Slave
|
||||
====
|
||||
[![Build Status](https://travis-ci.org/OpenEtherCATsociety/SOES.svg?branch=master)](https://travis-ci.org/OpenEtherCATsociety/SOES)
|
||||
[![Build Status](https://github.com/OpenEtherCATsociety/SOES/workflows/build/badge.svg?branch=master)](https://github.com/OpenEtherCATsociety/SOES/actions?workflow=build)
|
||||
|
||||
SOES (Simple OpenSource EtherCAT Slave Stack) is an opensource slave
|
||||
stack that is very easy to use and provides a small footprint. It is a
|
||||
|
|
|
@ -0,0 +1,8 @@
|
|||
|
||||
add_executable (soes-demo
|
||||
main.c
|
||||
slave_objectlist.c
|
||||
)
|
||||
target_link_libraries(soes-demo LINK_PUBLIC soes bcm2835)
|
||||
install (TARGETS soes-demo DESTINATION sbin)
|
||||
install (PROGRAMS S60soes DESTINATION /etc/init.d)
|
|
@ -0,0 +1,40 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# soes Starts soes.
|
||||
#
|
||||
|
||||
start() {
|
||||
printf "Starting soes: "
|
||||
/usr/sbin/soes-demo &
|
||||
touch /var/lock/soes-demo
|
||||
echo "OK"
|
||||
}
|
||||
stop() {
|
||||
printf "Stopping soes: "
|
||||
killall soes-demo
|
||||
rm -f /var/lock/soes-demo
|
||||
echo "OK"
|
||||
}
|
||||
restart() {
|
||||
stop
|
||||
start
|
||||
}
|
||||
|
||||
case "$1" in
|
||||
start)
|
||||
start
|
||||
;;
|
||||
stop)
|
||||
stop
|
||||
;;
|
||||
restart|reload)
|
||||
restart
|
||||
;;
|
||||
*)
|
||||
echo "Usage: $0 {start|stop|restart}"
|
||||
exit 1
|
||||
esac
|
||||
|
||||
exit $?
|
||||
|
||||
|
|
@ -0,0 +1,42 @@
|
|||
#ifndef __ECAT_OPTIONS_H__
|
||||
#define __ECAT_OPTIONS_H__
|
||||
|
||||
#define USE_FOE 1
|
||||
#define USE_EOE 0
|
||||
|
||||
#define MBXSIZE 128
|
||||
#define MBXSIZEBOOT 128
|
||||
#define MBXBUFFERS 3
|
||||
|
||||
#define MBX0_sma 0x1000
|
||||
#define MBX0_sml MBXSIZE
|
||||
#define MBX0_sme MBX0_sma+MBX0_sml-1
|
||||
#define MBX0_smc 0x26
|
||||
#define MBX1_sma MBX0_sma+MBX0_sml
|
||||
#define MBX1_sml MBXSIZE
|
||||
#define MBX1_sme MBX1_sma+MBX1_sml-1
|
||||
#define MBX1_smc 0x22
|
||||
|
||||
#define MBX0_sma_b 0x1000
|
||||
#define MBX0_sml_b MBXSIZEBOOT
|
||||
#define MBX0_sme_b MBX0_sma_b+MBX0_sml_b-1
|
||||
#define MBX0_smc_b 0x26
|
||||
#define MBX1_sma_b MBX0_sma_b+MBX0_sml_b
|
||||
#define MBX1_sml_b MBXSIZEBOOT
|
||||
#define MBX1_sme_b MBX1_sma_b+MBX1_sml_b-1
|
||||
#define MBX1_smc_b 0x22
|
||||
|
||||
#define SM2_sma 0x1100
|
||||
#define SM2_smc 0x24
|
||||
#define SM2_act 1
|
||||
#define SM3_sma 0x1180
|
||||
#define SM3_smc 0x20
|
||||
#define SM3_act 1
|
||||
|
||||
#define MAX_MAPPINGS_SM2 7
|
||||
#define MAX_MAPPINGS_SM3 7
|
||||
|
||||
#define MAX_RXPDO_SIZE 42
|
||||
#define MAX_TXPDO_SIZE 42
|
||||
|
||||
#endif /* __ECAT_OPTIONS_H__ */
|
|
@ -0,0 +1,108 @@
|
|||
#include <stdio.h>
|
||||
#include "ecat_slv.h"
|
||||
#include "utypes.h"
|
||||
#include <bcm2835.h>
|
||||
|
||||
/* Application variables */
|
||||
_Objects Obj;
|
||||
|
||||
#define GPIO21 RPI_BPLUS_GPIO_J8_40
|
||||
#define GPIO20 RPI_BPLUS_GPIO_J8_38
|
||||
#define GPIO16 RPI_BPLUS_GPIO_J8_36
|
||||
#define GPIO12 RPI_BPLUS_GPIO_J8_32
|
||||
#define GPIO24 RPI_BPLUS_GPIO_J8_18
|
||||
#define GPIO23 RPI_BPLUS_GPIO_J8_16
|
||||
#define GPIO26 RPI_BPLUS_GPIO_J8_37
|
||||
#define GPIO19 RPI_BPLUS_GPIO_J8_35
|
||||
#define GPIO13 RPI_BPLUS_GPIO_J8_33
|
||||
#define GPIO06 RPI_BPLUS_GPIO_J8_31
|
||||
#define GPIO05 RPI_BPLUS_GPIO_J8_29
|
||||
#define GPIO22 RPI_BPLUS_GPIO_J8_15
|
||||
|
||||
void cb_get_inputs (void)
|
||||
{
|
||||
// Assume LEDs connected to 3.3v
|
||||
bcm2835_gpio_write(GPIO21, (Obj.LEDs.LED0 ? LOW : HIGH));
|
||||
bcm2835_gpio_write(GPIO20, (Obj.LEDs.LED1 ? LOW : HIGH));
|
||||
bcm2835_gpio_write(GPIO16, (Obj.LEDs.LED2 ? LOW : HIGH));
|
||||
bcm2835_gpio_write(GPIO12, (Obj.LEDs.LED3 ? LOW : HIGH));
|
||||
bcm2835_gpio_write(GPIO24, (Obj.LEDs.LED4 ? LOW : HIGH));
|
||||
bcm2835_gpio_write(GPIO23, (Obj.LEDs.LED5 ? LOW : HIGH));
|
||||
}
|
||||
|
||||
void cb_set_outputs (void)
|
||||
{
|
||||
// Assume Buttons connected to 3.3v
|
||||
Obj.Buttons.Button0 = bcm2835_gpio_lev(GPIO26);
|
||||
Obj.Buttons.Button0 = bcm2835_gpio_lev(GPIO19);
|
||||
Obj.Buttons.Button0 = bcm2835_gpio_lev(GPIO13);
|
||||
Obj.Buttons.Button0 = bcm2835_gpio_lev(GPIO06);
|
||||
Obj.Buttons.Button0 = bcm2835_gpio_lev(GPIO05);
|
||||
Obj.Buttons.Button0 = bcm2835_gpio_lev(GPIO22);
|
||||
}
|
||||
|
||||
void GPIO_init (void)
|
||||
{
|
||||
bcm2835_init();
|
||||
// Assume LEDs connected to 3.3v side of header
|
||||
bcm2835_gpio_fsel(GPIO21, BCM2835_GPIO_FSEL_OUTP);
|
||||
bcm2835_gpio_fsel(GPIO20, BCM2835_GPIO_FSEL_OUTP);
|
||||
bcm2835_gpio_fsel(GPIO16, BCM2835_GPIO_FSEL_OUTP);
|
||||
bcm2835_gpio_fsel(GPIO12, BCM2835_GPIO_FSEL_OUTP);
|
||||
bcm2835_gpio_fsel(GPIO24, BCM2835_GPIO_FSEL_OUTP);
|
||||
bcm2835_gpio_fsel(GPIO23, BCM2835_GPIO_FSEL_OUTP);
|
||||
// Assume buttons connected to 5v side of header
|
||||
// Do not bridge to 5v, the ports might burn
|
||||
bcm2835_gpio_fsel(GPIO26, BCM2835_GPIO_FSEL_INPT);
|
||||
bcm2835_gpio_fsel(GPIO19, BCM2835_GPIO_FSEL_INPT);
|
||||
bcm2835_gpio_fsel(GPIO13, BCM2835_GPIO_FSEL_INPT);
|
||||
bcm2835_gpio_fsel(GPIO06, BCM2835_GPIO_FSEL_INPT);
|
||||
bcm2835_gpio_fsel(GPIO05, BCM2835_GPIO_FSEL_INPT);
|
||||
bcm2835_gpio_fsel(GPIO22, BCM2835_GPIO_FSEL_INPT);
|
||||
bcm2835_gpio_set_pud(GPIO26, BCM2835_GPIO_PUD_DOWN);
|
||||
bcm2835_gpio_set_pud(GPIO19, BCM2835_GPIO_PUD_DOWN);
|
||||
bcm2835_gpio_set_pud(GPIO13, BCM2835_GPIO_PUD_DOWN);
|
||||
bcm2835_gpio_set_pud(GPIO06, BCM2835_GPIO_PUD_DOWN);
|
||||
bcm2835_gpio_set_pud(GPIO05, BCM2835_GPIO_PUD_DOWN);
|
||||
bcm2835_gpio_set_pud(GPIO22, BCM2835_GPIO_PUD_DOWN);
|
||||
}
|
||||
|
||||
int main_run (void * arg)
|
||||
{
|
||||
static esc_cfg_t config =
|
||||
{
|
||||
.user_arg = "rpi3,cs0",
|
||||
.use_interrupt = 0,
|
||||
.watchdog_cnt = 150,
|
||||
.set_defaults_hook = NULL,
|
||||
.pre_state_change_hook = NULL,
|
||||
.post_state_change_hook = NULL,
|
||||
.application_hook = NULL,
|
||||
.safeoutput_override = NULL,
|
||||
.pre_object_download_hook = NULL,
|
||||
.post_object_download_hook = NULL,
|
||||
.rxpdo_override = NULL,
|
||||
.txpdo_override = NULL,
|
||||
.esc_hw_interrupt_enable = NULL,
|
||||
.esc_hw_interrupt_disable = NULL,
|
||||
.esc_hw_eep_handler = NULL,
|
||||
.esc_check_dc_handler = NULL,
|
||||
};
|
||||
|
||||
printf ("Hello Main\n");
|
||||
GPIO_init();
|
||||
ecat_slv_init (&config);
|
||||
while (1)
|
||||
{
|
||||
ecat_slv();
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int main (void)
|
||||
{
|
||||
printf ("Hello Main\n");
|
||||
main_run (NULL);
|
||||
return 0;
|
||||
}
|
Binary file not shown.
|
@ -0,0 +1,532 @@
|
|||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<Slave xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:noNamespaceSchemaLocation="com.rtlabs.emf.esx" fileVersion="2" id="evb9252_dig" productCode="1234" additionalInfo="0x0190">
|
||||
<Name>lan9252</Name>
|
||||
<Vendor>
|
||||
<Id>0x1337</Id>
|
||||
<Name>rt-labs AB</Name>
|
||||
</Vendor>
|
||||
<Group>
|
||||
<Type>lan9252_spi</Type>
|
||||
<Name>lan9252</Name>
|
||||
</Group>
|
||||
<Fmmu>Outputs</Fmmu>
|
||||
<Fmmu>Inputs</Fmmu>
|
||||
<Sm ControlByte="0x26" DefaultSize="128" StartAddress="0x1000">MBoxOut</Sm>
|
||||
<Sm ControlByte="0x22" DefaultSize="128" StartAddress="0x1080">MBoxIn</Sm>
|
||||
<Sm ControlByte="0x24" DefaultSize="0" StartAddress="0x1100">Outputs</Sm>
|
||||
<Sm ControlByte="0x20" DefaultSize="0" StartAddress="0x1180">Inputs</Sm>
|
||||
<Mailbox CoE="true" FoE="true">
|
||||
<Bootstrap Length="128" Start="0x1000"/>
|
||||
<Standard Length="128" Start="0x1000"/>
|
||||
</Mailbox>
|
||||
<Eeprom Lan9252="true">
|
||||
<ConfigData>8002000000000000</ConfigData>
|
||||
<BootStrap>0010800080108000</BootStrap>
|
||||
</Eeprom>
|
||||
<Dictionary>
|
||||
<Item Managed="true">
|
||||
<Index>0x1000</Index>
|
||||
<Name>Device Type</Name>
|
||||
<DataType>UNSIGNED32</DataType>
|
||||
<DefaultValue>0x01901389</DefaultValue>
|
||||
</Item>
|
||||
<Item Managed="true">
|
||||
<Index>0x1008</Index>
|
||||
<Name>Device Name</Name>
|
||||
<DataType>VISIBLE_STRING</DataType>
|
||||
<DefaultValue>evb9252_dig</DefaultValue>
|
||||
<Length>11</Length>
|
||||
</Item>
|
||||
<Item Managed="false">
|
||||
<Index>0x1009</Index>
|
||||
<Name>Hardware Version</Name>
|
||||
<DataType>VISIBLE_STRING</DataType>
|
||||
<DefaultValue>1.0</DefaultValue>
|
||||
</Item>
|
||||
<Item Managed="false">
|
||||
<Index>0x100A</Index>
|
||||
<Name>Software Version</Name>
|
||||
<DataType>VISIBLE_STRING</DataType>
|
||||
<DefaultValue>1.0</DefaultValue>
|
||||
</Item>
|
||||
<Item Managed="true">
|
||||
<Index>0x1018</Index>
|
||||
<Name>Identity Object</Name>
|
||||
<DataType>RECORD</DataType>
|
||||
<SubItem>
|
||||
<Index>0x00</Index>
|
||||
<Name>Max SubIndex</Name>
|
||||
<DataType>UNSIGNED8</DataType>
|
||||
<DefaultValue>4</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x01</Index>
|
||||
<Name>Vendor ID</Name>
|
||||
<DataType>UNSIGNED32</DataType>
|
||||
<DefaultValue>0x1337</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x02</Index>
|
||||
<Name>Product Code</Name>
|
||||
<DataType>UNSIGNED32</DataType>
|
||||
<DefaultValue>1234</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x03</Index>
|
||||
<Name>Revision Number</Name>
|
||||
<DataType>UNSIGNED32</DataType>
|
||||
<DefaultValue>0</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x04</Index>
|
||||
<Name>Serial Number</Name>
|
||||
<DataType>UNSIGNED32</DataType>
|
||||
<DefaultValue>0x00000000</DefaultValue>
|
||||
</SubItem>
|
||||
</Item>
|
||||
<Item Managed="true">
|
||||
<Index>0x1600</Index>
|
||||
<Name>LEDs</Name>
|
||||
<DataType>RECORD</DataType>
|
||||
<SubItem>
|
||||
<Index>0x00</Index>
|
||||
<Name>Max SubIndex</Name>
|
||||
<DataType>UNSIGNED8</DataType>
|
||||
<DefaultValue>9</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x01</Index>
|
||||
<Name>LED0</Name>
|
||||
<DataType>UNSIGNED32</DataType>
|
||||
<DefaultValue>0x70000108</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x02</Index>
|
||||
<Name>LED1</Name>
|
||||
<DataType>UNSIGNED32</DataType>
|
||||
<DefaultValue>0x70000208</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x03</Index>
|
||||
<Name>New Member</Name>
|
||||
<DataType>UNSIGNED32</DataType>
|
||||
<DefaultValue>0x70000301</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x04</Index>
|
||||
<Name>New Member</Name>
|
||||
<DataType>UNSIGNED32</DataType>
|
||||
<DefaultValue>0x70000401</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x05</Index>
|
||||
<Name>New Member</Name>
|
||||
<DataType>UNSIGNED32</DataType>
|
||||
<DefaultValue>0x70000501</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x06</Index>
|
||||
<Name>New Member</Name>
|
||||
<DataType>UNSIGNED32</DataType>
|
||||
<DefaultValue>0x70000601</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x07</Index>
|
||||
<Name>New Member</Name>
|
||||
<DataType>UNSIGNED32</DataType>
|
||||
<DefaultValue>0x70000701</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x08</Index>
|
||||
<Name>New Member</Name>
|
||||
<DataType>UNSIGNED32</DataType>
|
||||
<DefaultValue>0x70000801</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x09</Index>
|
||||
<Name>Padding 9</Name>
|
||||
<DataType>UNSIGNED32</DataType>
|
||||
<DefaultValue>0x00000002</DefaultValue>
|
||||
</SubItem>
|
||||
</Item>
|
||||
<Item Managed="true">
|
||||
<Index>0x1A00</Index>
|
||||
<Name>Buttons</Name>
|
||||
<DataType>RECORD</DataType>
|
||||
<SubItem>
|
||||
<Index>0x00</Index>
|
||||
<Name>Max SubIndex</Name>
|
||||
<DataType>UNSIGNED8</DataType>
|
||||
<DefaultValue>1</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x01</Index>
|
||||
<Name>Button1</Name>
|
||||
<DataType>UNSIGNED32</DataType>
|
||||
<DefaultValue>0x60000108</DefaultValue>
|
||||
</SubItem>
|
||||
</Item>
|
||||
<Item Managed="true">
|
||||
<Index>0x1C00</Index>
|
||||
<Name>Sync Manager Communication Type</Name>
|
||||
<DataType>ARRAY</DataType>
|
||||
<SubItem>
|
||||
<Index>0x00</Index>
|
||||
<Name>Max SubIndex</Name>
|
||||
<DataType>UNSIGNED8</DataType>
|
||||
<DefaultValue>4</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x01</Index>
|
||||
<Name>Communications Type SM0</Name>
|
||||
<DataType>UNSIGNED8</DataType>
|
||||
<DefaultValue>1</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x02</Index>
|
||||
<Name>Communications Type SM1</Name>
|
||||
<DataType>UNSIGNED8</DataType>
|
||||
<DefaultValue>2</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x03</Index>
|
||||
<Name>Communications Type SM2</Name>
|
||||
<DataType>UNSIGNED8</DataType>
|
||||
<DefaultValue>3</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x04</Index>
|
||||
<Name>Communications Type SM3</Name>
|
||||
<DataType>UNSIGNED8</DataType>
|
||||
<DefaultValue>4</DefaultValue>
|
||||
</SubItem>
|
||||
</Item>
|
||||
<Item Managed="true">
|
||||
<Index>0x1C12</Index>
|
||||
<Name>Sync Manager 2 PDO Assignment</Name>
|
||||
<DataType>ARRAY</DataType>
|
||||
<SubItem>
|
||||
<Index>0x00</Index>
|
||||
<Name>Max SubIndex</Name>
|
||||
<DataType>UNSIGNED8</DataType>
|
||||
<DefaultValue>1</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x01</Index>
|
||||
<Name>PDO Mapping</Name>
|
||||
<DataType>UNSIGNED16</DataType>
|
||||
<DefaultValue>0x1600</DefaultValue>
|
||||
</SubItem>
|
||||
</Item>
|
||||
<Item Managed="true">
|
||||
<Index>0x1C13</Index>
|
||||
<Name>Sync Manager 3 PDO Assignment</Name>
|
||||
<DataType>ARRAY</DataType>
|
||||
<SubItem>
|
||||
<Index>0x00</Index>
|
||||
<Name>Max SubIndex</Name>
|
||||
<DataType>UNSIGNED8</DataType>
|
||||
<DefaultValue>1</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x01</Index>
|
||||
<Name>PDO Mapping</Name>
|
||||
<DataType>UNSIGNED16</DataType>
|
||||
<DefaultValue>0x1A00</DefaultValue>
|
||||
</SubItem>
|
||||
</Item>
|
||||
<Item Managed="true">
|
||||
<Index>0x6000</Index>
|
||||
<Name>Buttons</Name>
|
||||
<DataType>RECORD</DataType>
|
||||
<Variable>Buttons</Variable>
|
||||
<VariableType>Input</VariableType>
|
||||
<SubItem>
|
||||
<Index>0x00</Index>
|
||||
<Name>Max SubIndex</Name>
|
||||
<DataType>UNSIGNED8</DataType>
|
||||
<DefaultValue>1</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x01</Index>
|
||||
<Access>RO</Access>
|
||||
<Name>Button1</Name>
|
||||
<DataType>UNSIGNED8</DataType>
|
||||
<DefaultValue>0</DefaultValue>
|
||||
<Variable>Button1</Variable>
|
||||
<VariableType>Input</VariableType>
|
||||
</SubItem>
|
||||
</Item>
|
||||
<Item Managed="true">
|
||||
<Index>0x7000</Index>
|
||||
<Name>LEDs</Name>
|
||||
<DataType>RECORD</DataType>
|
||||
<Variable>LEDs</Variable>
|
||||
<VariableType>Output</VariableType>
|
||||
<SubItem>
|
||||
<Index>0x00</Index>
|
||||
<Name>Max SubIndex</Name>
|
||||
<DataType>UNSIGNED8</DataType>
|
||||
<DefaultValue>8</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x01</Index>
|
||||
<Access>RO</Access>
|
||||
<Name>LED0</Name>
|
||||
<DataType>UNSIGNED8</DataType>
|
||||
<DefaultValue>0</DefaultValue>
|
||||
<Variable>LED0</Variable>
|
||||
<VariableType>Output</VariableType>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x02</Index>
|
||||
<Access>RO</Access>
|
||||
<Name>LED1</Name>
|
||||
<DataType>UNSIGNED8</DataType>
|
||||
<DefaultValue>0</DefaultValue>
|
||||
<Variable>LED1</Variable>
|
||||
<VariableType>Output</VariableType>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x03</Index>
|
||||
<Access>RO</Access>
|
||||
<Name>New Member</Name>
|
||||
<DataType>BOOLEAN</DataType>
|
||||
<DefaultValue>0</DefaultValue>
|
||||
<PdoMapping>RX</PdoMapping>
|
||||
<Variable>New_Member</Variable>
|
||||
<VariableType>Output</VariableType>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x04</Index>
|
||||
<Access>RO</Access>
|
||||
<Name>New Member</Name>
|
||||
<DataType>BOOLEAN</DataType>
|
||||
<DefaultValue>0</DefaultValue>
|
||||
<PdoMapping>RX</PdoMapping>
|
||||
<Variable>New_Member</Variable>
|
||||
<VariableType>Output</VariableType>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x05</Index>
|
||||
<Access>RO</Access>
|
||||
<Name>New Member</Name>
|
||||
<DataType>BOOLEAN</DataType>
|
||||
<DefaultValue>0</DefaultValue>
|
||||
<PdoMapping>RX</PdoMapping>
|
||||
<Variable>New_Member</Variable>
|
||||
<VariableType>Output</VariableType>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x06</Index>
|
||||
<Access>RO</Access>
|
||||
<Name>New Member</Name>
|
||||
<DataType>BOOLEAN</DataType>
|
||||
<DefaultValue>0</DefaultValue>
|
||||
<PdoMapping>RX</PdoMapping>
|
||||
<Variable>New_Member</Variable>
|
||||
<VariableType>Output</VariableType>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x07</Index>
|
||||
<Access>RO</Access>
|
||||
<Name>New Member</Name>
|
||||
<DataType>BOOLEAN</DataType>
|
||||
<DefaultValue>0</DefaultValue>
|
||||
<PdoMapping>RX</PdoMapping>
|
||||
<Variable>New_Member</Variable>
|
||||
<VariableType>Output</VariableType>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x08</Index>
|
||||
<Access>RO</Access>
|
||||
<Name>New Member</Name>
|
||||
<DataType>BOOLEAN</DataType>
|
||||
<DefaultValue>0</DefaultValue>
|
||||
<PdoMapping>RX</PdoMapping>
|
||||
<Variable>New_Member</Variable>
|
||||
<VariableType>Output</VariableType>
|
||||
</SubItem>
|
||||
</Item>
|
||||
<Item Managed="true">
|
||||
<Index>0x8000</Index>
|
||||
<Name>Parameters</Name>
|
||||
<DataType>RECORD</DataType>
|
||||
<Variable>Parameters</Variable>
|
||||
<VariableType>Parameter</VariableType>
|
||||
<SubItem>
|
||||
<Index>0x00</Index>
|
||||
<Name>Max SubIndex</Name>
|
||||
<DataType>UNSIGNED8</DataType>
|
||||
<DefaultValue>1</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x01</Index>
|
||||
<Access>RW</Access>
|
||||
<Name>Multiplier</Name>
|
||||
<DataType>UNSIGNED32</DataType>
|
||||
<DefaultValue>0</DefaultValue>
|
||||
<Variable>Multiplier</Variable>
|
||||
<VariableType>Parameter</VariableType>
|
||||
</SubItem>
|
||||
</Item>
|
||||
</Dictionary>
|
||||
<SmAssignment>
|
||||
<Index>0x1C12</Index>
|
||||
<Entry>
|
||||
<Index>0x01</Index>
|
||||
<AssignedPdo>0x1600</AssignedPdo>
|
||||
</Entry>
|
||||
</SmAssignment>
|
||||
<SmAssignment>
|
||||
<Index>0x1C13</Index>
|
||||
<Entry>
|
||||
<Index>0x01</Index>
|
||||
<AssignedPdo>0x1A00</AssignedPdo>
|
||||
</Entry>
|
||||
</SmAssignment>
|
||||
<RxPdo>
|
||||
<Index>0x1600</Index>
|
||||
<Name>LEDs</Name>
|
||||
<Entry>
|
||||
<Index>0x1</Index>
|
||||
<MappedIndex>0x7000</MappedIndex>
|
||||
<MappedSubIndex>0x01</MappedSubIndex>
|
||||
<Variable>LED0</Variable>
|
||||
</Entry>
|
||||
<Entry>
|
||||
<Index>0x2</Index>
|
||||
<MappedIndex>0x7000</MappedIndex>
|
||||
<MappedSubIndex>0x02</MappedSubIndex>
|
||||
<Variable>LED1</Variable>
|
||||
</Entry>
|
||||
<Entry>
|
||||
<Index>0x3</Index>
|
||||
<MappedIndex>0x7000</MappedIndex>
|
||||
<MappedSubIndex>0x03</MappedSubIndex>
|
||||
<Variable>LED2</Variable>
|
||||
</Entry>
|
||||
<Entry>
|
||||
<Index>0x4</Index>
|
||||
<MappedIndex>0x7000</MappedIndex>
|
||||
<MappedSubIndex>0x04</MappedSubIndex>
|
||||
<Variable>LED3</Variable>
|
||||
</Entry>
|
||||
<Entry>
|
||||
<Index>0x5</Index>
|
||||
<MappedIndex>0x7000</MappedIndex>
|
||||
<MappedSubIndex>0x05</MappedSubIndex>
|
||||
<Variable>LED4</Variable>
|
||||
</Entry>
|
||||
<Entry>
|
||||
<Index>0x6</Index>
|
||||
<MappedIndex>0x7000</MappedIndex>
|
||||
<MappedSubIndex>0x06</MappedSubIndex>
|
||||
<Variable>LED5</Variable>
|
||||
</Entry>
|
||||
<Entry padBits="2">
|
||||
<Index>0x09</Index>
|
||||
</Entry>
|
||||
</RxPdo>
|
||||
<TxPdo>
|
||||
<Index>0x1A00</Index>
|
||||
<Name>Buttons</Name>
|
||||
<Entry>
|
||||
<Index>0x1</Index>
|
||||
<MappedIndex>0x6000</MappedIndex>
|
||||
<MappedSubIndex>0x01</MappedSubIndex>
|
||||
<Variable>Button0</Variable>
|
||||
</Entry>
|
||||
</TxPdo>
|
||||
<Input>
|
||||
<Index>0x6000</Index>
|
||||
<Name>Buttons</Name>
|
||||
<ObjectType>RECORD</ObjectType>
|
||||
<Member>
|
||||
<Index>0x01</Index>
|
||||
<Access>RO</Access>
|
||||
<Name>Button0</Name>
|
||||
<Type>BOOLEAN</Type>
|
||||
<DefaultValue>0</DefaultValue>
|
||||
<PdoMapping>TX</PdoMapping>
|
||||
</Member>
|
||||
<Member>
|
||||
<Index>0x02</Index>
|
||||
<Name>Button1</Name>
|
||||
<PdoMapping>TX</PdoMapping>
|
||||
</Member>
|
||||
<Member>
|
||||
<Index>0x03</Index>
|
||||
<Name>Button2</Name>
|
||||
<PdoMapping>TX</PdoMapping>
|
||||
</Member>
|
||||
<Member>
|
||||
<Index>0x04</Index>
|
||||
<Name>Button3</Name>
|
||||
<PdoMapping>TX</PdoMapping>
|
||||
</Member>
|
||||
<Member>
|
||||
<Index>0x05</Index>
|
||||
<Name>Button4</Name>
|
||||
<PdoMapping>TX</PdoMapping>
|
||||
</Member>
|
||||
<Member>
|
||||
<Index>0x06</Index>
|
||||
<Name>Button5</Name>
|
||||
<PdoMapping>TX</PdoMapping>
|
||||
</Member>
|
||||
</Input>
|
||||
<Output>
|
||||
<Index>0x7000</Index>
|
||||
<Name>LEDs</Name>
|
||||
<ObjectType>RECORD</ObjectType>
|
||||
<Member>
|
||||
<Index>0x01</Index>
|
||||
<Access>RO</Access>
|
||||
<Name>LED0</Name>
|
||||
<Type>BOOLEAN</Type>
|
||||
<DefaultValue>0</DefaultValue>
|
||||
<PdoMapping>RX</PdoMapping>
|
||||
</Member>
|
||||
<Member>
|
||||
<Index>0x02</Index>
|
||||
<Access>RO</Access>
|
||||
<Name>LED1</Name>
|
||||
<Type>BOOLEAN</Type>
|
||||
<DefaultValue>0</DefaultValue>
|
||||
<PdoMapping>RX</PdoMapping>
|
||||
</Member>
|
||||
<Member>
|
||||
<Index>0x03</Index>
|
||||
<Name>LED2</Name>
|
||||
<PdoMapping>RX</PdoMapping>
|
||||
</Member>
|
||||
<Member>
|
||||
<Index>0x04</Index>
|
||||
<Name>LED3</Name>
|
||||
<PdoMapping>RX</PdoMapping>
|
||||
</Member>
|
||||
<Member>
|
||||
<Index>0x05</Index>
|
||||
<Name>LED4</Name>
|
||||
<PdoMapping>RX</PdoMapping>
|
||||
</Member>
|
||||
<Member>
|
||||
<Index>0x06</Index>
|
||||
<Name>LED5</Name>
|
||||
<PdoMapping>RX</PdoMapping>
|
||||
</Member>
|
||||
</Output>
|
||||
<Parameter>
|
||||
<Index>0x8000</Index>
|
||||
<Name>Parameters</Name>
|
||||
<ObjectType>RECORD</ObjectType>
|
||||
<Member>
|
||||
<Index>0x01</Index>
|
||||
<Access>RW</Access>
|
||||
<Name>Multiplier</Name>
|
||||
<Type>UNSIGNED32</Type>
|
||||
<DefaultValue>0</DefaultValue>
|
||||
</Member>
|
||||
</Parameter>
|
||||
</Slave>
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,179 @@
|
|||
#include "esc_coe.h"
|
||||
#include "utypes.h"
|
||||
#include <stddef.h>
|
||||
|
||||
#ifndef HW_REV
|
||||
#define HW_REV "1.0"
|
||||
#endif
|
||||
|
||||
#ifndef SW_REV
|
||||
#define SW_REV "1.0"
|
||||
#endif
|
||||
|
||||
static const char acName1000[] = "Device Type";
|
||||
static const char acName1008[] = "Device Name";
|
||||
static const char acName1009[] = "Hardware Version";
|
||||
static const char acName100A[] = "Software Version";
|
||||
static const char acName1018[] = "Identity Object";
|
||||
static const char acName1018_00[] = "Max SubIndex";
|
||||
static const char acName1018_01[] = "Vendor ID";
|
||||
static const char acName1018_02[] = "Product Code";
|
||||
static const char acName1018_03[] = "Revision Number";
|
||||
static const char acName1018_04[] = "Serial Number";
|
||||
static const char acName1600[] = "LEDs";
|
||||
static const char acName1600_00[] = "Max SubIndex";
|
||||
static const char acName1600_01[] = "LED0";
|
||||
static const char acName1600_02[] = "LED1";
|
||||
static const char acName1600_03[] = "LED2";
|
||||
static const char acName1600_04[] = "LED3";
|
||||
static const char acName1600_05[] = "LED4";
|
||||
static const char acName1600_06[] = "LED5";
|
||||
static const char acName1600_07[] = "Padding 7";
|
||||
static const char acName1A00[] = "Buttons";
|
||||
static const char acName1A00_00[] = "Max SubIndex";
|
||||
static const char acName1A00_01[] = "Button0";
|
||||
static const char acName1A00_02[] = "Button1";
|
||||
static const char acName1A00_03[] = "Button2";
|
||||
static const char acName1A00_04[] = "Button3";
|
||||
static const char acName1A00_05[] = "Button4";
|
||||
static const char acName1A00_06[] = "Button5";
|
||||
static const char acName1A00_07[] = "Padding 7";
|
||||
static const char acName1C00[] = "Sync Manager Communication Type";
|
||||
static const char acName1C00_00[] = "Max SubIndex";
|
||||
static const char acName1C00_01[] = "Communications Type SM0";
|
||||
static const char acName1C00_02[] = "Communications Type SM1";
|
||||
static const char acName1C00_03[] = "Communications Type SM2";
|
||||
static const char acName1C00_04[] = "Communications Type SM3";
|
||||
static const char acName1C12[] = "Sync Manager 2 PDO Assignment";
|
||||
static const char acName1C12_00[] = "Max SubIndex";
|
||||
static const char acName1C12_01[] = "PDO Mapping";
|
||||
static const char acName1C13[] = "Sync Manager 3 PDO Assignment";
|
||||
static const char acName1C13_00[] = "Max SubIndex";
|
||||
static const char acName1C13_01[] = "PDO Mapping";
|
||||
static const char acName6000[] = "Buttons";
|
||||
static const char acName6000_00[] = "Max SubIndex";
|
||||
static const char acName6000_01[] = "Button0";
|
||||
static const char acName6000_02[] = "Button1";
|
||||
static const char acName6000_03[] = "Button2";
|
||||
static const char acName6000_04[] = "Button3";
|
||||
static const char acName6000_05[] = "Button4";
|
||||
static const char acName6000_06[] = "Button5";
|
||||
static const char acName7000[] = "LEDs";
|
||||
static const char acName7000_00[] = "Max SubIndex";
|
||||
static const char acName7000_01[] = "LED0";
|
||||
static const char acName7000_02[] = "LED1";
|
||||
static const char acName7000_03[] = "LED2";
|
||||
static const char acName7000_04[] = "LED3";
|
||||
static const char acName7000_05[] = "LED4";
|
||||
static const char acName7000_06[] = "LED5";
|
||||
static const char acName8000[] = "Parameters";
|
||||
static const char acName8000_00[] = "Max SubIndex";
|
||||
static const char acName8000_01[] = "Multiplier";
|
||||
|
||||
const _objd SDO1000[] =
|
||||
{
|
||||
{0x0, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1000, 0x01901389, NULL},
|
||||
};
|
||||
const _objd SDO1008[] =
|
||||
{
|
||||
{0x0, DTYPE_VISIBLE_STRING, 88, ATYPE_RO, acName1008, 0, "evb9252_dig"},
|
||||
};
|
||||
const _objd SDO1009[] =
|
||||
{
|
||||
{0x0, DTYPE_VISIBLE_STRING, 0, ATYPE_RO, acName1009, 0, HW_REV},
|
||||
};
|
||||
const _objd SDO100A[] =
|
||||
{
|
||||
{0x0, DTYPE_VISIBLE_STRING, 0, ATYPE_RO, acName100A, 0, SW_REV},
|
||||
};
|
||||
const _objd SDO1018[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1018_00, 4, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_01, 0x1337, NULL},
|
||||
{0x02, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_02, 1234, NULL},
|
||||
{0x03, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_03, 0, NULL},
|
||||
{0x04, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_04, 0x00000000, &Obj.serial},
|
||||
};
|
||||
const _objd SDO1600[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1600_00, 7, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1600_01, 0x70000101, NULL},
|
||||
{0x02, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1600_02, 0x70000201, NULL},
|
||||
{0x03, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1600_03, 0x70000301, NULL},
|
||||
{0x04, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1600_04, 0x70000401, NULL},
|
||||
{0x05, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1600_05, 0x70000501, NULL},
|
||||
{0x06, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1600_06, 0x70000601, NULL},
|
||||
{0x07, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1600_07, 0x00000002, NULL},
|
||||
};
|
||||
const _objd SDO1A00[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A00_00, 7, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A00_01, 0x60000101, NULL},
|
||||
{0x02, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A00_02, 0x60000201, NULL},
|
||||
{0x03, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A00_03, 0x60000301, NULL},
|
||||
{0x04, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A00_04, 0x60000401, NULL},
|
||||
{0x05, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A00_05, 0x60000501, NULL},
|
||||
{0x06, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A00_06, 0x60000601, NULL},
|
||||
{0x07, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A00_07, 0x00000002, NULL},
|
||||
};
|
||||
const _objd SDO1C00[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C00_00, 4, NULL},
|
||||
{0x01, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C00_01, 1, NULL},
|
||||
{0x02, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C00_02, 2, NULL},
|
||||
{0x03, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C00_03, 3, NULL},
|
||||
{0x04, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C00_04, 4, NULL},
|
||||
};
|
||||
const _objd SDO1C12[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C12_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_01, 0x1600, NULL},
|
||||
};
|
||||
const _objd SDO1C13[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C13_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_01, 0x1A00, NULL},
|
||||
};
|
||||
const _objd SDO6000[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName6000_00, 6, NULL},
|
||||
{0x01, DTYPE_BOOLEAN, 1, ATYPE_RO | ATYPE_TXPDO, acName6000_01, 0, &Obj.Buttons.Button0},
|
||||
{0x02, DTYPE_BOOLEAN, 1, ATYPE_RO | ATYPE_TXPDO, acName6000_02, 0, &Obj.Buttons.Button1},
|
||||
{0x03, DTYPE_BOOLEAN, 1, ATYPE_RO | ATYPE_TXPDO, acName6000_03, 0, &Obj.Buttons.Button2},
|
||||
{0x04, DTYPE_BOOLEAN, 1, ATYPE_RO | ATYPE_TXPDO, acName6000_04, 0, &Obj.Buttons.Button3},
|
||||
{0x05, DTYPE_BOOLEAN, 1, ATYPE_RO | ATYPE_TXPDO, acName6000_05, 0, &Obj.Buttons.Button4},
|
||||
{0x06, DTYPE_BOOLEAN, 1, ATYPE_RO | ATYPE_TXPDO, acName6000_06, 0, &Obj.Buttons.Button5},
|
||||
};
|
||||
const _objd SDO7000[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7000_00, 6, NULL},
|
||||
{0x01, DTYPE_BOOLEAN, 1, ATYPE_RO | ATYPE_RXPDO, acName7000_01, 0, &Obj.LEDs.LED0},
|
||||
{0x02, DTYPE_BOOLEAN, 1, ATYPE_RO | ATYPE_RXPDO, acName7000_02, 0, &Obj.LEDs.LED1},
|
||||
{0x03, DTYPE_BOOLEAN, 1, ATYPE_RO | ATYPE_RXPDO, acName7000_03, 0, &Obj.LEDs.LED2},
|
||||
{0x04, DTYPE_BOOLEAN, 1, ATYPE_RO | ATYPE_RXPDO, acName7000_04, 0, &Obj.LEDs.LED3},
|
||||
{0x05, DTYPE_BOOLEAN, 1, ATYPE_RO | ATYPE_RXPDO, acName7000_05, 0, &Obj.LEDs.LED4},
|
||||
{0x06, DTYPE_BOOLEAN, 1, ATYPE_RO | ATYPE_RXPDO, acName7000_06, 0, &Obj.LEDs.LED5},
|
||||
};
|
||||
const _objd SDO8000[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName8000_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RW, acName8000_01, 0, &Obj.Parameters.Multiplier},
|
||||
};
|
||||
|
||||
const _objectlist SDOobjects[] =
|
||||
{
|
||||
{0x1000, OTYPE_VAR, 0, 0, acName1000, SDO1000},
|
||||
{0x1008, OTYPE_VAR, 0, 0, acName1008, SDO1008},
|
||||
{0x1009, OTYPE_VAR, 0, 0, acName1009, SDO1009},
|
||||
{0x100A, OTYPE_VAR, 0, 0, acName100A, SDO100A},
|
||||
{0x1018, OTYPE_RECORD, 4, 0, acName1018, SDO1018},
|
||||
{0x1600, OTYPE_RECORD, 7, 0, acName1600, SDO1600},
|
||||
{0x1A00, OTYPE_RECORD, 7, 0, acName1A00, SDO1A00},
|
||||
{0x1C00, OTYPE_ARRAY, 4, 0, acName1C00, SDO1C00},
|
||||
{0x1C12, OTYPE_ARRAY, 1, 0, acName1C12, SDO1C12},
|
||||
{0x1C13, OTYPE_ARRAY, 1, 0, acName1C13, SDO1C13},
|
||||
{0x6000, OTYPE_RECORD, 6, 0, acName6000, SDO6000},
|
||||
{0x7000, OTYPE_RECORD, 6, 0, acName7000, SDO7000},
|
||||
{0x8000, OTYPE_RECORD, 1, 0, acName8000, SDO8000},
|
||||
{0xffff, 0xff, 0xff, 0xff, NULL, NULL}
|
||||
};
|
|
@ -0,0 +1,49 @@
|
|||
#ifndef __UTYPES_H__
|
||||
#define __UTYPES_H__
|
||||
|
||||
#include "cc.h"
|
||||
|
||||
/* Object dictionary storage */
|
||||
|
||||
typedef struct
|
||||
{
|
||||
/* Identity */
|
||||
|
||||
uint32_t serial;
|
||||
|
||||
/* Inputs */
|
||||
|
||||
struct
|
||||
{
|
||||
uint8_t Button0;
|
||||
uint8_t Button1;
|
||||
uint8_t Button2;
|
||||
uint8_t Button3;
|
||||
uint8_t Button4;
|
||||
uint8_t Button5;
|
||||
} Buttons;
|
||||
|
||||
/* Outputs */
|
||||
|
||||
struct
|
||||
{
|
||||
uint8_t LED0;
|
||||
uint8_t LED1;
|
||||
uint8_t LED2;
|
||||
uint8_t LED3;
|
||||
uint8_t LED4;
|
||||
uint8_t LED5;
|
||||
} LEDs;
|
||||
|
||||
/* Parameters */
|
||||
|
||||
struct
|
||||
{
|
||||
uint32_t Multiplier;
|
||||
} Parameters;
|
||||
|
||||
} _Objects;
|
||||
|
||||
extern _Objects Obj;
|
||||
|
||||
#endif /* __UTYPES_H__ */
|
|
@ -38,6 +38,13 @@ void cb_state_change (uint8_t * as, uint8_t * an)
|
|||
/* Enable watchdog interrupt */
|
||||
ESC_ALeventmaskwrite (ESC_ALeventmaskread() | ESCREG_ALEVENT_WD);
|
||||
}
|
||||
else if (*as == PREOP_TO_SAFEOP)
|
||||
{
|
||||
/* Write initial input data requried if an input only slave,
|
||||
* otherwise the SM3 will never occur.
|
||||
*/
|
||||
DIG_process (DIG_PROCESS_INPUTS_FLAG);
|
||||
}
|
||||
}
|
||||
|
||||
/* Setup of DC */
|
||||
|
@ -70,6 +77,7 @@ int main (void)
|
|||
.esc_hw_interrupt_disable = ESC_interrupt_disable,
|
||||
.esc_hw_eep_handler = ESC_eep_handler,
|
||||
.esc_check_dc_handler = dc_checker
|
||||
.get_device_id = NULL
|
||||
};
|
||||
|
||||
rprintf ("Hello world\n");
|
||||
|
|
Binary file not shown.
|
@ -1571,7 +1571,7 @@
|
|||
<Name>TXPDO 2</Name>
|
||||
</TxPdo>
|
||||
<Mailbox DataLinkLayer="true">
|
||||
<CoE CompleteAccess="false" PdoAssign="true" PdoConfig="true" PdoUpload="false" SdoInfo="true"/>
|
||||
<CoE CompleteAccess="true" PdoAssign="true" PdoConfig="true" PdoUpload="false" SdoInfo="true"/>
|
||||
</Mailbox>
|
||||
<Eeprom>
|
||||
<ByteSize>256</ByteSize>
|
||||
|
|
|
@ -136,7 +136,7 @@ const _objd SDO1018[] =
|
|||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_01, 0x1337, NULL},
|
||||
{0x02, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_02, 0x4800, NULL},
|
||||
{0x03, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_03, 0, NULL},
|
||||
{0x04, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_04, 0x00000000, NULL},
|
||||
{0x04, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_04, 0x00000000, &Obj.serial},
|
||||
};
|
||||
const _objd SDO10F1[] =
|
||||
{
|
||||
|
|
|
@ -7,6 +7,10 @@
|
|||
|
||||
typedef struct
|
||||
{
|
||||
/* Identity */
|
||||
|
||||
uint32_t serial;
|
||||
|
||||
/* Inputs */
|
||||
|
||||
struct
|
||||
|
|
|
@ -1,14 +1,20 @@
|
|||
|
||||
set(SOES_DEMO applications/linux_lan9252demo)
|
||||
if(RPI_VARIANT)
|
||||
set (SOES_DEMO applications/raspberry_lan9252demo)
|
||||
set(HAL_SOURCES
|
||||
${SOES_SOURCE_DIR}/soes/hal/raspberrypi-lan9252/esc_hw.c
|
||||
${SOES_SOURCE_DIR}/soes/hal/raspberrypi-lan9252/esc_hw.h
|
||||
)
|
||||
else()
|
||||
set(SOES_DEMO applications/linux_lan9252demo)
|
||||
set(HAL_SOURCES
|
||||
${SOES_SOURCE_DIR}/soes/hal/linux-lan9252/esc_hw.c
|
||||
)
|
||||
endif()
|
||||
|
||||
include_directories(
|
||||
${SOES_SOURCE_DIR}/soes/include/sys/gcc
|
||||
${SOES_SOURCE_DIR}/${SOES_DEMO}
|
||||
)
|
||||
|
||||
set(HAL_SOURCES
|
||||
${SOES_SOURCE_DIR}/soes/hal/linux-lan9252/esc_hw.c
|
||||
)
|
||||
|
||||
# Common compile flags
|
||||
add_compile_options(-Wall -Wextra -Wno-unused-parameter -Werror)
|
||||
add_compile_options(-Wall -Wextra -Wconversion -Wno-unused-parameter -Werror)
|
||||
|
|
|
@ -25,13 +25,13 @@ static volatile int watchdog;
|
|||
#if MAX_MAPPINGS_SM2 > 0
|
||||
static uint8_t rxpdo[MAX_RXPDO_SIZE] __attribute__((aligned (8)));
|
||||
#else
|
||||
extern uint8_t * rxpdo;
|
||||
extern uint8_t rxpdo[];
|
||||
#endif
|
||||
|
||||
#if MAX_MAPPINGS_SM3 > 0
|
||||
static uint8_t txpdo[MAX_TXPDO_SIZE] __attribute__((aligned (8)));
|
||||
#else
|
||||
extern uint8_t * txpdo;
|
||||
extern uint8_t txpdo[];
|
||||
#endif
|
||||
|
||||
/** Function to pre-qualify the incoming SDO download.
|
||||
|
@ -40,35 +40,34 @@ extern uint8_t * txpdo;
|
|||
* @param[in] sub-index = sub-index of SDO download request to check
|
||||
* @return SDO abort code, or 0 on success
|
||||
*/
|
||||
uint32_t ESC_pre_objecthandler (uint16_t index,
|
||||
uint32_t ESC_download_pre_objecthandler (uint16_t index,
|
||||
uint8_t subindex,
|
||||
void * data,
|
||||
size_t size,
|
||||
uint16_t flags)
|
||||
{
|
||||
uint32_t abort = 0;
|
||||
|
||||
if (IS_RXPDO (index) ||
|
||||
IS_TXPDO (index) ||
|
||||
index == RX_PDO_OBJIDX ||
|
||||
index == TX_PDO_OBJIDX)
|
||||
{
|
||||
if (subindex > 0 && COE_maxSub (index) != 0)
|
||||
uint8_t minSub = ((flags & COMPLETE_ACCESS_FLAG) == 0) ? 0 : 1;
|
||||
if (subindex > minSub && COE_maxSub (index) != 0)
|
||||
{
|
||||
abort = ABORT_SUBINDEX0_NOT_ZERO;
|
||||
return ABORT_SUBINDEX0_NOT_ZERO;
|
||||
}
|
||||
}
|
||||
|
||||
if (ESCvar.pre_object_download_hook)
|
||||
{
|
||||
abort = (ESCvar.pre_object_download_hook) (index,
|
||||
return (ESCvar.pre_object_download_hook) (index,
|
||||
subindex,
|
||||
data,
|
||||
size,
|
||||
flags);
|
||||
}
|
||||
|
||||
return abort;
|
||||
return 0;
|
||||
}
|
||||
|
||||
/** Hook called from the slave stack SDO Download handler to act on
|
||||
|
@ -76,13 +75,57 @@ uint32_t ESC_pre_objecthandler (uint16_t index,
|
|||
*
|
||||
* @param[in] index = index of SDO download request to handle
|
||||
* @param[in] sub-index = sub-index of SDO download request to handle
|
||||
* @return SDO abort code, or 0 on success
|
||||
*/
|
||||
void ESC_objecthandler (uint16_t index, uint8_t subindex, uint16_t flags)
|
||||
uint32_t ESC_download_post_objecthandler (uint16_t index, uint8_t subindex, uint16_t flags)
|
||||
{
|
||||
if (ESCvar.post_object_download_hook != NULL)
|
||||
{
|
||||
(ESCvar.post_object_download_hook)(index, subindex, flags);
|
||||
return (ESCvar.post_object_download_hook)(index, subindex, flags);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/** Function to pre-qualify the incoming SDO upload.
|
||||
*
|
||||
* @param[in] index = index of SDO upload request to handle
|
||||
* @param[in] sub-index = sub-index of SDO upload request to handle
|
||||
* @return SDO abort code, or 0 on success
|
||||
*/
|
||||
uint32_t ESC_upload_pre_objecthandler (uint16_t index,
|
||||
uint8_t subindex,
|
||||
void * data,
|
||||
size_t *size,
|
||||
uint16_t flags)
|
||||
{
|
||||
if (ESCvar.pre_object_upload_hook != NULL)
|
||||
{
|
||||
return (ESCvar.pre_object_upload_hook) (index,
|
||||
subindex,
|
||||
data,
|
||||
size,
|
||||
flags);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/** Hook called from the slave stack SDO Upload handler to act on
|
||||
* user specified Index and Sub-index.
|
||||
*
|
||||
* @param[in] index = index of SDO upload request to handle
|
||||
* @param[in] sub-index = sub-index of SDO upload request to handle
|
||||
* @return SDO abort code, or 0 on success
|
||||
*/
|
||||
uint32_t ESC_upload_post_objecthandler (uint16_t index, uint8_t subindex, uint16_t flags)
|
||||
{
|
||||
if (ESCvar.post_object_upload_hook != NULL)
|
||||
{
|
||||
return (ESCvar.post_object_upload_hook)(index, subindex, flags);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/** Hook called from the slave stack ESC_stopoutputs to act on state changes
|
||||
|
@ -159,7 +202,8 @@ void DIG_process (uint8_t flags)
|
|||
}
|
||||
|
||||
if ((CC_ATOMIC_GET(watchdog) <= 0) &&
|
||||
((CC_ATOMIC_GET(ESCvar.App.state) & APPSTATE_OUTPUT) > 0))
|
||||
((CC_ATOMIC_GET(ESCvar.App.state) & APPSTATE_OUTPUT) > 0) &&
|
||||
(ESCvar.ESC_SM2_sml > 0))
|
||||
{
|
||||
DPRINT("DIG_process watchdog expired\n");
|
||||
ESC_ALstatusgotoerror((ESCsafeop | ESCerror), ALERR_WATCHDOG);
|
||||
|
@ -183,7 +227,7 @@ void DIG_process (uint8_t flags)
|
|||
}
|
||||
else if (ESCvar.ALevent & ESCREG_ALEVENT_SM2)
|
||||
{
|
||||
RXPDO_update();
|
||||
ESC_read (ESC_SM2_sma, rxpdo, ESCvar.ESC_SM2_sml);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -325,18 +369,20 @@ void ecat_slv_init (esc_cfg_t * config)
|
|||
|
||||
#if USE_FOE
|
||||
/* Init FoE */
|
||||
FOE_init();
|
||||
FOE_init ();
|
||||
#endif
|
||||
|
||||
#if USE_EOE
|
||||
/* Init EoE */
|
||||
EOE_init();
|
||||
EOE_init ();
|
||||
#endif
|
||||
|
||||
/* reset ESC to init state */
|
||||
ESC_ALstatus (ESCinit);
|
||||
ESC_ALerror (ALERR_NONE);
|
||||
ESC_stopmbx();
|
||||
ESC_stopinput();
|
||||
ESC_stopoutput();
|
||||
ESC_stopmbx ();
|
||||
ESC_stopinput ();
|
||||
ESC_stopoutput ();
|
||||
/* Init Object Dictionary default values */
|
||||
COE_initDefaultValues ();
|
||||
}
|
||||
|
|
|
@ -1,7 +1,11 @@
|
|||
/*
|
||||
* Licensed under the GNU General Public License version 2 with exceptions. See
|
||||
* LICENSE file in the project root for full license information
|
||||
*/
|
||||
|
||||
#ifndef __ECAT_SLV_H__
|
||||
#define __ECAT_SLV_H__
|
||||
|
||||
#include "ecat_slv.h"
|
||||
#include "options.h"
|
||||
#include "esc.h"
|
||||
|
||||
|
|
244
soes/esc.c
244
soes/esc.c
|
@ -62,7 +62,7 @@ void ESC_ALstatusgotoerror (uint8_t status, uint16_t errornumber)
|
|||
as = ESCvar.ALstatus & ESCREG_AL_ERRACKMASK;
|
||||
an = as;
|
||||
/* Set the state transition, new state in high bits and old in bits */
|
||||
as = ((status & ESCREG_AL_ERRACKMASK) << 4) | (as & 0x0f);
|
||||
as = (uint8_t)(((status & ESCREG_AL_ERRACKMASK) << 4) | (as & 0x0f));
|
||||
/* Call post state change hook case it have been configured */
|
||||
if (ESCvar.pre_state_change_hook != NULL)
|
||||
{
|
||||
|
@ -136,7 +136,7 @@ uint32_t ESC_ALeventread (void)
|
|||
void ESC_SMack (uint8_t n)
|
||||
{
|
||||
uint8_t dummy;
|
||||
ESC_read (ESCREG_SM0ACTIVATE + (n << 3), &dummy, 1);
|
||||
ESC_read ((uint16_t)(ESCREG_SM0ACTIVATE + (n << 3)), &dummy, 1);
|
||||
}
|
||||
|
||||
/** Read SM Status register 0x805(+ offset to SyncManager n) and save the
|
||||
|
@ -148,7 +148,7 @@ void ESC_SMstatus (uint8_t n)
|
|||
{
|
||||
_ESCsm2 *sm;
|
||||
sm = (_ESCsm2 *)&ESCvar.SM[n];
|
||||
ESC_read (ESCREG_SM0STATUS + (n << 3), &(sm->Status), 1);
|
||||
ESC_read ((uint16_t)(ESCREG_SM0STATUS + (n << 3)), &(sm->Status), 1);
|
||||
}
|
||||
|
||||
/** Write ESCvar.SM[n] data to ESC PDI control register 0x807(+ offset to SyncManager n).
|
||||
|
@ -159,7 +159,18 @@ void ESC_SMwritepdi (uint8_t n)
|
|||
{
|
||||
_ESCsm2 *sm;
|
||||
sm = (_ESCsm2 *)&ESCvar.SM[n];
|
||||
ESC_write (ESCREG_SM0PDI + (n << 3), &(sm->ActPDI), 1);
|
||||
ESC_write ((uint16_t)(ESCREG_SM0PDI + (n << 3)), &(sm->ActPDI), 1);
|
||||
}
|
||||
|
||||
/** Read ESC PDI control register 0x807(+ offset to SyncManager n) to ESCvar.SM[n] data.
|
||||
*
|
||||
* @param[in] n = Read from Sync Manager no. n
|
||||
*/
|
||||
void ESC_SMreadpdi (uint8_t n)
|
||||
{
|
||||
_ESCsm2* sm;
|
||||
sm = (_ESCsm2*)&ESCvar.SM[n];
|
||||
ESC_read ((uint16_t)(ESCREG_SM0PDI + (n << 3)), &(sm->ActPDI), 1);
|
||||
}
|
||||
|
||||
/** Write 0 to Bit0 in SM PDI control register 0x807(+ offset to SyncManager n) to Activate the Sync Manager n.
|
||||
|
@ -170,8 +181,13 @@ void ESC_SMenable (uint8_t n)
|
|||
{
|
||||
_ESCsm2 *sm;
|
||||
sm = (_ESCsm2 *)&ESCvar.SM[n];
|
||||
sm->ActPDI &= ~ESCREG_SMENABLE_BIT;
|
||||
sm->ActPDI &= (uint8_t)~ESCREG_SMENABLE_BIT;
|
||||
ESC_SMwritepdi (n);
|
||||
/* Read back wait until enabled */
|
||||
do
|
||||
{
|
||||
ESC_SMreadpdi (n);
|
||||
} while ((sm->ActPDI & ESCREG_SMENABLE_BIT) == 1);
|
||||
}
|
||||
/** Write 1 to Bit0 in SM PDI control register 0x807(+ offset to SyncManager n) to De-activte the Sync Manager n.
|
||||
*
|
||||
|
@ -183,6 +199,11 @@ void ESC_SMdisable (uint8_t n)
|
|||
sm = (_ESCsm2 *)&ESCvar.SM[n];
|
||||
sm->ActPDI |= ESCREG_SMENABLE_BIT;
|
||||
ESC_SMwritepdi (n);
|
||||
/* Read back wait until disabled */
|
||||
do
|
||||
{
|
||||
ESC_SMreadpdi (n);
|
||||
} while ((sm->ActPDI & ESCREG_SMENABLE_BIT) == 0);
|
||||
}
|
||||
/** Read Configured Station Address register 0x010 assigned by the Master.
|
||||
*
|
||||
|
@ -321,7 +342,6 @@ uint8_t ESC_startmbx (uint8_t state)
|
|||
ESCvar.activemb0 = &ESCvar.mb[0];
|
||||
ESCvar.activemb1 = &ESCvar.mb[1];
|
||||
|
||||
|
||||
ESC_SMenable (0);
|
||||
ESC_SMenable (1);
|
||||
ESC_SMstatus (0);
|
||||
|
@ -334,6 +354,8 @@ uint8_t ESC_startmbx (uint8_t state)
|
|||
else
|
||||
{
|
||||
ESCvar.toggle = ESCvar.SM[1].ECrep; //sync repeat request toggle state
|
||||
ESCvar.SM[1].PDIrep = ESCvar.toggle & 0x1U;
|
||||
ESC_SMwritepdi (1);
|
||||
ESCvar.MBXrun = 1;
|
||||
}
|
||||
return state;
|
||||
|
@ -367,6 +389,8 @@ uint8_t ESC_startmbxboot (uint8_t state)
|
|||
else
|
||||
{
|
||||
ESCvar.toggle = ESCvar.SM[1].ECrep; //sync repeat request toggle state
|
||||
ESCvar.SM[1].PDIrep = ESCvar.toggle & 0x1U;
|
||||
ESC_SMwritepdi (1);
|
||||
ESCvar.MBXrun = 1;
|
||||
}
|
||||
return state;
|
||||
|
@ -395,6 +419,9 @@ void ESC_stopmbx (void)
|
|||
ESCvar.frags = 0;
|
||||
ESCvar.fragsleft = 0;
|
||||
ESCvar.txcue = 0;
|
||||
ESCvar.index = 0;
|
||||
ESCvar.subindex = 0;
|
||||
ESCvar.flags = 0;
|
||||
}
|
||||
|
||||
/** Read Receive mailbox and store data in local ESCvar.MBX variable.
|
||||
|
@ -411,9 +438,9 @@ void ESC_readmbx (void)
|
|||
|
||||
if (length > (ESC_MBX0_sml - ESC_MBXHSIZE))
|
||||
{
|
||||
length = ESC_MBX0_sml - ESC_MBXHSIZE;
|
||||
length = (uint16_t)(ESC_MBX0_sml - ESC_MBXHSIZE);
|
||||
}
|
||||
ESC_read (ESC_MBX0_sma + ESC_MBXHSIZE, MB->b, length);
|
||||
ESC_read ((uint16_t)(ESC_MBX0_sma + ESC_MBXHSIZE), MB->b, length);
|
||||
if (length + ESC_MBXHSIZE < ESC_MBX0_sml)
|
||||
{
|
||||
ESC_read (ESC_MBX0_sme, &length, 1);
|
||||
|
@ -436,9 +463,9 @@ void ESC_writembx (uint8_t n)
|
|||
|
||||
if (length > (ESC_MBX1_sml - ESC_MBXHSIZE))
|
||||
{
|
||||
length = ESC_MBX1_sml - ESC_MBXHSIZE;
|
||||
length = (uint16_t)(ESC_MBX1_sml - ESC_MBXHSIZE);
|
||||
}
|
||||
ESC_write (ESC_MBX1_sma, MBh, ESC_MBXHSIZE + length);
|
||||
ESC_write (ESC_MBX1_sma, MBh, (uint16_t)(ESC_MBXHSIZE + length));
|
||||
if (length + ESC_MBXHSIZE < ESC_MBX1_sml)
|
||||
{
|
||||
ESC_write (ESC_MBX1_sme, &dummy, 1);
|
||||
|
@ -484,7 +511,7 @@ uint8_t ESC_claimbuffer (void)
|
|||
MBh->address = htoes (0x0000); // destination is master
|
||||
MBh->channel = 0;
|
||||
MBh->priority = 0;
|
||||
MBh->mbxcnt = ESCvar.mbxcnt;
|
||||
MBh->mbxcnt = ESCvar.mbxcnt & 0xFU;
|
||||
ESCvar.txcue++;
|
||||
}
|
||||
return n;
|
||||
|
@ -598,7 +625,7 @@ uint8_t ESC_mbxprocess (void)
|
|||
ESC_writembx (ESCvar.mbxbackup);
|
||||
}
|
||||
ESCvar.toggle = ESCvar.SM[1].ECrep;
|
||||
ESCvar.SM[1].PDIrep = ESCvar.toggle;
|
||||
ESCvar.SM[1].PDIrep = ESCvar.toggle & 0x1U;
|
||||
ESC_SMwritepdi (1);
|
||||
}
|
||||
return 0;
|
||||
|
@ -685,23 +712,78 @@ uint8_t ESC_checkSM23 (uint8_t state)
|
|||
_ESCsm2 *SM;
|
||||
ESC_read (ESCREG_SM2, (void *) &ESCvar.SM[2], sizeof (ESCvar.SM[2]));
|
||||
SM = (_ESCsm2 *) & ESCvar.SM[2];
|
||||
if ((etohs (SM->PSA) != ESC_SM2_sma) || (etohs (SM->Length) != ESCvar.ESC_SM2_sml)
|
||||
|| (SM->Command != ESC_SM2_smc) || !(SM->ActESC & ESC_SM2_act))
|
||||
|
||||
/* Check SM settings */
|
||||
if ((etohs (SM->PSA) != ESC_SM2_sma) ||
|
||||
(SM->Command != ESC_SM2_smc))
|
||||
{
|
||||
ESCvar.SMtestresult = SMRESULT_ERRSM2;
|
||||
/* fail state change */
|
||||
return (ESCpreop | ESCerror);
|
||||
}
|
||||
/* Check run-time settings */
|
||||
/* Check length */
|
||||
else if (etohs (SM->Length) != ESCvar.ESC_SM2_sml)
|
||||
{
|
||||
ESCvar.SMtestresult = SMRESULT_ERRSM2;
|
||||
/* fail state change */
|
||||
return (ESCpreop | ESCerror);
|
||||
}
|
||||
/* SM disabled and (SM activated or length > 0) set by master */
|
||||
else if (((ESC_SM2_act & ESCREG_SYNC_ACT_ACTIVATED) == 0) &&
|
||||
((SM->ActESC & ESCREG_SYNC_ACT_ACTIVATED) || (ESCvar.ESC_SM2_sml > 0)))
|
||||
{
|
||||
ESCvar.SMtestresult = SMRESULT_ERRSM2;
|
||||
/* fail state change */
|
||||
return (ESCpreop | ESCerror);
|
||||
}
|
||||
/* SM enabled and (length > 0 but SM disabled) set by master */
|
||||
else if (((ESC_SM2_act & ESCREG_SYNC_ACT_ACTIVATED) > 0) &&
|
||||
((SM->ActESC & ESCREG_SYNC_ACT_ACTIVATED) == 0) &&
|
||||
(ESCvar.ESC_SM2_sml > 0))
|
||||
{
|
||||
ESCvar.SMtestresult = SMRESULT_ERRSM2;
|
||||
/* fail state change */
|
||||
return (ESCpreop | ESCerror);
|
||||
}
|
||||
|
||||
if ((ESC_SM2_sma + (etohs (SM->Length) * 3)) > ESC_SM3_sma)
|
||||
{
|
||||
ESCvar.SMtestresult = SMRESULT_ERRSM2;
|
||||
/* SM2 overlaps SM3, fail state change */
|
||||
return (ESCpreop | ESCerror);
|
||||
}
|
||||
|
||||
ESC_read (ESCREG_SM3, (void *) &ESCvar.SM[3], sizeof (ESCvar.SM[3]));
|
||||
SM = (_ESCsm2 *) & ESCvar.SM[3];
|
||||
if ((etohs (SM->PSA) != ESC_SM3_sma) || (etohs (SM->Length) != ESCvar.ESC_SM3_sml)
|
||||
|| (SM->Command != ESC_SM3_smc) || !(SM->ActESC & ESC_SM3_act))
|
||||
/* Check SM settings */
|
||||
if ((etohs (SM->PSA) != ESC_SM3_sma) ||
|
||||
(SM->Command != ESC_SM3_smc))
|
||||
{
|
||||
ESCvar.SMtestresult = SMRESULT_ERRSM3;
|
||||
/* fail state change */
|
||||
return (ESCpreop | ESCerror);
|
||||
}
|
||||
/* Check run-time settings */
|
||||
/* Check length */
|
||||
else if (etohs (SM->Length) != ESCvar.ESC_SM3_sml)
|
||||
{
|
||||
ESCvar.SMtestresult = SMRESULT_ERRSM3;
|
||||
/* fail state change */
|
||||
return (ESCpreop | ESCerror);
|
||||
}
|
||||
/* SM disabled and (SM activated or length > 0) set by master */
|
||||
else if (((ESC_SM3_act & ESCREG_SYNC_ACT_ACTIVATED) == 0) &&
|
||||
((SM->ActESC & ESCREG_SYNC_ACT_ACTIVATED) || (ESCvar.ESC_SM3_sml > 0)))
|
||||
{
|
||||
ESCvar.SMtestresult = SMRESULT_ERRSM3;
|
||||
/* fail state change */
|
||||
return (ESCpreop | ESCerror);
|
||||
}
|
||||
/* SM enabled and (length > 0 but SM disabled) set by master */
|
||||
else if (((ESC_SM3_act & ESCREG_SYNC_ACT_ACTIVATED) > 0) &&
|
||||
((SM->ActESC & ESCREG_SYNC_ACT_ACTIVATED) == 0) &&
|
||||
(ESCvar.ESC_SM3_sml > 0))
|
||||
{
|
||||
ESCvar.SMtestresult = SMRESULT_ERRSM3;
|
||||
/* fail state change */
|
||||
|
@ -724,7 +806,12 @@ uint8_t ESC_startinput (uint8_t state)
|
|||
|
||||
if (state != (ESCpreop | ESCerror))
|
||||
{
|
||||
ESC_SMenable (3);
|
||||
/* If inputs > 0 , enable SM3 */
|
||||
if (ESCvar.ESC_SM3_sml > 0)
|
||||
{
|
||||
ESC_SMenable (3);
|
||||
}
|
||||
/* Go to state input regardless of any inputs present */
|
||||
CC_ATOMIC_SET(ESCvar.App.state, APPSTATE_INPUT);
|
||||
}
|
||||
else
|
||||
|
@ -764,15 +851,22 @@ uint8_t ESC_startinput (uint8_t state)
|
|||
{
|
||||
if (ESCvar.esc_hw_interrupt_enable != NULL)
|
||||
{
|
||||
if(ESCvar.dcsync > 0)
|
||||
uint32_t int_mask;
|
||||
|
||||
if (ESCvar.ESC_SM2_sml == 0)
|
||||
{
|
||||
ESCvar.esc_hw_interrupt_enable(ESCREG_ALEVENT_DC_SYNC0 |
|
||||
ESCREG_ALEVENT_SM2);
|
||||
int_mask = ESCREG_ALEVENT_SM3;
|
||||
}
|
||||
else
|
||||
{
|
||||
ESCvar.esc_hw_interrupt_enable(ESCREG_ALEVENT_SM2);
|
||||
int_mask = ESCREG_ALEVENT_SM2;
|
||||
}
|
||||
|
||||
if (ESCvar.dcsync > 0)
|
||||
{
|
||||
int_mask |= ESCREG_ALEVENT_DC_SYNC0;
|
||||
}
|
||||
ESCvar.esc_hw_interrupt_enable (int_mask);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -795,7 +889,8 @@ void ESC_stopinput (void)
|
|||
(ESCvar.esc_hw_interrupt_disable != NULL))
|
||||
{
|
||||
ESCvar.esc_hw_interrupt_disable (ESCREG_ALEVENT_DC_SYNC0 |
|
||||
ESCREG_ALEVENT_SM2);
|
||||
ESCREG_ALEVENT_SM2 |
|
||||
ESCREG_ALEVENT_SM3);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -809,8 +904,13 @@ void ESC_stopinput (void)
|
|||
*/
|
||||
uint8_t ESC_startoutput (uint8_t state)
|
||||
{
|
||||
|
||||
ESC_SMenable (2);
|
||||
|
||||
/* If outputs > 0 , enable SM2 */
|
||||
if (ESCvar.ESC_SM2_sml > 0)
|
||||
{
|
||||
ESC_SMenable (2);
|
||||
}
|
||||
/* Go to state output regardless of any outputs present */
|
||||
CC_ATOMIC_OR(ESCvar.App.state, APPSTATE_OUTPUT);
|
||||
return state;
|
||||
|
||||
|
@ -917,6 +1017,75 @@ void ESC_sm_act_event (void)
|
|||
ESC_SMack (7);
|
||||
}
|
||||
}
|
||||
|
||||
static bool ESC_check_id_request (uint16_t ALcontrol, uint8_t * an)
|
||||
{
|
||||
if ((ALcontrol & ESCREG_AL_ID_REQUEST) != 0)
|
||||
{
|
||||
uint8_t state = ALcontrol & ESCREG_AL_ERRACKMASK;
|
||||
|
||||
if ((state != ESCboot) &&
|
||||
((state < ESCsafeop) || (*an == ESCsafeop) || (*an == ESCop)))
|
||||
{
|
||||
uint16_t ALstatuscode;
|
||||
|
||||
ESC_read (ESCREG_ALERROR,
|
||||
(void *)&ALstatuscode,
|
||||
sizeof (ALstatuscode));
|
||||
|
||||
return (ALstatuscode == ALERR_NONE);
|
||||
}
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
static uint8_t ESC_load_device_id (void)
|
||||
{
|
||||
uint16_t device_id;
|
||||
|
||||
if (ESCvar.get_device_id != NULL)
|
||||
{
|
||||
if (ESCvar.get_device_id (&device_id) != 0)
|
||||
{
|
||||
device_id = 0;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
ESC_read (ESCREG_CONF_STATION_ALIAS,
|
||||
(void *)&device_id,
|
||||
sizeof (device_id));
|
||||
}
|
||||
|
||||
if (device_id != 0)
|
||||
{
|
||||
/* Load the Device Identification Value to the AL Status Code register */
|
||||
ESC_ALerror (device_id);
|
||||
|
||||
return ESCREG_AL_ID_REQUEST;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
#ifdef ESC_DEBUG
|
||||
static char * ESC_state_to_string (uint8_t ESC_state)
|
||||
{
|
||||
switch (ESC_state)
|
||||
{
|
||||
case ESCinit: return "Init";
|
||||
case ESCpreop: return "Pre-Operational";
|
||||
case ESCboot: return "Bootstrap";
|
||||
case ESCsafeop: return "Safe-Operational";
|
||||
case ESCop: return "Operational";
|
||||
case ESCerror: return "Error";
|
||||
}
|
||||
|
||||
return "Unknown";
|
||||
}
|
||||
#endif
|
||||
|
||||
/** The state handler acting on ALControl Bit(0)
|
||||
* events in the Al Event Request register 0x220.
|
||||
*
|
||||
|
@ -955,7 +1124,7 @@ void ESC_state (void)
|
|||
}
|
||||
|
||||
/* Mask high bits ALcommand, low bits ALstatus */
|
||||
as = (ac << 4) | (as & 0x0f);
|
||||
as = (uint8_t)((ac << 4) | (as & 0x0f));
|
||||
|
||||
/* Call post state change hook case it have been configured */
|
||||
if (ESCvar.pre_state_change_hook != NULL)
|
||||
|
@ -978,7 +1147,6 @@ void ESC_state (void)
|
|||
{
|
||||
/* get station address */
|
||||
ESC_address ();
|
||||
COE_initDefaultValues ();
|
||||
an = ESC_startmbx (ac);
|
||||
break;
|
||||
}
|
||||
|
@ -1096,6 +1264,11 @@ void ESC_state (void)
|
|||
an = ESCsafeop | ESCerror;
|
||||
ESC_ALerror (ALERR_INVALIDSTATECHANGE);
|
||||
ESC_stopoutput ();
|
||||
/* If no outputs present, we need to flag error using SM3 */
|
||||
if (ESCvar.ESC_SM2_sml == 0 && ESCvar.ESC_SM3_sml > 0)
|
||||
{
|
||||
ESC_SMdisable (3);
|
||||
}
|
||||
break;
|
||||
}
|
||||
case OP_TO_SAFEOP:
|
||||
|
@ -1109,6 +1282,11 @@ void ESC_state (void)
|
|||
if (an == ESCop)
|
||||
{
|
||||
ESC_stopoutput ();
|
||||
/* If no outputs present, we need to flag error using SM3 */
|
||||
if (ESCvar.ESC_SM2_sml == 0 && ESCvar.ESC_SM3_sml > 0)
|
||||
{
|
||||
ESC_SMdisable (3);
|
||||
}
|
||||
an = ESCsafeop;
|
||||
}
|
||||
if (as == ESCsafeop)
|
||||
|
@ -1133,8 +1311,16 @@ void ESC_state (void)
|
|||
ESC_ALerror (ALERR_NONE);
|
||||
}
|
||||
|
||||
if (ESC_check_id_request (ESCvar.ALcontrol, &an))
|
||||
{
|
||||
an |= ESC_load_device_id ();
|
||||
}
|
||||
|
||||
ESC_ALstatus (an);
|
||||
DPRINT ("state %x\n", an);
|
||||
|
||||
#ifdef ESC_DEBUG
|
||||
DPRINT ("state %s\n", ESC_state_to_string (an & 0xF));
|
||||
#endif
|
||||
}
|
||||
/** Function copying the application configuration variable
|
||||
* data to the stack local variable.
|
||||
|
@ -1158,6 +1344,7 @@ void ESC_config (esc_cfg_t * cfg)
|
|||
ESCvar.mbboot[0] = mbboot0;
|
||||
ESCvar.mbboot[1] = mbboot1;
|
||||
|
||||
ESCvar.skip_default_initialization = cfg->skip_default_initialization;
|
||||
ESCvar.set_defaults_hook = cfg->set_defaults_hook;
|
||||
ESCvar.pre_state_change_hook = cfg->pre_state_change_hook;
|
||||
ESCvar.post_state_change_hook = cfg->post_state_change_hook;
|
||||
|
@ -1165,10 +1352,13 @@ void ESC_config (esc_cfg_t * cfg)
|
|||
ESCvar.safeoutput_override = cfg->safeoutput_override;
|
||||
ESCvar.pre_object_download_hook = cfg->pre_object_download_hook;
|
||||
ESCvar.post_object_download_hook = cfg->post_object_download_hook;
|
||||
ESCvar.pre_object_upload_hook = cfg->pre_object_upload_hook;
|
||||
ESCvar.post_object_upload_hook = cfg->post_object_upload_hook;
|
||||
ESCvar.rxpdo_override = cfg->rxpdo_override;
|
||||
ESCvar.txpdo_override = cfg->txpdo_override;
|
||||
ESCvar.esc_hw_interrupt_enable = cfg->esc_hw_interrupt_enable;
|
||||
ESCvar.esc_hw_interrupt_disable = cfg->esc_hw_interrupt_disable;
|
||||
ESCvar.esc_hw_eep_handler = cfg->esc_hw_eep_handler;
|
||||
ESCvar.esc_check_dc_handler = cfg->esc_check_dc_handler;
|
||||
ESCvar.get_device_id = cfg->get_device_id;
|
||||
}
|
||||
|
|
87
soes/esc.h
87
soes/esc.h
|
@ -11,14 +11,18 @@
|
|||
#ifndef __esc__
|
||||
#define __esc__
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <cc.h>
|
||||
#include <esc_coe.h>
|
||||
#include "options.h"
|
||||
|
||||
#define ESCREG_ADDRESS 0x0010
|
||||
#define ESCREG_CONF_STATION_ALIAS 0x0012
|
||||
#define ESCREG_DLSTATUS 0x0110
|
||||
#define ESCREG_ALCONTROL 0x0120
|
||||
#define ESCREG_ALCONTROL_ERROR_ACK 0x0010
|
||||
#define ESCREG_ALSTATUS 0x0130
|
||||
#define ESCREG_ALSTATUS_ERROR_IND 0x0010
|
||||
#define ESCREG_ALERROR 0x0134
|
||||
#define ESCREG_ALEVENTMASK 0x0204
|
||||
#define ESCREG_ALEVENT 0x0220
|
||||
|
@ -57,6 +61,7 @@
|
|||
#define ESCREG_AL_STATEMASK 0x001f
|
||||
#define ESCREG_AL_ALLBUTINITMASK 0x0e
|
||||
#define ESCREG_AL_ERRACKMASK 0x0f
|
||||
#define ESCREG_AL_ID_REQUEST 0x0020
|
||||
|
||||
#define SYNCTYPE_SUPPORT_FREERUN 0x01
|
||||
#define SYNCTYPE_SUPPORT_SYNCHRON 0x02
|
||||
|
@ -161,17 +166,41 @@
|
|||
#define MBXERR_INVALIDSIZE 0x0008
|
||||
|
||||
#define ABORT_NOTOGGLE 0x05030000
|
||||
#define ABORT_TRANSFER_TIMEOUT 0x05040000
|
||||
#define ABORT_UNKNOWN 0x05040001
|
||||
#define ABORT_INVALID_BLOCK_SIZE 0x05040002
|
||||
#define ABORT_INVALID_SEQUENCE_NUMBER 0x05040003
|
||||
#define ABORT_BLOCK_CRC_ERROR 0x05040004
|
||||
#define ABORT_OUT_OF_MEMORY 0x05040005
|
||||
#define ABORT_UNSUPPORTED 0x06010000
|
||||
#define ABORT_WRITEONLY 0x06010001
|
||||
#define ABORT_READONLY 0x06010002
|
||||
#define ABORT_SUBINDEX0_NOT_ZERO 0x06010003
|
||||
#define ABORT_CA_NOT_SUPPORTED 0x06010004
|
||||
#define ABORT_EXCEEDS_MBOX_SIZE 0x06010005
|
||||
#define ABORT_SDO_DOWNLOAD_BLOCKED 0x06010006
|
||||
#define ABORT_NOOBJECT 0x06020000
|
||||
#define ABORT_MAPPING_OBJECT_ERROR 0x06040041
|
||||
#define ABORT_MAPPING_LENGTH_ERROR 0x06040042
|
||||
#define ABORT_GENERAL_PARAMETER_ERROR 0x06040043
|
||||
#define ABORT_GENERAL_DEVICE_ERROR 0x06040047
|
||||
#define ABORT_HARDWARE_ERROR 0x06060000
|
||||
#define ABORT_TYPEMISMATCH 0x06070010
|
||||
#define ABORT_DATATYPE_TOO_HIGH 0x06070012
|
||||
#define ABORT_DATATYPE_TOO_LOW 0x06070013
|
||||
#define ABORT_NOSUBINDEX 0x06090011
|
||||
#define ABORT_VALUE_EXCEEDED 0x06090030
|
||||
#define ABORT_VALUE_TOO_HIGH 0x06090031
|
||||
#define ABORT_VALUE_TOO_LOW 0x06090032
|
||||
#define ABORT_MODULE_LIST_MISMATCH 0x06090033
|
||||
#define ABORT_MAX_VAL_LESS_THAN_MIN_VAL 0x06090036
|
||||
#define ABORT_RESOURCE_NOT_AVAILABLE 0x060A0023
|
||||
#define ABORT_GENERALERROR 0x08000000
|
||||
#define ABORT_DATA_STORE_ERROR 0x08000020
|
||||
#define ABORT_DATA_STORE_LOCAL_ERROR 0x08000021
|
||||
#define ABORT_NOTINTHISSTATE 0x08000022
|
||||
#define ABORT_OBJECT_DICTIONARY_ERROR 0x08000023
|
||||
#define ABORT_NO_DATA_AVAILABLE 0x08000024
|
||||
|
||||
#define MBXstate_idle 0x00
|
||||
#define MBXstate_inclaim 0x01
|
||||
|
@ -181,9 +210,9 @@
|
|||
#define MBXstate_backup 0x05
|
||||
#define MBXstate_again 0x06
|
||||
|
||||
#define COE_DEFAULTLENGTH 0x0a
|
||||
#define COE_HEADERSIZE 0x0a
|
||||
#define COE_SEGMENTHEADERSIZE 0x03
|
||||
#define COE_DEFAULTLENGTH 0x0AU
|
||||
#define COE_HEADERSIZE 0x0AU
|
||||
#define COE_SEGMENTHEADERSIZE 0x03U
|
||||
#define COE_SDOREQUEST 0x02
|
||||
#define COE_SDORESPONSE 0x03
|
||||
#define COE_SDOINFORMATION 0x08
|
||||
|
@ -192,7 +221,10 @@
|
|||
#define COE_COMMAND_UPLOADRESPONSE 0x40
|
||||
#define COE_COMMAND_UPLOADSEGMENT 0x00
|
||||
#define COE_COMMAND_UPLOADSEGREQ 0x60
|
||||
#define COE_COMMAND_DOWNLOADREQUEST 0x20
|
||||
#define COE_COMMAND_DOWNLOADRESPONSE 0x60
|
||||
#define COE_COMMAND_DOWNLOADSEGREQ 0x00
|
||||
#define COE_COMMAND_DOWNLOADSEGRESP 0x20
|
||||
#define COE_COMMAND_LASTSEGMENTBIT 0x01
|
||||
#define COE_SIZE_INDICATOR 0x01
|
||||
#define COE_EXPEDITED_INDICATOR 0x02
|
||||
|
@ -239,6 +271,7 @@
|
|||
#define FOE_ERR_NOTINBOOTSTRAP 0x8009
|
||||
#define FOE_ERR_NORIGHTS 0x800A
|
||||
#define FOE_ERR_PROGERROR 0x800B
|
||||
#define FOE_ERR_CHECKSUM 0x800C
|
||||
|
||||
#define FOE_OP_RRQ 1
|
||||
#define FOE_OP_WRQ 2
|
||||
|
@ -263,6 +296,8 @@
|
|||
#define APPSTATE_INPUT 0x01
|
||||
#define APPSTATE_OUTPUT 0x02
|
||||
|
||||
#define PREALLOC_BUFFER_SIZE (PREALLOC_FACTOR * MBXSIZE)
|
||||
|
||||
typedef struct sm_cfg
|
||||
{
|
||||
uint16_t cfg_sma;
|
||||
|
@ -277,6 +312,7 @@ typedef struct esc_cfg
|
|||
void * user_arg;
|
||||
int use_interrupt;
|
||||
int watchdog_cnt;
|
||||
bool skip_default_initialization;
|
||||
void (*set_defaults_hook) (void);
|
||||
void (*pre_state_change_hook) (uint8_t * as, uint8_t * an);
|
||||
void (*post_state_change_hook) (uint8_t * as, uint8_t * an);
|
||||
|
@ -287,7 +323,15 @@ typedef struct esc_cfg
|
|||
void * data,
|
||||
size_t size,
|
||||
uint16_t flags);
|
||||
void (*post_object_download_hook) (uint16_t index,
|
||||
uint32_t (*post_object_download_hook) (uint16_t index,
|
||||
uint8_t subindex,
|
||||
uint16_t flags);
|
||||
uint32_t (*pre_object_upload_hook) (uint16_t index,
|
||||
uint8_t subindex,
|
||||
void * data,
|
||||
size_t *size,
|
||||
uint16_t flags);
|
||||
uint32_t (*post_object_upload_hook) (uint16_t index,
|
||||
uint8_t subindex,
|
||||
uint16_t flags);
|
||||
void (*rxpdo_override) (void);
|
||||
|
@ -296,6 +340,7 @@ typedef struct esc_cfg
|
|||
void (*esc_hw_interrupt_disable) (uint32_t mask);
|
||||
void (*esc_hw_eep_handler) (void);
|
||||
uint16_t (*esc_check_dc_handler) (void);
|
||||
int (*get_device_id) (uint16_t * device_id);
|
||||
} esc_cfg_t;
|
||||
|
||||
typedef struct
|
||||
|
@ -392,6 +437,7 @@ typedef struct
|
|||
int use_interrupt;
|
||||
sm_cfg_t mb[2];
|
||||
sm_cfg_t mbboot[2];
|
||||
bool skip_default_initialization;
|
||||
void (*set_defaults_hook) (void);
|
||||
void (*pre_state_change_hook) (uint8_t * as, uint8_t * an);
|
||||
void (*post_state_change_hook) (uint8_t * as, uint8_t * an);
|
||||
|
@ -402,7 +448,15 @@ typedef struct
|
|||
void * data,
|
||||
size_t size,
|
||||
uint16_t flags);
|
||||
void (*post_object_download_hook) (uint16_t index,
|
||||
uint32_t (*post_object_download_hook) (uint16_t index,
|
||||
uint8_t subindex,
|
||||
uint16_t flags);
|
||||
uint32_t (*pre_object_upload_hook) (uint16_t index,
|
||||
uint8_t subindex,
|
||||
void * data,
|
||||
size_t *size,
|
||||
uint16_t flags);
|
||||
uint32_t (*post_object_upload_hook) (uint16_t index,
|
||||
uint8_t subindex,
|
||||
uint16_t flags);
|
||||
void (*rxpdo_override) (void);
|
||||
|
@ -411,8 +465,9 @@ typedef struct
|
|||
void (*esc_hw_interrupt_disable) (uint32_t mask);
|
||||
void (*esc_hw_eep_handler) (void);
|
||||
uint16_t (*esc_check_dc_handler) (void);
|
||||
int (*get_device_id) (uint16_t * device_id);
|
||||
uint8_t MBXrun;
|
||||
size_t activembxsize;
|
||||
uint32_t activembxsize;
|
||||
sm_cfg_t * activemb0;
|
||||
sm_cfg_t * activemb1;
|
||||
uint16_t ESC_SM2_sml;
|
||||
|
@ -434,8 +489,11 @@ typedef struct
|
|||
uint8_t segmented;
|
||||
void *data;
|
||||
uint16_t entries;
|
||||
uint16_t frags;
|
||||
uint16_t fragsleft;
|
||||
uint32_t frags;
|
||||
uint32_t fragsleft;
|
||||
uint16_t index;
|
||||
uint8_t subindex;
|
||||
uint16_t flags;
|
||||
|
||||
uint8_t toggle;
|
||||
|
||||
|
@ -448,9 +506,10 @@ typedef struct
|
|||
/* Volatile since it may be read from ISR */
|
||||
volatile int watchdogcnt;
|
||||
volatile uint32_t Time;
|
||||
volatile uint16_t ALevent;
|
||||
volatile uint32_t ALevent;
|
||||
volatile int8_t synccounter;
|
||||
volatile _App App;
|
||||
uint8_t mbxdata[PREALLOC_BUFFER_SIZE];
|
||||
} _ESCvar;
|
||||
|
||||
CC_PACKED_BEGIN
|
||||
|
@ -520,7 +579,7 @@ typedef struct CC_PACKED
|
|||
CC_PACKED_END
|
||||
|
||||
CC_PACKED_BEGIN
|
||||
typedef struct CC_PACKED
|
||||
typedef struct CC_PACKED CC_ALIGNED(4)
|
||||
{
|
||||
_MBXh mbxheader;
|
||||
_COEh coeheader;
|
||||
|
@ -532,7 +591,7 @@ typedef struct CC_PACKED
|
|||
CC_PACKED_END
|
||||
|
||||
CC_PACKED_BEGIN
|
||||
typedef struct CC_PACKED
|
||||
typedef struct CC_PACKED CC_ALIGNED(4)
|
||||
{
|
||||
_MBXh mbxheader;
|
||||
_COEh coeheader;
|
||||
|
@ -642,11 +701,11 @@ typedef struct
|
|||
#define ESC_SM3_smc (SM3_smc)
|
||||
#define ESC_SM3_act (SM3_act)
|
||||
|
||||
#define ESC_MBXHSIZE sizeof(_MBXh)
|
||||
#define ESC_MBXHSIZE ((uint32_t)sizeof(_MBXh))
|
||||
#define ESC_MBXDSIZE (ESC_MBXSIZE - ESC_MBXHSIZE)
|
||||
#define ESC_FOEHSIZE sizeof(_FOEh)
|
||||
#define ESC_FOEHSIZE (uint32_t)sizeof(_FOEh)
|
||||
#define ESC_FOE_DATA_SIZE (ESC_MBXSIZE - (ESC_MBXHSIZE +ESC_FOEHSIZE))
|
||||
#define ESC_EOEHSIZE sizeof(_EOEh)
|
||||
#define ESC_EOEHSIZE ((uint32_t)sizeof(_EOEh))
|
||||
#define ESC_EOE_DATA_SIZE (ESC_MBXSIZE - (ESC_MBXHSIZE +ESC_EOEHSIZE))
|
||||
|
||||
void ESC_config (esc_cfg_t * cfg);
|
||||
|
|
973
soes/esc_coe.c
973
soes/esc_coe.c
File diff suppressed because it is too large
Load Diff
|
@ -13,8 +13,8 @@
|
|||
|
||||
#include <cc.h>
|
||||
|
||||
CC_PACKED_BEGIN
|
||||
typedef struct CC_PACKED
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint16_t subindex;
|
||||
uint16_t datatype;
|
||||
|
@ -24,10 +24,9 @@ typedef struct CC_PACKED
|
|||
uint32_t value;
|
||||
void *data;
|
||||
} _objd;
|
||||
CC_PACKED_END
|
||||
|
||||
CC_PACKED_BEGIN
|
||||
typedef struct CC_PACKED
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint16_t index;
|
||||
uint16_t objtype;
|
||||
|
@ -36,12 +35,13 @@ typedef struct CC_PACKED
|
|||
const char *name;
|
||||
const _objd *objdesc;
|
||||
} _objectlist;
|
||||
CC_PACKED_END
|
||||
|
||||
|
||||
typedef struct
|
||||
{
|
||||
const _objd * obj;
|
||||
uint16_t offset;
|
||||
const _objectlist * objectlistitem;
|
||||
uint32_t offset;
|
||||
} _SMmap;
|
||||
|
||||
#define OBJH_READ 0
|
||||
|
@ -72,6 +72,9 @@ typedef struct
|
|||
#define DTYPE_REAL64 0x0011
|
||||
#define DTYPE_PDO_MAPPING 0x0021
|
||||
#define DTYPE_IDENTITY 0x0023
|
||||
#define DTYPE_BITARR8 0x002D
|
||||
#define DTYPE_BITARR16 0x002E
|
||||
#define DTYPE_BITARR32 0x002F
|
||||
#define DTYPE_BIT1 0x0030
|
||||
#define DTYPE_BIT2 0x0031
|
||||
#define DTYPE_BIT3 0x0032
|
||||
|
@ -80,6 +83,10 @@ typedef struct
|
|||
#define DTYPE_BIT6 0x0035
|
||||
#define DTYPE_BIT7 0x0036
|
||||
#define DTYPE_BIT8 0x0037
|
||||
#define DTYPE_ARRAY_OF_INT 0x0260
|
||||
#define DTYPE_ARRAY_OF_SINT 0x0261
|
||||
#define DTYPE_ARRAY_OF_DINT 0x0262
|
||||
#define DTYPE_ARRAY_OF_UDINT 0x0263
|
||||
|
||||
#define ATYPE_Rpre 0x01
|
||||
#define ATYPE_Rsafe 0x02
|
||||
|
@ -89,29 +96,43 @@ typedef struct
|
|||
#define ATYPE_Wop 0x20
|
||||
#define ATYPE_RXPDO 0x40
|
||||
#define ATYPE_TXPDO 0x80
|
||||
#define ATYPE_BACKUP 0x100
|
||||
#define ATYPE_SETTING 0x200
|
||||
|
||||
#define ATYPE_RO (ATYPE_Rpre | ATYPE_Rsafe | ATYPE_Rop)
|
||||
#define ATYPE_RW (ATYPE_Wpre | ATYPE_Wsafe | ATYPE_Wop | ATYPE_RO)
|
||||
#define ATYPE_WO (ATYPE_Wpre | ATYPE_Wsafe | ATYPE_Wop)
|
||||
#define ATYPE_RW (ATYPE_RO | ATYPE_WO)
|
||||
#define ATYPE_RWpre (ATYPE_Wpre | ATYPE_RO)
|
||||
#define ATYPE_RWop (ATYPE_Wop | ATYPE_RO)
|
||||
#define ATYPE_RWpre_safe (ATYPE_Wpre | ATYPE_Wsafe | ATYPE_RO)
|
||||
|
||||
#define TX_PDO_OBJIDX 0x1c13
|
||||
#define RX_PDO_OBJIDX 0x1c12
|
||||
|
||||
#define COMPLETE_ACCESS_FLAG (1 << 15)
|
||||
|
||||
void ESC_coeprocess (void);
|
||||
int16_t SDO_findsubindex (int32_t nidx, uint8_t subindex);
|
||||
int32_t SDO_findobject (uint16_t index);
|
||||
uint16_t sizeOfPDO (uint16_t index, int * nmappings, _SMmap * sm, int max_mappings);
|
||||
void SDO_abort (uint16_t index, uint8_t subindex, uint32_t abortcode);
|
||||
void COE_initDefaultValues (void);
|
||||
|
||||
void COE_pdoPack (uint8_t * buffer, int nmappings, _SMmap * sm);
|
||||
void COE_pdoUnpack (uint8_t * buffer, int nmappings, _SMmap * sm);
|
||||
uint8_t COE_maxSub (uint16_t index);
|
||||
|
||||
extern void ESC_objecthandler (uint16_t index, uint8_t subindex, uint16_t flags);
|
||||
extern uint32_t ESC_pre_objecthandler (uint16_t index,
|
||||
extern uint32_t ESC_download_post_objecthandler (uint16_t index, uint8_t subindex, uint16_t flags);
|
||||
extern uint32_t ESC_download_pre_objecthandler (uint16_t index,
|
||||
uint8_t subindex,
|
||||
void * data,
|
||||
size_t size,
|
||||
uint16_t flags);
|
||||
extern uint32_t ESC_upload_pre_objecthandler (uint16_t index,
|
||||
uint8_t subindex,
|
||||
void * data,
|
||||
size_t *size,
|
||||
uint16_t flags);
|
||||
extern uint32_t ESC_upload_post_objecthandler (uint16_t index, uint8_t subindex, uint16_t flags);
|
||||
extern const _objectlist SDOobjects[];
|
||||
|
||||
#endif
|
||||
|
|
|
@ -15,6 +15,8 @@
|
|||
#include <string.h>
|
||||
|
||||
static uint8_t eep_buf[8];
|
||||
static uint16_t eep_read_size = 8U;
|
||||
static void (*eep_reload_ptr)(eep_stat_t *stat) = NULL;
|
||||
|
||||
/** EPP periodic task of ESC side EEPROM emulation.
|
||||
*
|
||||
|
@ -51,19 +53,53 @@ void EEP_process (void)
|
|||
break;
|
||||
|
||||
case EEP_CMD_READ:
|
||||
case EEP_CMD_RELOAD:
|
||||
/* handle read request */
|
||||
if (EEP_read (stat.addr * sizeof(uint16_t), eep_buf, EEP_READ_SIZE) != 0) {
|
||||
if (EEP_read (stat.addr * 2U /* sizeof(uint16_t) */, eep_buf, eep_read_size) != 0) {
|
||||
stat.contstat.bits.ackErr = 1;
|
||||
} else {
|
||||
ESC_write (ESCREG_EEDATA, eep_buf, EEP_READ_SIZE);
|
||||
}
|
||||
else {
|
||||
ESC_write(ESCREG_EEDATA, eep_buf, eep_read_size);
|
||||
}
|
||||
break;
|
||||
|
||||
case EEP_CMD_RELOAD:
|
||||
/* user defined reload if set */
|
||||
if (eep_reload_ptr != NULL) {
|
||||
/* Reload function is responsible to update
|
||||
* control status register bits.
|
||||
*/
|
||||
(*eep_reload_ptr)(&stat);
|
||||
}
|
||||
else {
|
||||
if (eep_read_size == 8U) {
|
||||
/* handle reload request */
|
||||
if (EEP_read(stat.addr * 2U /* sizeof(uint16_t) */, eep_buf, eep_read_size) != 0) {
|
||||
stat.contstat.bits.ackErr = 1;
|
||||
}
|
||||
else {
|
||||
ESC_write(ESCREG_EEDATA, eep_buf, eep_read_size);
|
||||
}
|
||||
}
|
||||
else {
|
||||
/* Default handler of reload request for 4 Byte read, load config alias.
|
||||
* To support other ESC behavior, implement user defined reload.
|
||||
*/
|
||||
if (EEP_read(EEP_CONFIG_ALIAS_WORD_OFFSET * 2U /* sizeof(uint16_t) */,
|
||||
eep_buf,
|
||||
2U /* 2 Bytes config alias*/) != 0) {
|
||||
stat.contstat.bits.ackErr = 1;
|
||||
}
|
||||
else {
|
||||
ESC_write(ESCREG_EEDATA, eep_buf, 2U /* 2 Bytes config alias*/);
|
||||
}
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case EEP_CMD_WRITE:
|
||||
/* handle write request */
|
||||
ESC_read (ESCREG_EEDATA, eep_buf, EEP_WRITE_SIZE);
|
||||
if (EEP_write (stat.addr * sizeof(uint16_t), eep_buf, EEP_WRITE_SIZE) != 0) {
|
||||
if (EEP_write (stat.addr * 2U /* sizeof(uint16_t) */, eep_buf, EEP_WRITE_SIZE) != 0) {
|
||||
stat.contstat.bits.ackErr = 1;
|
||||
}
|
||||
break;
|
||||
|
@ -78,3 +114,24 @@ void EEP_process (void)
|
|||
}
|
||||
}
|
||||
|
||||
/** EPP Set read size, 4 Byte or 8 Byte depending on ESC.
|
||||
* Default 8 Byte.
|
||||
*/
|
||||
void EEP_set_read_size (uint16_t read_size)
|
||||
{
|
||||
if ((read_size == 8U) || (read_size == 4U)) {
|
||||
eep_read_size = read_size;
|
||||
}
|
||||
}
|
||||
|
||||
/** EPP Set reload function pointer.
|
||||
* Function shall update current stat accordingly.
|
||||
* Eg. on CRC error reload function shall set
|
||||
* stat.contstat.bits.csumErr = 1
|
||||
* stat.contstat.bits.ackErr = 1
|
||||
*
|
||||
*/
|
||||
void EEP_set_reload_function_pointer(void (*reload_ptr)(eep_stat_t* stat))
|
||||
{
|
||||
eep_reload_ptr = reload_ptr;
|
||||
}
|
||||
|
|
|
@ -15,14 +15,16 @@
|
|||
#include "esc.h"
|
||||
|
||||
/* EEPROM commands */
|
||||
#define EEP_CMD_IDLE 0x0
|
||||
#define EEP_CMD_READ 0x1
|
||||
#define EEP_CMD_WRITE 0x2
|
||||
#define EEP_CMD_RELOAD 0x3
|
||||
#define EEP_CMD_IDLE 0x0
|
||||
#define EEP_CMD_READ 0x1
|
||||
#define EEP_CMD_WRITE 0x2
|
||||
#define EEP_CMD_RELOAD 0x4
|
||||
|
||||
/* read/write size */
|
||||
#define EEP_READ_SIZE 8
|
||||
#define EEP_WRITE_SIZE 2
|
||||
/* write size */
|
||||
#define EEP_WRITE_SIZE 2
|
||||
|
||||
/* EEPROm word offset */
|
||||
#define EEP_CONFIG_ALIAS_WORD_OFFSET 4
|
||||
|
||||
/* CONSTAT register content */
|
||||
typedef struct CC_PACKED
|
||||
|
@ -69,6 +71,80 @@ typedef union eep_config
|
|||
/* periodic task */
|
||||
void EEP_process (void);
|
||||
|
||||
/**
|
||||
* Application Notes: EEPROM emulation
|
||||
*
|
||||
* NOTE: Special handling needed when 4 Byte read is supported.
|
||||
*
|
||||
* Ref. ET1100 Datasheet sec2_registers_3i0, chapter 2.45.1,
|
||||
* "EEPROM emulation with 32 bit EEPROM data register (0x0502[6]=0)".
|
||||
*
|
||||
* For a Reload command, fill the EEPROM Data register with the
|
||||
* values shown in the chapter 2.45.1 before acknowledging
|
||||
* the command. These values are automatically transferred to the
|
||||
* designated registers after the Reload command is acknowledged.
|
||||
*
|
||||
* NOTE: When 4 Byte read is supported, EEP_process will only load
|
||||
* config alias on reload.
|
||||
*
|
||||
* NOTE: EEP_process support implementing a custom reload function
|
||||
* for both 4 Byte and 8 Byte read support.
|
||||
*
|
||||
* NOTE: Code snippet for custom reload function when 4 Byte read is supported.
|
||||
*
|
||||
* void reload_ptr(eep_stat_t *stat)
|
||||
* {
|
||||
* eep_config_t ee_cfg;
|
||||
*
|
||||
* // Read configuration area
|
||||
* EEP_read(0, &ee_cfg, sizeof(ee_cfg);
|
||||
*
|
||||
* // Check CRC
|
||||
* if(is_crc_ok(&ee_cfg) == true)
|
||||
* {
|
||||
* // Write config alias to EEPROM data registers.
|
||||
* // Will be loaded to 0x12:13 on command ack.
|
||||
* ESC_write(ESCREG_EEDATA,
|
||||
* &ee_cfg.configured_station_alias,
|
||||
* sizeof(configured_station_alias));
|
||||
* }
|
||||
* else
|
||||
* {
|
||||
* // Indicate CRC error
|
||||
* stat->contstat.bits.csumErr = 1;
|
||||
* stat->contstat.bits.ackErr = 1;
|
||||
* }
|
||||
* }
|
||||
* NOTE: Code snippet for custom reload function when 8 Byte read is supported.
|
||||
*
|
||||
* void reload_ptr(eep_stat_t *stat)
|
||||
* {
|
||||
* eep_config_t ee_cfg;
|
||||
*
|
||||
* // Read configuration area
|
||||
* EEP_read(0, &ee_cfg, sizeof(ee_cfg);
|
||||
*
|
||||
* // Check CRC
|
||||
* if(is_crc_ok(&ee_cfg) == true)
|
||||
* {
|
||||
* // Load EEPROM data at requested EEPROM address
|
||||
* EEP_read (stat->addr * sizeof(uint16_t), eep_buf, 8U);
|
||||
* // Write loaded data to EEPROM data registers
|
||||
* ESC_write(ESCREG_EEDATA, eep_buf, 8U);
|
||||
* }
|
||||
* else
|
||||
* {
|
||||
* // Indicate CRC error
|
||||
* stat->contstat.bits.csumErr = 1;
|
||||
* stat->contstat.bits.ackErr = 1;
|
||||
* }
|
||||
* }
|
||||
*/
|
||||
|
||||
/* Set eep internal variables */
|
||||
void EEP_set_read_size (uint16_t read_size);
|
||||
void EEP_set_reload_function_pointer (void (*reload_ptr)(eep_stat_t *stat));
|
||||
|
||||
/* From hardware file */
|
||||
void EEP_init (void);
|
||||
int8_t EEP_read (uint32_t addr, uint8_t *data, uint16_t size);
|
||||
|
|
167
soes/esc_eoe.c
167
soes/esc_eoe.c
|
@ -20,12 +20,12 @@
|
|||
#define EOE_HTONL(x) (x)
|
||||
#define EOE_NTOHL(x) (x)
|
||||
#else
|
||||
#define EOE_HTONS(x) ((((x) & 0x00ffUL) << 8) | (((x) & 0xff00UL) >> 8))
|
||||
#define EOE_HTONS(x) ((((x) & 0x00ffU) << 8) | (((x) & 0xff00U) >> 8))
|
||||
#define EOE_NTOHS(x) EOE_HTONS(x)
|
||||
#define EOE_HTONL(x) ((((x) & 0x000000ffUL) << 24) | \
|
||||
(((x) & 0x0000ff00UL) << 8) | \
|
||||
(((x) & 0x00ff0000UL) >> 8) | \
|
||||
(((x) & 0xff000000UL) >> 24))
|
||||
#define EOE_HTONL(x) ((((x) & 0x000000ffU) << 24) | \
|
||||
(((x) & 0x0000ff00U) << 8) | \
|
||||
(((x) & 0x00ff0000U) >> 8) | \
|
||||
(((x) & 0xff000000U) >> 24))
|
||||
#define EOE_NTOHL(x) EOE_HTONL(x)
|
||||
#endif /* #if defined(EC_BIG_ENDIAN) */
|
||||
|
||||
|
@ -47,37 +47,37 @@
|
|||
/** Header frame info 1 */
|
||||
#define EOE_HDR_FRAME_TYPE_OFFSET 0
|
||||
#define EOE_HDR_FRAME_TYPE (0xF << 0)
|
||||
#define EOE_HDR_FRAME_TYPE_SET(x) (((x) & 0xF) << 0)
|
||||
#define EOE_HDR_FRAME_TYPE_SET(x) ((uint16_t)(((x) & 0xF) << 0))
|
||||
#define EOE_HDR_FRAME_TYPE_GET(x) (((x) >> 0) & 0xF)
|
||||
#define EOE_HDR_FRAME_PORT_OFFSET 4
|
||||
#define EOE_HDR_FRAME_PORT (0xF << 4)
|
||||
#define EOE_HDR_FRAME_PORT_SET(x) (((x) & 0xF) << 4)
|
||||
#define EOE_HDR_FRAME_PORT_SET(x) ((uint16_t)(((x) & 0xF) << 4))
|
||||
#define EOE_HDR_FRAME_PORT_GET(x) (((x) >> 4) & 0xF)
|
||||
#define EOE_HDR_LAST_FRAGMENT_OFFSET 8
|
||||
#define EOE_HDR_LAST_FRAGMENT (0x1 << 8)
|
||||
#define EOE_HDR_LAST_FRAGMENT_SET(x) (((x) & 0x1) << 8)
|
||||
#define EOE_HDR_LAST_FRAGMENT_SET(x) ((uint16_t)(((x) & 0x1) << 8))
|
||||
#define EOE_HDR_LAST_FRAGMENT_GET(x) (((x) >> 8) & 0x1)
|
||||
#define EOE_HDR_TIME_APPEND_OFFSET 9
|
||||
#define EOE_HDR_TIME_APPEND (0x1 << 9)
|
||||
#define EOE_HDR_TIME_APPEND_SET(x) (((x) & 0x1) << 9)
|
||||
#define EOE_HDR_TIME_APPEND_SET(x) ((uint16_t)(((x) & 0x1) << 9))
|
||||
#define EOE_HDR_TIME_APPEND_GET(x) (((x) >> 9) & 0x1)
|
||||
#define EOE_HDR_TIME_REQUEST_OFFSET 10
|
||||
#define EOE_HDR_TIME_REQUEST (0x1 << 10)
|
||||
#define EOE_HDR_TIME_REQUEST_SET(x) (((x) & 0x1) << 10)
|
||||
#define EOE_HDR_TIME_REQUEST_SET(x) ((uint16_t)(((x) & 0x1) << 10))
|
||||
#define EOE_HDR_TIME_REQUEST_GET(x) (((x) >> 10) & 0x1)
|
||||
|
||||
/** Header frame info 2 */
|
||||
#define EOE_HDR_FRAG_NO_OFFSET 0
|
||||
#define EOE_HDR_FRAG_NO (0x3F << 0)
|
||||
#define EOE_HDR_FRAG_NO_SET(x) (((x) & 0x3F) << 0)
|
||||
#define EOE_HDR_FRAG_NO_SET(x) ((uint16_t)(((x) & 0x3F) << 0))
|
||||
#define EOE_HDR_FRAG_NO_GET(x) (((x) >> 0) & 0x3F)
|
||||
#define EOE_HDR_FRAME_OFFSET_OFFSET 6
|
||||
#define EOE_HDR_FRAME_OFFSET (0x3F << 6)
|
||||
#define EOE_HDR_FRAME_OFFSET_SET(x) (((x) & 0x3F) << 6)
|
||||
#define EOE_HDR_FRAME_OFFSET_SET(x) ((uint16_t)(((x) & 0x3F) << 6))
|
||||
#define EOE_HDR_FRAME_OFFSET_GET(x) (((x) >> 6) & 0x3F)
|
||||
#define EOE_HDR_FRAME_NO_OFFSET 12
|
||||
#define EOE_HDR_FRAME_NO (0xF << 12)
|
||||
#define EOE_HDR_FRAME_NO_SET(x) (((x) & 0xF) << 12)
|
||||
#define EOE_HDR_FRAME_NO_SET(x) ((uint16_t)(((x) & 0xF) << 12))
|
||||
#define EOE_HDR_FRAME_NO_GET(x) (((x) >> 12) & 0xF)
|
||||
|
||||
/** EOE param */
|
||||
|
@ -108,6 +108,8 @@
|
|||
#define EOE_DNS_NAME_LENGTH 32
|
||||
/** Ethernet address length not including VLAN */
|
||||
#define EOE_ETHADDR_LENGTH 6
|
||||
/** IPv4 address length */
|
||||
#define EOE_IP4_LENGTH 4U /* sizeof(uint32_t) */
|
||||
|
||||
/** EOE ip4 address in network order */
|
||||
struct eoe_ip4_addr {
|
||||
|
@ -133,18 +135,18 @@ typedef struct
|
|||
/** Current RX fragment number */
|
||||
uint8_t rxfragmentno;
|
||||
/** Complete RX frame size of current frame */
|
||||
uint16_t rxframesize;
|
||||
uint32_t rxframesize;
|
||||
/** Current RX data offset in frame */
|
||||
uint16_t rxframeoffset;
|
||||
uint32_t rxframeoffset;
|
||||
/** Current RX frame number */
|
||||
uint16_t rxframeno;
|
||||
|
||||
/** Current TX fragment number */
|
||||
uint8_t txfragmentno;
|
||||
/** Complete TX frame size of current frame */
|
||||
uint16_t txframesize;
|
||||
uint32_t txframesize;
|
||||
/** Current TX data offset in frame */
|
||||
uint16_t txframeoffset;
|
||||
uint32_t txframeoffset;
|
||||
} _EOEvar;
|
||||
|
||||
/** EoE IP request structure */
|
||||
|
@ -215,7 +217,7 @@ static void EOE_ip_byte_to_uint32 (uint8_t * byte_ip, eoe_ip4_addr_t * ip)
|
|||
* @param[out] mac = variable to store mac in, should fit EOE_ETHADDR_LENGTH
|
||||
* @return 0= if we succeed, -1 if not set
|
||||
*/
|
||||
int EOE_get_mac(uint8_t port, uint8_t mac[])
|
||||
int EOE_ecat_get_mac(uint8_t port, uint8_t mac[])
|
||||
{
|
||||
int ret = -1;
|
||||
int port_ix;
|
||||
|
@ -504,7 +506,7 @@ static void EOE_get_ip (void)
|
|||
uint16_t frameinfo1;
|
||||
uint8_t port;
|
||||
uint8_t flags;
|
||||
uint8_t data_offset;
|
||||
uint32_t data_offset;
|
||||
int port_ix;
|
||||
|
||||
req_eoembx = (_EOE *) &MBX[0];
|
||||
|
@ -516,15 +518,15 @@ static void EOE_get_ip (void)
|
|||
if(port > EOE_NUMBER_OF_PORTS)
|
||||
{
|
||||
DPRINT("Invalid port\n");
|
||||
frameinfo1 = EOE_HDR_FRAME_PORT_SET(port);
|
||||
frameinfo1 |= EOE_INIT_RESP;
|
||||
frameinfo1 |= EOE_HDR_LAST_FRAGMENT;
|
||||
/* Return error response on given port */
|
||||
EOE_no_data_response((EOE_HDR_FRAME_PORT_SET(port) |
|
||||
EOE_INIT_RESP |
|
||||
EOE_HDR_LAST_FRAGMENT),
|
||||
EOE_no_data_response(frameinfo1,
|
||||
EOE_RESULT_UNSPECIFIED_ERROR);
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
/* Refresh settings if needed */
|
||||
if(eoe_cfg->load_eth_settings != NULL)
|
||||
{
|
||||
|
@ -538,10 +540,10 @@ static void EOE_get_ip (void)
|
|||
eoembx = (_EOE *) &MBX[mbxhandle * ESC_MBXSIZE];
|
||||
eoembx->mbxheader.mbxtype = MBXEOE;
|
||||
MBXcontrol[mbxhandle].state = MBXstate_outreq;
|
||||
eoembx->eoeheader.frameinfo1 =
|
||||
htoes(EOE_HDR_FRAME_TYPE_SET(EOE_GET_IP_PARAM_RESP) |
|
||||
EOE_HDR_FRAME_PORT_SET(port) |
|
||||
EOE_HDR_LAST_FRAGMENT);
|
||||
frameinfo1 = EOE_HDR_FRAME_PORT_SET(port);
|
||||
frameinfo1 |= EOE_HDR_FRAME_TYPE_SET(EOE_GET_IP_PARAM_RESP);
|
||||
frameinfo1 |= EOE_HDR_LAST_FRAGMENT;
|
||||
eoembx->eoeheader.frameinfo1 = htoes(frameinfo1);
|
||||
eoembx->eoeheader.frameinfo2 = 0;
|
||||
|
||||
/* include mac in get ip request */
|
||||
|
@ -552,55 +554,60 @@ static void EOE_get_ip (void)
|
|||
memcpy(&eoembx->data[data_offset] ,
|
||||
nic_ports[port_ix].mac.addr,
|
||||
EOE_ETHADDR_LENGTH);
|
||||
/* Add size of mac address */
|
||||
data_offset += EOE_ETHADDR_LENGTH;
|
||||
|
||||
}
|
||||
/* Add size of mac address */
|
||||
data_offset += EOE_ETHADDR_LENGTH;
|
||||
/* include ip in get ip request */
|
||||
if(nic_ports[port_ix].ip_set)
|
||||
{
|
||||
flags |= EOE_PARAM_IP_INCLUDE;
|
||||
EOE_ip_uint32_to_byte(&nic_ports[port_ix].ip,
|
||||
&eoembx->data[data_offset]);
|
||||
/* Add size of uint32 IP address */
|
||||
data_offset += EOE_IP4_LENGTH;
|
||||
}
|
||||
/* Add size of uint32 IP address */
|
||||
data_offset += 4;
|
||||
|
||||
/* include subnet in get ip request */
|
||||
if(nic_ports[port_ix].subnet_set)
|
||||
{
|
||||
flags |= EOE_PARAM_SUBNET_IP_INCLUDE;
|
||||
EOE_ip_uint32_to_byte(&nic_ports[port_ix].subnet,
|
||||
&eoembx->data[data_offset]);
|
||||
/* Add size of uint32 IP address */
|
||||
data_offset += EOE_IP4_LENGTH;
|
||||
}
|
||||
/* Add size of uint32 IP address */
|
||||
data_offset += 4;
|
||||
|
||||
/* include default gateway in get ip request */
|
||||
if(nic_ports[port_ix].default_gateway_set)
|
||||
{
|
||||
flags |= EOE_PARAM_DEFAULT_GATEWAY_INCLUDE;
|
||||
EOE_ip_uint32_to_byte(&nic_ports[port_ix].default_gateway,
|
||||
&eoembx->data[data_offset]);
|
||||
/* Add size of uint32 IP address */
|
||||
data_offset += EOE_IP4_LENGTH;
|
||||
}
|
||||
/* Add size of uint32 IP address */
|
||||
data_offset += 4;
|
||||
/* include dns ip in get ip request */
|
||||
if(nic_ports[port_ix].dns_ip_set)
|
||||
{
|
||||
flags |= EOE_PARAM_DNS_IP_INCLUDE;
|
||||
EOE_ip_uint32_to_byte(&nic_ports[port_ix].dns_ip,
|
||||
&eoembx->data[data_offset]);
|
||||
/* Add size of uint32 IP address */
|
||||
data_offset += EOE_IP4_LENGTH;
|
||||
}
|
||||
/* Add size of uint32 IP address */
|
||||
data_offset += 4;
|
||||
|
||||
/* include dns name in get ip request */
|
||||
if(nic_ports[port_ix].dns_name_set)
|
||||
{
|
||||
/* TwinCAT include EOE_DNS_NAME_LENGTH chars even if name is shorter */
|
||||
flags |= EOE_PARAM_DNS_NAME_INCLUDE;
|
||||
memcpy(&eoembx->data[data_offset],
|
||||
nic_ports[port_ix].dns_name,
|
||||
EOE_DNS_NAME_LENGTH);
|
||||
/* Add size of dns name length */
|
||||
data_offset += EOE_DNS_NAME_LENGTH;
|
||||
}
|
||||
/* Add size of dns name length */
|
||||
data_offset += EOE_DNS_NAME_LENGTH;
|
||||
|
||||
eoembx->data[0] = flags;
|
||||
eoembx->mbxheader.length = htoes (ESC_EOEHSIZE + data_offset);
|
||||
|
@ -612,11 +619,10 @@ static void EOE_get_ip (void)
|
|||
static void EOE_set_ip (void)
|
||||
{
|
||||
_EOE *eoembx;
|
||||
uint16_t eoedatasize;
|
||||
uint32_t eoedatasize, data_offset;
|
||||
uint16_t frameinfo1;
|
||||
uint8_t port;
|
||||
uint8_t flags;
|
||||
uint8_t data_offset;
|
||||
uint16_t result;
|
||||
int port_ix;
|
||||
|
||||
|
@ -631,10 +637,10 @@ static void EOE_set_ip (void)
|
|||
{
|
||||
DPRINT("Invalid port\n");
|
||||
/* Return error response on given port */
|
||||
EOE_no_data_response((EOE_HDR_FRAME_PORT_SET(port) |
|
||||
EOE_INIT_RESP |
|
||||
EOE_HDR_LAST_FRAGMENT),
|
||||
EOE_RESULT_UNSPECIFIED_ERROR);
|
||||
frameinfo1 = EOE_HDR_FRAME_PORT_SET(port);
|
||||
frameinfo1 |= EOE_INIT_RESP;
|
||||
frameinfo1 |= EOE_HDR_LAST_FRAGMENT;
|
||||
EOE_no_data_response(frameinfo1, EOE_RESULT_UNSPECIFIED_ERROR);
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -646,55 +652,55 @@ static void EOE_set_ip (void)
|
|||
&eoembx->data[data_offset],
|
||||
EOE_ETHADDR_LENGTH);
|
||||
nic_ports[port_ix].mac_set = 1;
|
||||
/* Add size of mac address */
|
||||
data_offset += EOE_ETHADDR_LENGTH;
|
||||
}
|
||||
/* Add size of mac address */
|
||||
data_offset += EOE_ETHADDR_LENGTH;
|
||||
/* ip included in set ip request? */
|
||||
if(flags & EOE_PARAM_IP_INCLUDE)
|
||||
{
|
||||
EOE_ip_byte_to_uint32(&eoembx->data[data_offset],
|
||||
&nic_ports[port_ix].ip);
|
||||
nic_ports[port_ix].ip_set = 1;
|
||||
/* Add size of uint32 IP address */
|
||||
data_offset += EOE_IP4_LENGTH;
|
||||
}
|
||||
/* Add size of uint32 IP address */
|
||||
data_offset += 4;
|
||||
/* subnet included in set ip request? */
|
||||
if(flags & EOE_PARAM_SUBNET_IP_INCLUDE)
|
||||
{
|
||||
EOE_ip_byte_to_uint32(&eoembx->data[data_offset],
|
||||
&nic_ports[port_ix].subnet);
|
||||
nic_ports[port_ix].subnet_set = 1;
|
||||
/* Add size of uint32 IP address */
|
||||
data_offset += EOE_IP4_LENGTH;
|
||||
}
|
||||
/* Add size of uint32 IP address */
|
||||
data_offset += 4;
|
||||
/* default gateway included in set ip request? */
|
||||
if(flags & EOE_PARAM_DEFAULT_GATEWAY_INCLUDE)
|
||||
{
|
||||
EOE_ip_byte_to_uint32(&eoembx->data[data_offset],
|
||||
&nic_ports[port_ix].default_gateway);
|
||||
nic_ports[port_ix].default_gateway_set = 1;
|
||||
/* Add size of uint32 IP address */
|
||||
data_offset += EOE_IP4_LENGTH;
|
||||
}
|
||||
/* Add size of uint32 IP address */
|
||||
data_offset += 4;
|
||||
/* dns ip included in set ip request? */
|
||||
if(flags & EOE_PARAM_DNS_IP_INCLUDE)
|
||||
{
|
||||
EOE_ip_byte_to_uint32(&eoembx->data[data_offset],
|
||||
&nic_ports[port_ix].dns_ip);
|
||||
nic_ports[port_ix].dns_ip_set = 1;
|
||||
/* Add size of uint32 IP address */
|
||||
data_offset += EOE_IP4_LENGTH;
|
||||
}
|
||||
/* Add size of uint32 IP address */
|
||||
data_offset += 4;
|
||||
/* dns name included in set ip request? */
|
||||
if(flags & EOE_PARAM_DNS_NAME_INCLUDE)
|
||||
{
|
||||
uint16_t dns_len = MIN((eoedatasize - data_offset), EOE_DNS_NAME_LENGTH);
|
||||
uint32_t dns_len = MIN((eoedatasize - data_offset), EOE_DNS_NAME_LENGTH);
|
||||
memcpy(nic_ports[port_ix].dns_name,
|
||||
&eoembx->data[data_offset],
|
||||
dns_len);
|
||||
nic_ports[port_ix].dns_name_set = 1;
|
||||
data_offset += dns_len; /* expected 1- EOE_DNS_NAME_LENGTH; */
|
||||
}
|
||||
data_offset += EOE_DNS_NAME_LENGTH;
|
||||
|
||||
if(data_offset > eoedatasize)
|
||||
{
|
||||
|
@ -706,17 +712,17 @@ static void EOE_set_ip (void)
|
|||
* you typically set the IP for the TCP/IP stack */
|
||||
if(eoe_cfg->store_ethernet_settings != NULL)
|
||||
{
|
||||
result = eoe_cfg->store_ethernet_settings();
|
||||
result = (uint16_t)eoe_cfg->store_ethernet_settings();
|
||||
}
|
||||
else
|
||||
{
|
||||
result = EOE_RESULT_NO_IP_SUPPORT;
|
||||
}
|
||||
}
|
||||
EOE_no_data_response((EOE_HDR_FRAME_PORT_SET(port) |
|
||||
EOE_INIT_RESP |
|
||||
EOE_HDR_LAST_FRAGMENT),
|
||||
result);
|
||||
frameinfo1 = EOE_HDR_FRAME_PORT_SET(port);
|
||||
frameinfo1 |= EOE_INIT_RESP;
|
||||
frameinfo1 |= EOE_HDR_LAST_FRAGMENT;
|
||||
EOE_no_data_response(frameinfo1, result);
|
||||
}
|
||||
|
||||
/** EoE receive fragment handler.
|
||||
|
@ -725,14 +731,14 @@ static void EOE_receive_fragment (void)
|
|||
{
|
||||
_EOE *eoembx;
|
||||
eoembx = (_EOE *) &MBX[0];
|
||||
uint16_t eoedatasize = etohs(eoembx->mbxheader.length) - ESC_EOEHSIZE;
|
||||
uint32_t eoedatasize = etohs(eoembx->mbxheader.length) - ESC_EOEHSIZE;
|
||||
uint16_t frameinfo1 = etohs(eoembx->eoeheader.frameinfo1);
|
||||
uint16_t frameinfo2 = etohs(eoembx->eoeheader.frameinfo2);
|
||||
|
||||
/* Capture error case */
|
||||
if(EOEvar.rxfragmentno != EOE_HDR_FRAG_NO_GET(frameinfo2))
|
||||
{
|
||||
DPRINT("Unexpected fragment number %d, expected: %d\n",
|
||||
DPRINT("Unexpected fragment number %"PRIu32", expected: %"PRIu32"\n",
|
||||
EOE_HDR_FRAG_NO_GET(frameinfo2), EOEvar.rxfragmentno);
|
||||
/* Clean up existing saved data */
|
||||
if(EOEvar.rxfragmentno != 0)
|
||||
|
@ -757,22 +763,28 @@ static void EOE_receive_fragment (void)
|
|||
EOEvar.rxframeoffset = 0;
|
||||
EOEvar.rxframeno = EOE_HDR_FRAME_NO_GET(frameinfo2);
|
||||
}
|
||||
else
|
||||
{
|
||||
DPRINT("Receive buffer is invalid\n");
|
||||
EOE_init_rx ();
|
||||
return;
|
||||
}
|
||||
}
|
||||
/* In frame fragment received */
|
||||
else
|
||||
{
|
||||
uint16_t offset = (EOE_HDR_FRAME_OFFSET_GET(frameinfo2) << 5);
|
||||
uint32_t offset = (EOE_HDR_FRAME_OFFSET_GET(frameinfo2) << 5);
|
||||
/* Validate received fragment */
|
||||
if(EOEvar.rxframeno != EOE_HDR_FRAME_NO_GET(frameinfo2))
|
||||
{
|
||||
DPRINT("Unexpected frame number %d, expected: %d\n",
|
||||
DPRINT("Unexpected frame number %"PRIu32", expected: %"PRIu32"\n",
|
||||
EOE_HDR_FRAME_NO_GET(frameinfo2), EOEvar.rxframeno);
|
||||
EOE_init_rx ();
|
||||
return;
|
||||
}
|
||||
else if(EOEvar.rxframeoffset != offset)
|
||||
{
|
||||
DPRINT("Unexpected frame offset %d, expected: %d\n",
|
||||
DPRINT("Unexpected frame offset %"PRIu32", expected: %"PRIu32"\n",
|
||||
offset, EOEvar.rxframeoffset);
|
||||
EOE_init_rx ();
|
||||
return;
|
||||
|
@ -800,7 +812,7 @@ static void EOE_receive_fragment (void)
|
|||
/* Remove time stamp, TODO support for time stamp? */
|
||||
if(EOE_HDR_TIME_APPEND_GET(frameinfo1))
|
||||
{
|
||||
EOEvar.rxframeoffset -= 4;
|
||||
EOEvar.rxframeoffset -= 4U;
|
||||
}
|
||||
EOEvar.rxebuf.len = EOEvar.rxframeoffset;
|
||||
eoe_cfg->handle_recv_buffer(EOE_HDR_FRAME_PORT_GET(frameinfo1),
|
||||
|
@ -818,7 +830,7 @@ static void EOE_send_fragment ()
|
|||
_EOE *eoembx;
|
||||
uint8_t mbxhandle;
|
||||
int len;
|
||||
int len_to_send;
|
||||
uint32_t len_to_send;
|
||||
uint16_t frameinfo1;
|
||||
uint16_t frameinfo2;
|
||||
static uint8_t frameno = 0;
|
||||
|
@ -830,7 +842,7 @@ static void EOE_send_fragment ()
|
|||
len = eoe_cfg->fetch_send_buffer(0, &EOEvar.txebuf);
|
||||
if(len > 0)
|
||||
{
|
||||
EOEvar.txframesize = len;
|
||||
EOEvar.txframesize = (uint32_t)len;
|
||||
}
|
||||
else
|
||||
{
|
||||
|
@ -842,7 +854,7 @@ static void EOE_send_fragment ()
|
|||
mbxhandle = ESC_claimbuffer ();
|
||||
if (mbxhandle)
|
||||
{
|
||||
len_to_send = EOEvar.txframesize - EOEvar.txframeoffset;
|
||||
len_to_send = (EOEvar.txframesize - EOEvar.txframeoffset);
|
||||
if((len_to_send + ESC_EOEHSIZE + ESC_MBXHSIZE) > ESC_MBXSIZE)
|
||||
{
|
||||
/* Adjust to len in whole 32 octet blocks to fit specification*/
|
||||
|
@ -860,23 +872,26 @@ static void EOE_send_fragment ()
|
|||
frameinfo1 = 0;
|
||||
}
|
||||
|
||||
uint16_t tempframe2;
|
||||
/* Set fragment number */
|
||||
frameinfo2 = EOE_HDR_FRAG_NO_SET(EOEvar.txfragmentno);
|
||||
|
||||
/* Set complete size for fragment 0 or offset for in frame fragments */
|
||||
if(EOEvar.txfragmentno > 0)
|
||||
{
|
||||
frameinfo2 |= (EOE_HDR_FRAME_OFFSET_SET((EOEvar.txframeoffset >> 5)));
|
||||
tempframe2 = EOE_HDR_FRAME_OFFSET_SET((EOEvar.txframeoffset >> 5));
|
||||
frameinfo2 |= tempframe2;
|
||||
}
|
||||
else
|
||||
{
|
||||
frameinfo2 |=
|
||||
(EOE_HDR_FRAME_OFFSET_SET(((EOEvar.txframesize + 31) >> 5)));
|
||||
tempframe2 = EOE_HDR_FRAME_OFFSET_SET(((EOEvar.txframesize + 31) >> 5));
|
||||
frameinfo2 |= tempframe2;
|
||||
frameno++;
|
||||
}
|
||||
|
||||
/* Set frame number */
|
||||
frameinfo2 = frameinfo2 | EOE_HDR_FRAME_NO_SET(frameno);
|
||||
tempframe2 = EOE_HDR_FRAME_NO_SET(frameno);
|
||||
frameinfo2 |= tempframe2;
|
||||
|
||||
eoembx = (_EOE *) &MBX[mbxhandle * ESC_MBXSIZE];
|
||||
eoembx->mbxheader.length = htoes (len_to_send + ESC_EOEHSIZE);
|
||||
|
@ -898,7 +913,7 @@ static void EOE_send_fragment ()
|
|||
else
|
||||
{
|
||||
EOEvar.txframeoffset += len_to_send;
|
||||
EOEvar.txfragmentno += 1;
|
||||
EOEvar.txfragmentno++;
|
||||
}
|
||||
if(eoe_cfg->fragment_sent_event != NULL)
|
||||
{
|
||||
|
|
127
soes/esc_foe.c
127
soes/esc_foe.c
|
@ -26,20 +26,16 @@
|
|||
|
||||
/** Variable holding current filename read at FOE Open.
|
||||
*/
|
||||
char foe_file_name[FOE_FN_MAX + 1];
|
||||
static char foe_file_name[FOE_FN_MAX + 1];
|
||||
|
||||
|
||||
/** Main FoE configuration pointer data array. Structure i allocated and filled
|
||||
* by the application defining what preferences it require.
|
||||
/** Main FoE configuration pointer data array. Structure is allocated and filled
|
||||
* by the application defining what preferences it requires.
|
||||
*/
|
||||
static foe_cfg_t * foe_cfg;
|
||||
/** Collection of files possible to receive by FoE. Structure i allocated and
|
||||
* filled by the application defining what preferences it require.
|
||||
*/
|
||||
static foe_writefile_cfg_t * foe_files;
|
||||
/** Pointer to current file configuration item used by FoE.
|
||||
*/
|
||||
static foe_writefile_cfg_t * foe_file;
|
||||
static foe_file_cfg_t * foe_file;
|
||||
/** Main FoE status data array. Structure gets filled with current status
|
||||
* variables during FoE usage.
|
||||
*/
|
||||
|
@ -54,7 +50,7 @@ static _FOEvar FOEvar;
|
|||
* @return 0= if we succeed, FOE_ERR_NOTFOUND something wrong with filename or
|
||||
* password
|
||||
*/
|
||||
int FOE_fopen (char *name, uint8_t num_chars, uint32_t pass, uint8_t op)
|
||||
static uint32_t FOE_fopen (char *name, uint8_t num_chars, uint32_t pass, uint8_t op)
|
||||
{
|
||||
uint32_t i;
|
||||
|
||||
|
@ -73,10 +69,21 @@ int FOE_fopen (char *name, uint8_t num_chars, uint32_t pass, uint8_t op)
|
|||
/* Figure out what file they're talking about. */
|
||||
for (i = 0; i < foe_cfg->n_files; i++)
|
||||
{
|
||||
if ((0 == strncmp (foe_file_name, foe_files[i].name, num_chars)) &&
|
||||
(pass == foe_files[i].filepass))
|
||||
if (0 == strncmp (foe_file_name, foe_cfg->files[i].name, num_chars))
|
||||
{
|
||||
foe_file = &foe_files[i];
|
||||
if (pass != foe_cfg->files[i].filepass)
|
||||
{
|
||||
return FOE_ERR_NORIGHTS;
|
||||
}
|
||||
|
||||
if (op == FOE_OP_WRQ &&
|
||||
(foe_cfg->files[i].write_only_in_boot) &&
|
||||
(ESCvar.ALstatus != ESCboot))
|
||||
{
|
||||
return FOE_ERR_NOTINBOOTSTRAP;
|
||||
}
|
||||
|
||||
foe_file = &foe_cfg->files[i];
|
||||
foe_file->address_offset = 0;
|
||||
foe_file->total_size = 0;
|
||||
switch (op)
|
||||
|
@ -84,13 +91,13 @@ int FOE_fopen (char *name, uint8_t num_chars, uint32_t pass, uint8_t op)
|
|||
case FOE_OP_RRQ:
|
||||
{
|
||||
FOEvar.fposition = 0;
|
||||
FOEvar.fend = foe_files[i].max_data;
|
||||
FOEvar.fend = foe_cfg->files[i].max_data;
|
||||
return 0;
|
||||
}
|
||||
case FOE_OP_WRQ:
|
||||
{
|
||||
FOEvar.fposition = 0;
|
||||
FOEvar.fend = foe_files[i].max_data;
|
||||
FOEvar.fend = foe_cfg->files[i].max_data;
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
@ -111,9 +118,9 @@ int FOE_fopen (char *name, uint8_t num_chars, uint32_t pass, uint8_t op)
|
|||
|
||||
* @return Number of copied bytes.
|
||||
*/
|
||||
uint16_t FOE_fread (uint8_t * data, uint16_t maxlength)
|
||||
static uint32_t FOE_fread (uint8_t * data, uint32_t maxlength)
|
||||
{
|
||||
uint16_t ncopied = 0;
|
||||
uint32_t ncopied = 0;
|
||||
|
||||
while (maxlength && (FOEvar.fend - FOEvar.fposition))
|
||||
{
|
||||
|
@ -137,9 +144,9 @@ uint16_t FOE_fread (uint8_t * data, uint16_t maxlength)
|
|||
|
||||
* @return Number of copied bytes.
|
||||
*/
|
||||
uint16_t FOE_fwrite (uint8_t *data, uint16_t length)
|
||||
static uint32_t FOE_fwrite (uint8_t *data, uint32_t length)
|
||||
{
|
||||
uint16_t ncopied = 0;
|
||||
uint32_t ncopied = 0;
|
||||
uint32_t failed = 0;
|
||||
|
||||
DPRINT("FOE_fwrite\n");
|
||||
|
@ -155,12 +162,19 @@ uint16_t FOE_fwrite (uint8_t *data, uint16_t length)
|
|||
foe_file->address_offset += foe_cfg->buffer_size;
|
||||
}
|
||||
FOEvar.fposition++;
|
||||
ncopied++;
|
||||
if(failed)
|
||||
{
|
||||
DPRINT("Failed FOE_fwrite ncopied=%"PRIu32"\n", ncopied);
|
||||
}
|
||||
else
|
||||
{
|
||||
ncopied++;
|
||||
}
|
||||
}
|
||||
|
||||
foe_file->total_size += ncopied;
|
||||
|
||||
DPRINT("FOE_fwrite END with : %d\n",ncopied);
|
||||
DPRINT("FOE_fwrite END with : %"PRIu32"\n",ncopied);
|
||||
return ncopied;
|
||||
}
|
||||
|
||||
|
@ -170,7 +184,7 @@ uint16_t FOE_fwrite (uint8_t *data, uint16_t length)
|
|||
*
|
||||
* @return Number of copied bytes on success, 0= if failed.
|
||||
*/
|
||||
uint32_t FOE_fclose (void)
|
||||
static uint32_t FOE_fclose (void)
|
||||
{
|
||||
uint32_t failed = 0;
|
||||
|
||||
|
@ -200,7 +214,7 @@ void FOE_init ()
|
|||
*
|
||||
* @param[in] code = abort code
|
||||
*/
|
||||
void FOE_abort (uint32_t code)
|
||||
static void FOE_abort (uint32_t code)
|
||||
{
|
||||
_FOE *foembx;
|
||||
uint8_t mbxhandle;
|
||||
|
@ -220,7 +234,7 @@ void FOE_abort (uint32_t code)
|
|||
}
|
||||
/* Nothing we can do if we can't get an outbound mailbox. */
|
||||
}
|
||||
DPRINT("FOE_abort: 0x%X\n", code);
|
||||
DPRINT("FOE_abort: 0x%"PRIX32"\n", code);
|
||||
FOE_init ();
|
||||
}
|
||||
|
||||
|
@ -235,10 +249,10 @@ void FOE_abort (uint32_t code)
|
|||
* @return Number of data bytes written or an error number. Error numbers
|
||||
* will be greater than FOE_DATA_SIZE.
|
||||
*/
|
||||
int FOE_send_data_packet ()
|
||||
static uint32_t FOE_send_data_packet ()
|
||||
{
|
||||
_FOE *foembx;
|
||||
uint16_t data_len;
|
||||
uint32_t data_len;
|
||||
uint8_t mbxhandle;
|
||||
|
||||
mbxhandle = ESC_claimbuffer ();
|
||||
|
@ -266,7 +280,7 @@ int FOE_send_data_packet ()
|
|||
|
||||
* @return 0= or error number.
|
||||
*/
|
||||
int FOE_send_ack ()
|
||||
static uint32_t FOE_send_ack ()
|
||||
{
|
||||
_FOE *foembx;
|
||||
uint8_t mbxhandle;
|
||||
|
@ -299,12 +313,12 @@ int FOE_send_ack ()
|
|||
* On error we will send FOE Abort.
|
||||
*
|
||||
*/
|
||||
void FOE_read ()
|
||||
static void FOE_read ()
|
||||
{
|
||||
_FOE *foembx;
|
||||
uint32_t data_len;
|
||||
uint32_t password;
|
||||
int res;
|
||||
uint32_t res;
|
||||
uint8_t data_len;
|
||||
|
||||
if (FOEvar.foestate != FOE_READY)
|
||||
{
|
||||
|
@ -315,7 +329,7 @@ void FOE_read ()
|
|||
FOE_init ();
|
||||
foembx = (_FOE *) &MBX[0];
|
||||
/* Get the length of the file name in octets. */
|
||||
data_len = etohs (foembx->mbxheader.length) - ESC_FOEHSIZE;
|
||||
data_len = (uint8_t)(etohs (foembx->mbxheader.length) - ESC_FOEHSIZE);
|
||||
password = etohl (foembx->foeheader.password);
|
||||
|
||||
res = FOE_fopen (foembx->filename, data_len, password, FOE_OP_RRQ);
|
||||
|
@ -326,7 +340,7 @@ void FOE_read ()
|
|||
* Attempt to send the packet
|
||||
*/
|
||||
res = FOE_send_data_packet ();
|
||||
if (res <= (int)ESC_FOE_DATA_SIZE)
|
||||
if (res <= ESC_FOE_DATA_SIZE)
|
||||
{
|
||||
FOEvar.foestate = FOE_WAIT_FOR_ACK;
|
||||
}
|
||||
|
@ -340,20 +354,13 @@ void FOE_read ()
|
|||
FOE_abort (res);
|
||||
}
|
||||
}
|
||||
#else
|
||||
void FOE_read()
|
||||
{
|
||||
FOE_abort(FOE_ERR_NOTDEFINED);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef FOE_READ_SUPPORTED
|
||||
/** FoE data ack handler. Will continue sending next frame until finished.
|
||||
* On error we will send FOE Abort.
|
||||
*/
|
||||
void FOE_ack ()
|
||||
static void FOE_ack ()
|
||||
{
|
||||
int res;
|
||||
uint32_t res;
|
||||
|
||||
/* Make sure we're able to take this. */
|
||||
if (FOEvar.foestate == FOE_WAIT_FOR_FINAL_ACK)
|
||||
|
@ -368,7 +375,7 @@ void FOE_ack ()
|
|||
return;
|
||||
}
|
||||
res = FOE_send_data_packet ();
|
||||
if (res < (int)ESC_FOE_DATA_SIZE)
|
||||
if (res < ESC_FOE_DATA_SIZE)
|
||||
{
|
||||
FOEvar.foestate = FOE_WAIT_FOR_FINAL_ACK;
|
||||
}
|
||||
|
@ -383,12 +390,12 @@ void FOE_ack ()
|
|||
* receive data. On error we will send FOE Abort.
|
||||
*
|
||||
*/
|
||||
void FOE_write ()
|
||||
static void FOE_write ()
|
||||
{
|
||||
_FOE *foembx;
|
||||
uint32_t data_len;
|
||||
uint32_t password;
|
||||
int res;
|
||||
uint32_t res;
|
||||
uint8_t data_len;
|
||||
|
||||
if (FOEvar.foestate != FOE_READY)
|
||||
{
|
||||
|
@ -398,12 +405,12 @@ void FOE_write ()
|
|||
|
||||
FOE_init ();
|
||||
foembx = (_FOE *) &MBX[0];
|
||||
data_len = etohs (foembx->mbxheader.length) - ESC_FOEHSIZE;
|
||||
data_len = (uint8_t)(etohs (foembx->mbxheader.length) - ESC_FOEHSIZE);
|
||||
password = etohl (foembx->foeheader.password);
|
||||
|
||||
/* Get an address we can write the file to, if possible. */
|
||||
res = FOE_fopen (foembx->filename, data_len, password, FOE_OP_WRQ);
|
||||
DPRINT("FOE_write\n");
|
||||
DPRINT("%s %sOK, file \"%s\"\n", __func__, (res == 0) ? "" : "N", foe_file_name);
|
||||
if (res == 0)
|
||||
{
|
||||
res = FOE_send_ack ();
|
||||
|
@ -421,16 +428,16 @@ void FOE_write ()
|
|||
FOE_abort (res);
|
||||
}
|
||||
}
|
||||
/** FoE data request handler. Validates and reads data until we're finsihed. Every
|
||||
* read frame follwed by an Ack frame. On error we will send FOE Abort.
|
||||
/** FoE data request handler. Validates and reads data until we're finished. Every
|
||||
* read frame followed by an Ack frame. On error we will send FOE Abort.
|
||||
*
|
||||
*/
|
||||
void FOE_data ()
|
||||
static void FOE_data ()
|
||||
{
|
||||
_FOE *foembx;
|
||||
uint32_t packet;
|
||||
uint16_t data_len, ncopied;
|
||||
int res;
|
||||
uint32_t data_len, ncopied;
|
||||
uint32_t res;
|
||||
|
||||
if(FOEvar.foestate != FOE_WAIT_FOR_DATA)
|
||||
{
|
||||
|
@ -444,7 +451,9 @@ void FOE_data ()
|
|||
|
||||
if (packet != FOEvar.foepacket)
|
||||
{
|
||||
DPRINT("FOE_data packet error,packet: %d foeheader.packet: %d\n",packet,FOEvar.foepacket);
|
||||
DPRINT("FOE_data packet error, packet: %"PRIu32", foeheader.packet: %"PRIu32"\n",
|
||||
packet,
|
||||
FOEvar.foepacket);
|
||||
FOE_abort (FOE_ERR_PACKETNO);
|
||||
}
|
||||
else if (data_len == 0)
|
||||
|
@ -472,7 +481,7 @@ void FOE_data ()
|
|||
DPRINT("FOE_data data_len == FOE_DATA_SIZE\n");
|
||||
if (ncopied != data_len)
|
||||
{
|
||||
DPRINT("FOE_data only %d of %d copied\n",ncopied, data_len);
|
||||
DPRINT("FOE_data only %"PRIu32" of %"PRIu32" copied\n",ncopied, data_len);
|
||||
FOE_abort (FOE_ERR_PROGERROR);
|
||||
}
|
||||
res = FOE_send_ack ();
|
||||
|
@ -499,11 +508,11 @@ void FOE_data ()
|
|||
}
|
||||
|
||||
#ifdef FOE_READ_SUPPORTED
|
||||
/** FoE read request buys handler. Send an Ack of last frame again. On error
|
||||
/** FoE read request busy handler. Send an Ack of last frame again. On error
|
||||
* we will send FOE Abort.
|
||||
*
|
||||
*/
|
||||
void FOE_busy ()
|
||||
static void FOE_busy ()
|
||||
{
|
||||
/* Only valid if we're servicing a read request. */
|
||||
if (FOEvar.foestate != FOE_WAIT_FOR_ACK)
|
||||
|
@ -523,7 +532,7 @@ void FOE_busy ()
|
|||
/** FoE error requesthandler. Send an FOE Abort.
|
||||
*
|
||||
*/
|
||||
void FOE_error ()
|
||||
static void FOE_error ()
|
||||
{
|
||||
/* Master panic! abort the transfer. */
|
||||
FOE_abort (0);
|
||||
|
@ -534,14 +543,10 @@ void FOE_error ()
|
|||
*
|
||||
* @param[in] cfg = Pointer to by the Application static declared
|
||||
* configuration variable holding application specific details.
|
||||
* @param[in] cfg_files = Pointer to by the Application static declared
|
||||
* configuration variable holding file specific details for files to be handled
|
||||
* by FoE
|
||||
*/
|
||||
void FOE_config (foe_cfg_t * cfg, foe_writefile_cfg_t * cfg_files)
|
||||
void FOE_config (foe_cfg_t * cfg)
|
||||
{
|
||||
foe_cfg = cfg;
|
||||
foe_files = cfg_files;
|
||||
}
|
||||
|
||||
/** Main FoE function checking the status on current mailbox buffers carrying
|
||||
|
|
|
@ -14,10 +14,10 @@
|
|||
#include <cc.h>
|
||||
|
||||
/** Maximum number of characters allowed in a file name. */
|
||||
#define FOE_FN_MAX 15
|
||||
#define FOE_FN_MAX 31
|
||||
|
||||
typedef struct foe_writefile_cfg foe_writefile_cfg_t;
|
||||
struct foe_writefile_cfg
|
||||
typedef struct foe_file_cfg foe_file_cfg_t;
|
||||
struct foe_file_cfg
|
||||
{
|
||||
/** Name of file to receive from master */
|
||||
const char * name;
|
||||
|
@ -31,8 +31,12 @@ struct foe_writefile_cfg
|
|||
uint32_t total_size;
|
||||
/** FoE password */
|
||||
uint32_t filepass;
|
||||
/** This file can be written only in BOOT state. Intended for FW files */
|
||||
uint8_t write_only_in_boot;
|
||||
/** for feature use */
|
||||
uint32_t padding:24;
|
||||
/** Pointer to application foe write function */
|
||||
uint32_t (*write_function) (foe_writefile_cfg_t * self, uint8_t * data, size_t length);
|
||||
uint32_t (*write_function) (foe_file_cfg_t * self, uint8_t * data, size_t length);
|
||||
};
|
||||
|
||||
typedef struct foe_cfg
|
||||
|
@ -44,7 +48,7 @@ typedef struct foe_cfg
|
|||
/** Number of files used in firmware update */
|
||||
uint32_t n_files;
|
||||
/** Pointer to files configured to be used by FoE */
|
||||
foe_writefile_cfg_t * files;
|
||||
foe_file_cfg_t * files;
|
||||
} foe_cfg_t;
|
||||
|
||||
typedef struct CC_PACKED
|
||||
|
@ -66,7 +70,7 @@ typedef struct CC_PACKED
|
|||
} _FOEvar;
|
||||
|
||||
/* Initializes FoE state. */
|
||||
void FOE_config (foe_cfg_t * cfg, foe_writefile_cfg_t * cfg_files);
|
||||
void FOE_config (foe_cfg_t * cfg);
|
||||
void FOE_init (void);
|
||||
void ESC_foeprocess (void);
|
||||
|
||||
|
|
|
@ -16,7 +16,7 @@
|
|||
#include <stdlib.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#define BIT(x) 1 << (x)
|
||||
#define BIT(x) (1U << (x))
|
||||
|
||||
#define ESC_CMD_SERIAL_WRITE 0x02
|
||||
#define ESC_CMD_SERIAL_READ 0x03
|
||||
|
@ -59,15 +59,15 @@ static int lan9252 = -1;
|
|||
static void lan9252_write_32 (uint16_t address, uint32_t val)
|
||||
{
|
||||
uint8_t data[7];
|
||||
int n;
|
||||
ssize_t n;
|
||||
|
||||
data[0] = ESC_CMD_SERIAL_WRITE;
|
||||
data[1] = ((address >> 8) & 0xFF);
|
||||
data[2] = (address & 0xFF);
|
||||
data[3] = (val & 0xFF);
|
||||
data[4] = ((val >> 8) & 0xFF);
|
||||
data[5] = ((val >> 16) & 0xFF);
|
||||
data[6] = ((val >> 24) & 0xFF);
|
||||
data[1] = (uint8_t)((address >> 8) & 0xFF);
|
||||
data[2] = (uint8_t)(address & 0xFF);
|
||||
data[3] = (uint8_t)(val & 0xFF);
|
||||
data[4] = (uint8_t)((val >> 8) & 0xFF);
|
||||
data[5] = (uint8_t)((val >> 16) & 0xFF);
|
||||
data[6] = (uint8_t)((val >> 24) & 0xFF);
|
||||
|
||||
/* Write data */
|
||||
n = write (lan9252, data, sizeof(data));
|
||||
|
@ -80,17 +80,17 @@ static uint32_t lan9252_read_32 (uint32_t address)
|
|||
uint8_t data[2];
|
||||
uint8_t result[4];
|
||||
uint16_t lseek_addr;
|
||||
int n;
|
||||
ssize_t n;
|
||||
|
||||
data[0] = ((address >>8) & 0xFF);
|
||||
data[1] = (address & 0xFF);
|
||||
|
||||
lseek_addr=((uint16_t)data[0] << 8) | data[1];
|
||||
lseek (lan9252, lseek_addr, SEEK_SET);
|
||||
lseek_addr=(uint16_t)((data[0] << 8) | data[1]);
|
||||
lseek (lan9252, lseek_addr, SEEK_SET);
|
||||
n = read (lan9252, result, sizeof(result));
|
||||
(void)n;
|
||||
|
||||
return ((result[3] << 24) |
|
||||
return (uint32_t)((result[3] << 24) |
|
||||
(result[2] << 16) |
|
||||
(result[1] << 8) |
|
||||
result[0]);
|
||||
|
@ -101,7 +101,9 @@ static void ESC_read_csr (uint16_t address, void *buf, uint16_t len)
|
|||
{
|
||||
uint32_t value;
|
||||
|
||||
value = (ESC_CSR_CMD_READ | ESC_CSR_CMD_SIZE(len) | address);
|
||||
value = ESC_CSR_CMD_READ;
|
||||
value |= (uint32_t)ESC_CSR_CMD_SIZE(len);
|
||||
value |= address;
|
||||
lan9252_write_32(ESC_CSR_CMD_REG, value);
|
||||
|
||||
do
|
||||
|
@ -120,7 +122,9 @@ static void ESC_write_csr (uint16_t address, void *buf, uint16_t len)
|
|||
|
||||
memcpy((uint8_t*)&value, buf,len);
|
||||
lan9252_write_32(ESC_CSR_DATA_REG, value);
|
||||
value = (ESC_CSR_CMD_WRITE | ESC_CSR_CMD_SIZE(len) | address);
|
||||
value = ESC_CSR_CMD_WRITE;
|
||||
value |= (uint32_t)ESC_CSR_CMD_SIZE(len);
|
||||
value |= address;
|
||||
lan9252_write_32(ESC_CSR_CMD_REG, value);
|
||||
|
||||
do
|
||||
|
@ -137,10 +141,10 @@ static void ESC_read_pram (uint16_t address, void *buf, uint16_t len)
|
|||
uint16_t byte_offset = 0;
|
||||
uint8_t fifo_cnt, first_byte_position, temp_len;
|
||||
uint8_t *buffer;
|
||||
int i, array_size, size;
|
||||
size_t i, array_size, size;
|
||||
float quotient,remainder;
|
||||
uint32_t temp;
|
||||
int n;
|
||||
ssize_t n;
|
||||
|
||||
value = ESC_PRAM_CMD_ABORT;
|
||||
lan9252_write_32(ESC_PRAM_RD_CMD_REG, value);
|
||||
|
@ -150,7 +154,7 @@ static void ESC_read_pram (uint16_t address, void *buf, uint16_t len)
|
|||
value = lan9252_read_32(ESC_PRAM_RD_CMD_REG);
|
||||
}while(value & ESC_PRAM_CMD_BUSY);
|
||||
|
||||
value = ESC_PRAM_SIZE(len) | ESC_PRAM_ADDR(address);
|
||||
value = (uint32_t)(ESC_PRAM_SIZE(len) | ESC_PRAM_ADDR(address));
|
||||
lan9252_write_32(ESC_PRAM_RD_ADDR_LEN_REG, value);
|
||||
|
||||
value = ESC_PRAM_CMD_BUSY;
|
||||
|
@ -162,7 +166,7 @@ static void ESC_read_pram (uint16_t address, void *buf, uint16_t len)
|
|||
}while((value & ESC_PRAM_CMD_AVAIL) == 0);
|
||||
|
||||
/* Fifo count */
|
||||
fifo_cnt = ESC_PRAM_CMD_CNT(value);
|
||||
fifo_cnt = (uint8_t)ESC_PRAM_CMD_CNT(value);
|
||||
|
||||
/* Read first value from FIFO */
|
||||
value = lan9252_read_32(ESC_PRAM_RD_FIFO_REG);
|
||||
|
@ -172,27 +176,27 @@ static void ESC_read_pram (uint16_t address, void *buf, uint16_t len)
|
|||
* according to LAN9252 datasheet and MicroChip SDK code
|
||||
*/
|
||||
first_byte_position = (address & 0x03);
|
||||
temp_len = ((4 - first_byte_position) > len) ? len : (4 - first_byte_position);
|
||||
temp_len = ((4 - first_byte_position) > len) ? (uint8_t)len : (uint8_t)(4 - first_byte_position);
|
||||
|
||||
memcpy(temp_buf ,((uint8_t *)&value + first_byte_position), temp_len);
|
||||
len -= temp_len;
|
||||
byte_offset += temp_len;
|
||||
len = (uint16_t)(len - temp_len);
|
||||
byte_offset = (uint16_t)(byte_offset + temp_len);
|
||||
|
||||
/* Continue reading until we have read len */
|
||||
if (len > 0){
|
||||
|
||||
quotient = len/4;
|
||||
remainder = len%4;
|
||||
quotient = (float)(len/4);
|
||||
remainder = (float)(len%4);
|
||||
|
||||
if (remainder == 0)
|
||||
array_size = quotient;
|
||||
array_size = (size_t)quotient;
|
||||
else
|
||||
array_size = quotient+1;
|
||||
array_size = (size_t)quotient+1;
|
||||
|
||||
size = 4*array_size;
|
||||
|
||||
buffer = (uint8_t *)malloc(size);
|
||||
buffer[0] = size;
|
||||
buffer[0] = (uint8_t)size;
|
||||
memset(buffer,0,size);
|
||||
|
||||
lseek (lan9252, ESC_PRAM_RD_FIFO_REG, SEEK_SET);
|
||||
|
@ -203,13 +207,13 @@ static void ESC_read_pram (uint16_t address, void *buf, uint16_t len)
|
|||
{
|
||||
|
||||
for (i=0; i<size; i=i+4) {
|
||||
temp_len = (len > 4) ? 4: len;
|
||||
temp_len = (len > 4) ? 4: (uint8_t)len;
|
||||
|
||||
temp = buffer[i] | (buffer[i+1] << 8) | (buffer[i+2] << 16) | (buffer[i+3] << 24);
|
||||
temp = (uint32_t)(buffer[i] | (buffer[i+1] << 8) | (buffer[i+2] << 16) | (buffer[i+3] << 24));
|
||||
memcpy(temp_buf + byte_offset ,&temp, temp_len);
|
||||
fifo_cnt--;
|
||||
len -= temp_len;
|
||||
byte_offset += temp_len;
|
||||
len = (uint16_t)(len - temp_len);
|
||||
byte_offset = (uint16_t)(byte_offset + temp_len);
|
||||
}
|
||||
}
|
||||
free(buffer);
|
||||
|
@ -224,9 +228,9 @@ static void ESC_write_pram (uint16_t address, void *buf, uint16_t len)
|
|||
uint16_t byte_offset = 0;
|
||||
uint8_t fifo_cnt, first_byte_position, temp_len;
|
||||
uint8_t *buffer;
|
||||
int i, array_size, size;
|
||||
size_t i, array_size, size;
|
||||
float quotient,remainder;
|
||||
int n;
|
||||
ssize_t n;
|
||||
|
||||
value = ESC_PRAM_CMD_ABORT;
|
||||
lan9252_write_32(ESC_PRAM_WR_CMD_REG, value);
|
||||
|
@ -236,7 +240,7 @@ static void ESC_write_pram (uint16_t address, void *buf, uint16_t len)
|
|||
value = lan9252_read_32(ESC_PRAM_WR_CMD_REG);
|
||||
}while(value & ESC_PRAM_CMD_BUSY);
|
||||
|
||||
value = ESC_PRAM_SIZE(len) | ESC_PRAM_ADDR(address);
|
||||
value = (uint32_t)(ESC_PRAM_SIZE(len) | ESC_PRAM_ADDR(address));
|
||||
lan9252_write_32(ESC_PRAM_WR_ADDR_LEN_REG, value);
|
||||
|
||||
value = ESC_PRAM_CMD_BUSY;
|
||||
|
@ -248,37 +252,37 @@ static void ESC_write_pram (uint16_t address, void *buf, uint16_t len)
|
|||
}while((value & ESC_PRAM_CMD_AVAIL) == 0);
|
||||
|
||||
/* Fifo count */
|
||||
fifo_cnt = ESC_PRAM_CMD_CNT(value);
|
||||
fifo_cnt = (uint8_t)ESC_PRAM_CMD_CNT(value);
|
||||
|
||||
/* Find out first byte position and adjust the copy from that
|
||||
* according to LAN9252 datasheet
|
||||
*/
|
||||
first_byte_position = (address & 0x03);
|
||||
temp_len = ((4 - first_byte_position) > len) ? len : (4 - first_byte_position);
|
||||
temp_len = ((4 - first_byte_position) > len) ? (uint8_t)len : (uint8_t)(4 - first_byte_position);
|
||||
|
||||
memcpy(((uint8_t *)&value + first_byte_position), temp_buf, temp_len);
|
||||
|
||||
/* Write first value from FIFO */
|
||||
lan9252_write_32(ESC_PRAM_WR_FIFO_REG, value);
|
||||
|
||||
len -= temp_len;
|
||||
byte_offset += temp_len;
|
||||
len = (uint16_t)(len - temp_len);
|
||||
byte_offset = (uint16_t)(byte_offset + temp_len);
|
||||
fifo_cnt--;
|
||||
|
||||
if (len > 0){
|
||||
|
||||
quotient = len/4;
|
||||
remainder = len%4;
|
||||
remainder = (float)(len%4);
|
||||
|
||||
if (remainder == 0)
|
||||
array_size = quotient;
|
||||
array_size = (size_t)quotient;
|
||||
else
|
||||
array_size = quotient+1;
|
||||
array_size = (size_t)quotient+1;
|
||||
|
||||
size = 3+4*array_size;
|
||||
|
||||
buffer = (uint8_t *)malloc(size);
|
||||
buffer[0] = size;
|
||||
buffer[0] = (uint8_t)size;
|
||||
memset(buffer,0,size);
|
||||
|
||||
buffer[0] = ESC_CMD_SERIAL_WRITE;
|
||||
|
@ -287,17 +291,17 @@ static void ESC_write_pram (uint16_t address, void *buf, uint16_t len)
|
|||
while(len > 0)
|
||||
{
|
||||
for (i=3; i<size; i=i+4) {
|
||||
temp_len = (len > 4) ? 4 : len;
|
||||
temp_len = (len > 4) ? 4 : (uint8_t)len;
|
||||
|
||||
memcpy((uint8_t *)&value, (temp_buf + byte_offset), temp_len);
|
||||
buffer[i] = (value & 0xFF);
|
||||
buffer[i+1] = ((value >> 8) & 0xFF);
|
||||
buffer[i+2] = ((value >> 16) & 0xFF);
|
||||
buffer[i+3] = ((value >> 24) & 0xFF);
|
||||
buffer[i] = (uint8_t)(value & 0xFF);
|
||||
buffer[i+1] = (uint8_t)((value >> 8) & 0xFF);
|
||||
buffer[i+2] = (uint8_t)((value >> 16) & 0xFF);
|
||||
buffer[i+3] = (uint8_t)((value >> 24) & 0xFF);
|
||||
|
||||
fifo_cnt--;
|
||||
len -= temp_len;
|
||||
byte_offset += temp_len;
|
||||
len = (uint16_t)(len - temp_len);
|
||||
byte_offset= (uint16_t)(byte_offset + temp_len);
|
||||
}
|
||||
}
|
||||
n = write (lan9252, buffer, size);
|
||||
|
@ -351,9 +355,9 @@ void ESC_read (uint16_t address, void *buf, uint16_t len)
|
|||
ESC_read_csr(address, temp_buf, size);
|
||||
|
||||
/* next address */
|
||||
len -= size;
|
||||
temp_buf += size;
|
||||
address += size;
|
||||
len = (uint16_t)(len - size);
|
||||
temp_buf = (uint8_t *)(temp_buf + size);
|
||||
address = (uint16_t)(address + size);
|
||||
}
|
||||
}
|
||||
/* To mimic the ET1100 always providing AlEvent on every read or write */
|
||||
|
@ -406,9 +410,9 @@ void ESC_write (uint16_t address, void *buf, uint16_t len)
|
|||
ESC_write_csr(address, temp_buf, size);
|
||||
|
||||
/* next address */
|
||||
len -= size;
|
||||
temp_buf += size;
|
||||
address += size;
|
||||
len = (uint16_t)(len - size);
|
||||
temp_buf = (uint8_t *)(temp_buf + size);
|
||||
address = (uint16_t)(address + size);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -0,0 +1,602 @@
|
|||
/*
|
||||
* Licensed under the GNU General Public License version 2 with exceptions. See
|
||||
* LICENSE file in the project root for full license information
|
||||
*/
|
||||
|
||||
/** \file
|
||||
* \brief
|
||||
* ESC hardware layer functions for LAN9252 through BCM2835 SPI on Raspberry PI.
|
||||
*
|
||||
* Function to read and write commands to the ESC. Used to read/write ESC
|
||||
* registers and memory.
|
||||
*/
|
||||
#include "esc.h"
|
||||
#include "esc_hw.h"
|
||||
#include <string.h>
|
||||
#include <fcntl.h>
|
||||
#include <stdlib.h>
|
||||
#include <unistd.h>
|
||||
#include <bcm2835.h>
|
||||
|
||||
#define BIT(x) (1U << (x))
|
||||
|
||||
#define ESC_CMD_SERIAL_WRITE 0x02
|
||||
#define ESC_CMD_SERIAL_READ 0x03
|
||||
|
||||
#define ESC_CMD_RESET_CTL 0x01F8 // reset register
|
||||
#define ESC_CMD_HW_CFG 0x0074 // hardware configuration register
|
||||
#define ESC_CMD_BYTE_TEST 0x0064 // byte order test register
|
||||
#define ESC_CMD_ID_REV 0x0050 // chip ID and revision
|
||||
#define ESC_CMD_IRQ_CFG 0x0054 // interrupt configuration
|
||||
#define ESC_CMD_INT_EN 0x005C // interrupt enable
|
||||
|
||||
#define ESC_RESET_DIGITAL 0x00000001
|
||||
#define ESC_RESET_ETHERCAT 0x00000040
|
||||
#define ESC_RESET_CTRL_RST (ESC_RESET_DIGITAL & ESC_RESET_ETHERCAT)
|
||||
#define ESC_HW_CFG_READY 0x08000000
|
||||
#define ESC_BYTE_TEST_OK 0x87654321
|
||||
|
||||
#define ESC_PRAM_RD_FIFO_REG 0x0000
|
||||
#define ESC_PRAM_WR_FIFO_REG 0x0020
|
||||
#define ESC_PRAM_RD_ADDR_LEN_REG 0x0308
|
||||
#define ESC_PRAM_RD_CMD_REG 0x030C
|
||||
#define ESC_PRAM_WR_ADDR_LEN_REG 0x0310
|
||||
#define ESC_PRAM_WR_CMD_REG 0x0314
|
||||
|
||||
#define ESC_PRAM_CMD_BUSY 0x80000000
|
||||
#define ESC_PRAM_CMD_ABORT 0x40000000
|
||||
#define ESC_PRAM_CMD_AVAIL 0x00000001
|
||||
#define ESC_PRAM_CMD_CNT(x) (((x) >> 8) & 0x1F)
|
||||
#define ESC_PRAM_SIZE(x) ((x) << 16)
|
||||
#define ESC_PRAM_ADDR(x) ((x) << 0)
|
||||
|
||||
#define ESC_CSR_DATA_REG 0x0300
|
||||
#define ESC_CSR_CMD_REG 0x0304
|
||||
|
||||
#define ESC_CSR_CMD_BUSY 0x80000000
|
||||
#define ESC_CSR_CMD_READ (0x80000000 | 0x40000000)
|
||||
#define ESC_CSR_CMD_WRITE 0x80000000
|
||||
#define ESC_CSR_CMD_SIZE(x) ((x) << 16)
|
||||
|
||||
/* bcm2835 spi single write */
|
||||
static void bcm2835_spi_write_32 (uint16_t address, uint32_t val)
|
||||
{
|
||||
char data[7];
|
||||
|
||||
data[0] = ESC_CMD_SERIAL_WRITE;
|
||||
data[1] = ((address >> 8) & 0xFF);
|
||||
data[2] = (address & 0xFF);
|
||||
data[3] = (val & 0xFF);
|
||||
data[4] = ((val >> 8) & 0xFF);
|
||||
data[5] = ((val >> 16) & 0xFF);
|
||||
data[6] = ((val >> 24) & 0xFF);
|
||||
|
||||
/* Write data */
|
||||
bcm2835_spi_transfern(data, 7);
|
||||
}
|
||||
|
||||
/* bcm2835 spi single read */
|
||||
static uint32_t bcm2835_spi_read_32 (uint16_t address)
|
||||
{
|
||||
char data[7];
|
||||
|
||||
data[0] = ESC_CMD_SERIAL_READ;
|
||||
data[1] = ((address >> 8) & 0xFF);
|
||||
data[2] = (address & 0xFF);
|
||||
|
||||
/* Read data */
|
||||
bcm2835_spi_transfern(data, 7);
|
||||
|
||||
return ((data[6] << 24) |
|
||||
(data[5] << 16) |
|
||||
(data[4] << 8) |
|
||||
data[3]);
|
||||
}
|
||||
|
||||
/* ESC read CSR function */
|
||||
static void ESC_read_csr (uint16_t address, void *buf, uint16_t len)
|
||||
{
|
||||
uint32_t value;
|
||||
|
||||
value = (ESC_CSR_CMD_READ | ESC_CSR_CMD_SIZE(len) | address);
|
||||
bcm2835_spi_write_32(ESC_CSR_CMD_REG, value);
|
||||
|
||||
do
|
||||
{
|
||||
value = bcm2835_spi_read_32(ESC_CSR_CMD_REG);
|
||||
} while(value & ESC_CSR_CMD_BUSY);
|
||||
|
||||
value = bcm2835_spi_read_32(ESC_CSR_DATA_REG);
|
||||
memcpy(buf, (uint8_t *)&value, len);
|
||||
}
|
||||
|
||||
/* ESC write CSR function */
|
||||
static void ESC_write_csr (uint16_t address, void *buf, uint16_t len)
|
||||
{
|
||||
uint32_t value;
|
||||
|
||||
memcpy((uint8_t*)&value, buf,len);
|
||||
bcm2835_spi_write_32(ESC_CSR_DATA_REG, value);
|
||||
value = (ESC_CSR_CMD_WRITE | ESC_CSR_CMD_SIZE(len) | address);
|
||||
bcm2835_spi_write_32(ESC_CSR_CMD_REG, value);
|
||||
|
||||
do
|
||||
{
|
||||
value = bcm2835_spi_read_32(ESC_CSR_CMD_REG);
|
||||
} while(value & ESC_CSR_CMD_BUSY);
|
||||
}
|
||||
|
||||
/* ESC read process data ram function */
|
||||
static void ESC_read_pram (uint16_t address, void *buf, uint16_t len)
|
||||
{
|
||||
uint32_t value;
|
||||
uint8_t * temp_buf = buf;
|
||||
uint16_t quotient, remainder, byte_offset = 0;
|
||||
uint8_t fifo_cnt, fifo_size, fifo_range, first_byte_position, temp_len;
|
||||
uint8_t *buffer = NULL;
|
||||
int i, size;
|
||||
|
||||
bcm2835_spi_write_32(ESC_PRAM_RD_CMD_REG, ESC_PRAM_CMD_ABORT);
|
||||
do
|
||||
{
|
||||
value = bcm2835_spi_read_32(ESC_PRAM_RD_CMD_REG);
|
||||
}while(value & ESC_PRAM_CMD_BUSY);
|
||||
|
||||
bcm2835_spi_write_32(ESC_PRAM_RD_ADDR_LEN_REG, (ESC_PRAM_SIZE(len) | ESC_PRAM_ADDR(address)));
|
||||
|
||||
bcm2835_spi_write_32(ESC_PRAM_RD_CMD_REG, ESC_PRAM_CMD_BUSY);
|
||||
|
||||
/* Find out first byte position and adjust the copy from that
|
||||
* according to LAN9252 datasheet and MicroChip SDK code
|
||||
*/
|
||||
first_byte_position = (address & 0x03);
|
||||
|
||||
/* Transfer data */
|
||||
while (len > 0)
|
||||
{
|
||||
/* Wait for read availabiliy */
|
||||
if (byte_offset > 0)
|
||||
{
|
||||
quotient = len/4;
|
||||
remainder = len - quotient*4;
|
||||
}
|
||||
else
|
||||
{
|
||||
quotient = (len + first_byte_position)/4;
|
||||
remainder = (len + first_byte_position) - quotient*4;
|
||||
}
|
||||
if (remainder != 0)
|
||||
{
|
||||
quotient++;
|
||||
}
|
||||
fifo_range = MIN(quotient,16);
|
||||
do
|
||||
{
|
||||
value = bcm2835_spi_read_32(ESC_PRAM_RD_CMD_REG);
|
||||
}while(!(value & ESC_PRAM_CMD_AVAIL) || (ESC_PRAM_CMD_CNT(value) < fifo_range));
|
||||
|
||||
/* Fifo size */
|
||||
fifo_size = ESC_PRAM_CMD_CNT(value);
|
||||
|
||||
/* Transfer data size */
|
||||
size = 3+4*fifo_size;
|
||||
|
||||
/* Allocate buffer */
|
||||
buffer = (uint8_t *)realloc(buffer, size);
|
||||
|
||||
/* Reset fifo count */
|
||||
fifo_cnt = fifo_size;
|
||||
|
||||
/* Reset buffer */
|
||||
memset(buffer,0,size);
|
||||
buffer[0] = ESC_CMD_SERIAL_READ;
|
||||
buffer[1] = ((ESC_PRAM_RD_FIFO_REG >>8) & 0xFF);
|
||||
buffer[2] = ( ESC_PRAM_RD_FIFO_REG & 0xFF);
|
||||
|
||||
/* Transfer batch of data */
|
||||
bcm2835_spi_transfern((char *)buffer, size);
|
||||
|
||||
i = 3;
|
||||
while (fifo_cnt > 0 && len > 0)
|
||||
{
|
||||
value = buffer[i] | (buffer[i+1] << 8) | (buffer[i+2] << 16) | (buffer[i+3] << 24);
|
||||
|
||||
if (byte_offset > 0)
|
||||
{
|
||||
temp_len = (len > 4) ? 4: len;
|
||||
memcpy(temp_buf + byte_offset ,&value, temp_len);
|
||||
}
|
||||
else
|
||||
{
|
||||
temp_len = (len > (4 - first_byte_position)) ? (4 - first_byte_position) : len;
|
||||
memcpy(temp_buf ,((uint8_t *)&value + first_byte_position), temp_len);
|
||||
}
|
||||
|
||||
i += 4;
|
||||
fifo_cnt--;
|
||||
len -= temp_len;
|
||||
byte_offset += temp_len;
|
||||
}
|
||||
}
|
||||
free(buffer);
|
||||
}
|
||||
|
||||
/* ESC write process data ram function */
|
||||
static void ESC_write_pram (uint16_t address, void *buf, uint16_t len)
|
||||
{
|
||||
uint32_t value;
|
||||
uint8_t * temp_buf = buf;
|
||||
uint16_t quotient, remainder, byte_offset = 0;
|
||||
uint8_t fifo_cnt, fifo_size, fifo_range, first_byte_position, temp_len;
|
||||
uint8_t *buffer = NULL;
|
||||
int i, size;
|
||||
|
||||
bcm2835_spi_write_32(ESC_PRAM_WR_CMD_REG, ESC_PRAM_CMD_ABORT);
|
||||
do
|
||||
{
|
||||
value = bcm2835_spi_read_32(ESC_PRAM_WR_CMD_REG);
|
||||
}while(value & ESC_PRAM_CMD_BUSY);
|
||||
|
||||
bcm2835_spi_write_32(ESC_PRAM_WR_ADDR_LEN_REG, (ESC_PRAM_SIZE(len) | ESC_PRAM_ADDR(address)));
|
||||
|
||||
bcm2835_spi_write_32(ESC_PRAM_WR_CMD_REG, ESC_PRAM_CMD_BUSY);
|
||||
|
||||
/* Find out first byte position and adjust the copy from that
|
||||
* according to LAN9252 datasheet and MicroChip SDK code
|
||||
*/
|
||||
first_byte_position = (address & 0x03);
|
||||
|
||||
/* Transfer data */
|
||||
while (len > 0)
|
||||
{
|
||||
/* Wait for write availabiliy */
|
||||
if (byte_offset > 0)
|
||||
{
|
||||
quotient = len/4;
|
||||
remainder = len - quotient*4;
|
||||
}
|
||||
else
|
||||
{
|
||||
quotient = (len + first_byte_position)/4;
|
||||
remainder = (len + first_byte_position) - quotient*4;
|
||||
}
|
||||
if (remainder != 0)
|
||||
{
|
||||
quotient++;
|
||||
}
|
||||
fifo_range = MIN(quotient,16);
|
||||
do
|
||||
{
|
||||
value = bcm2835_spi_read_32(ESC_PRAM_WR_CMD_REG);
|
||||
}while(!(value & ESC_PRAM_CMD_AVAIL) || (ESC_PRAM_CMD_CNT(value) < fifo_range));
|
||||
|
||||
/* Fifo size */
|
||||
fifo_size = ESC_PRAM_CMD_CNT(value);
|
||||
|
||||
/* Transfer data size */
|
||||
size = 3+4*fifo_size;
|
||||
|
||||
/* Allocate buffer */
|
||||
buffer = (uint8_t *)realloc(buffer, size);
|
||||
|
||||
/* Reset fifo count */
|
||||
fifo_cnt = fifo_size;
|
||||
|
||||
/* Reset buffer */
|
||||
memset(buffer,0,size);
|
||||
buffer[0] = ESC_CMD_SERIAL_WRITE;
|
||||
buffer[1] = ((ESC_PRAM_WR_FIFO_REG >> 8) & 0xFF);
|
||||
buffer[2] = (ESC_PRAM_WR_FIFO_REG & 0xFF);
|
||||
|
||||
i = 3;
|
||||
while (fifo_cnt > 0 && len > 0)
|
||||
{
|
||||
value = 0;
|
||||
if (byte_offset > 0)
|
||||
{
|
||||
temp_len = (len > 4) ? 4: len;
|
||||
memcpy(&value, (temp_buf + byte_offset), temp_len);
|
||||
}
|
||||
else
|
||||
{
|
||||
temp_len = (len > (4 - first_byte_position)) ? (4 - first_byte_position) : len;
|
||||
memcpy(((uint8_t *)&value + first_byte_position), temp_buf, temp_len);
|
||||
}
|
||||
|
||||
buffer[i] = (value & 0xFF);
|
||||
buffer[i+1] = ((value >> 8) & 0xFF);
|
||||
buffer[i+2] = ((value >> 16) & 0xFF);
|
||||
buffer[i+3] = ((value >> 24) & 0xFF);
|
||||
|
||||
i += 4;
|
||||
fifo_cnt--;
|
||||
len -= temp_len;
|
||||
byte_offset += temp_len;
|
||||
}
|
||||
|
||||
/* Transfer batch of data */
|
||||
bcm2835_spi_transfern((char *)buffer, size);
|
||||
}
|
||||
free(buffer);
|
||||
}
|
||||
|
||||
/** ESC read function used by the Slave stack.
|
||||
*
|
||||
* @param[in] address = address of ESC register to read
|
||||
* @param[out] buf = pointer to buffer to read in
|
||||
* @param[in] len = number of bytes to read
|
||||
*/
|
||||
void ESC_read (uint16_t address, void *buf, uint16_t len)
|
||||
{
|
||||
/* Select Read function depending on address, process data ram or not */
|
||||
if (address >= 0x1000)
|
||||
{
|
||||
ESC_read_pram(address, buf, len);
|
||||
}
|
||||
else
|
||||
{
|
||||
uint16_t size;
|
||||
uint8_t *temp_buf = (uint8_t *)buf;
|
||||
|
||||
while(len > 0)
|
||||
{
|
||||
/* We write maximum 4 bytes at the time */
|
||||
size = (len > 4) ? 4 : len;
|
||||
/* Make size aligned to address according to LAN9252 datasheet
|
||||
* Table 12-14 EtherCAT CSR Address VS size and MicroChip SDK code
|
||||
*/
|
||||
/* If we got an odd address size is 1 , 01b 11b is captured */
|
||||
if(address & BIT(0))
|
||||
{
|
||||
size = 1;
|
||||
}
|
||||
/* If address 1xb and size != 1 and 3 , allow size 2 else size 1 */
|
||||
else if (address & BIT(1))
|
||||
{
|
||||
size = (size & BIT(0)) ? 1 : 2;
|
||||
}
|
||||
/* size 3 not valid */
|
||||
else if (size == 3)
|
||||
{
|
||||
size = 1;
|
||||
}
|
||||
/* else size is kept AS IS */
|
||||
ESC_read_csr(address, temp_buf, size);
|
||||
|
||||
/* next address */
|
||||
len -= size;
|
||||
temp_buf += size;
|
||||
address += size;
|
||||
}
|
||||
}
|
||||
/* To mimic the ET1100 always providing AlEvent on every read or write */
|
||||
ESC_read_csr(ESCREG_ALEVENT,(void *)&ESCvar.ALevent,sizeof(ESCvar.ALevent));
|
||||
ESCvar.ALevent = etohs (ESCvar.ALevent);
|
||||
|
||||
}
|
||||
|
||||
/** ESC write function used by the Slave stack.
|
||||
*
|
||||
* @param[in] address = address of ESC register to write
|
||||
* @param[out] buf = pointer to buffer to write from
|
||||
* @param[in] len = number of bytes to write
|
||||
*/
|
||||
void ESC_write (uint16_t address, void *buf, uint16_t len)
|
||||
{
|
||||
/* Select Write function depending on address, process data ram or not */
|
||||
if (address >= 0x1000)
|
||||
{
|
||||
ESC_write_pram(address, buf, len);
|
||||
}
|
||||
else
|
||||
{
|
||||
uint16_t size;
|
||||
uint8_t *temp_buf = (uint8_t *)buf;
|
||||
|
||||
while(len > 0)
|
||||
{
|
||||
/* We write maximum 4 bytes at the time */
|
||||
size = (len > 4) ? 4 : len;
|
||||
/* Make size aligned to address according to LAN9252 datasheet
|
||||
* Table 12-14 EtherCAT CSR Address VS size and MicroChip SDK code
|
||||
*/
|
||||
/* If we got an odd address size is 1 , 01b 11b is captured */
|
||||
if(address & BIT(0))
|
||||
{
|
||||
size = 1;
|
||||
}
|
||||
/* If address 1xb and size != 1 and 3 , allow size 2 else size 1 */
|
||||
else if (address & BIT(1))
|
||||
{
|
||||
size = (size & BIT(0)) ? 1 : 2;
|
||||
}
|
||||
/* size 3 not valid */
|
||||
else if (size == 3)
|
||||
{
|
||||
size = 1;
|
||||
}
|
||||
/* else size is kept AS IS */
|
||||
ESC_write_csr(address, temp_buf, size);
|
||||
|
||||
/* next address */
|
||||
len -= size;
|
||||
temp_buf += size;
|
||||
address += size;
|
||||
}
|
||||
}
|
||||
|
||||
/* To mimic the ET1x00 always providing AlEvent on every read or write */
|
||||
ESC_read_csr(ESCREG_ALEVENT,(void *)&ESCvar.ALevent,sizeof(ESCvar.ALevent));
|
||||
ESCvar.ALevent = etohs (ESCvar.ALevent);
|
||||
}
|
||||
|
||||
/* Un-used due to evb-lan9252-digio not havning any possability to
|
||||
* reset except over SPI.
|
||||
*/
|
||||
void ESC_reset (void)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
void ESC_init (const esc_cfg_t * config)
|
||||
{
|
||||
bool rpi4 = false, cs1 = false;
|
||||
uint32_t value;
|
||||
uint32_t counter = 0;
|
||||
uint32_t timeout = 1000; // wait 100msec
|
||||
const char * user_arg = (char *)config->user_arg;
|
||||
size_t arg_len = strlen(user_arg)+1;
|
||||
char * arg_str = (char *)calloc(arg_len, sizeof(char));
|
||||
strncpy(arg_str,user_arg,arg_len);
|
||||
char * delim = " ,.-";
|
||||
char * token = strtok(arg_str,delim);
|
||||
|
||||
// parse user arguments
|
||||
while (token != NULL)
|
||||
{
|
||||
if (strncmp(token,"cs1",3) == 0)
|
||||
{
|
||||
cs1 = true; // select CS1 pin
|
||||
}
|
||||
else if (strncmp(token,"rpi4",4) == 0)
|
||||
{
|
||||
rpi4 = true; // select clock divider for raspberry pi 4 or newer
|
||||
}
|
||||
token = strtok(NULL,delim);
|
||||
}
|
||||
free(arg_str);
|
||||
|
||||
// start initialization
|
||||
if (bcm2835_init())
|
||||
{
|
||||
if (bcm2835_spi_begin())
|
||||
{
|
||||
// Set SPI bit order
|
||||
bcm2835_spi_setBitOrder(BCM2835_SPI_BIT_ORDER_MSBFIRST);
|
||||
// Set SPI data mode BCM2835_SPI_MODE0 = 0, CPOL = 0, CPHA = 0,
|
||||
// Clock idle low, data is clocked in on rising edge, output data (change) on falling edge
|
||||
bcm2835_spi_setDataMode(BCM2835_SPI_MODE0);
|
||||
if (rpi4)
|
||||
{
|
||||
// Raspberry 4 due to a higher CPU speed this value is to change to: BCM2835_SPI_CLOCK_DIVIDER_32
|
||||
bcm2835_spi_setClockDivider(BCM2835_SPI_CLOCK_DIVIDER_32);
|
||||
DPRINT("bcm2835_spi_setClockDivider set to 32 \n");
|
||||
}
|
||||
else
|
||||
{
|
||||
// Set SPI clock speed BCM2835_SPI_CLOCK_DIVIDER_16 = 16, 16 = 64ns = 15.625MHz
|
||||
bcm2835_spi_setClockDivider(BCM2835_SPI_CLOCK_DIVIDER_16);
|
||||
DPRINT("bcm2835_spi_setClockDivider set to 16 \n");
|
||||
}
|
||||
if (cs1)
|
||||
{
|
||||
// Enable management of CS1 pin
|
||||
bcm2835_spi_chipSelect(BCM2835_SPI_CS1);
|
||||
// Enable CS1 and set polarity
|
||||
bcm2835_spi_setChipSelectPolarity(BCM2835_SPI_CS1, LOW);
|
||||
DPRINT("bcm2835_spi_chipSelect set to CS1 \n");
|
||||
}
|
||||
else
|
||||
{
|
||||
// Enable management of CS0 pin
|
||||
bcm2835_spi_chipSelect(BCM2835_SPI_CS0);
|
||||
// enable CS0 and set polarity
|
||||
bcm2835_spi_setChipSelectPolarity(BCM2835_SPI_CS0, LOW);
|
||||
DPRINT("bcm2835_spi_chipSelect set to CS0 \n");
|
||||
}
|
||||
|
||||
// Reset the ecat core here due to evb-lan9252-digio not having any GPIO for that purpose.
|
||||
bcm2835_spi_write_32(ESC_CMD_RESET_CTL,ESC_RESET_CTRL_RST);
|
||||
|
||||
// Wait until reset command has been executed
|
||||
do
|
||||
{
|
||||
usleep(100);
|
||||
counter++;
|
||||
value = bcm2835_spi_read_32(ESC_CMD_RESET_CTL);
|
||||
} while ((value & ESC_RESET_CTRL_RST) && (counter < timeout));
|
||||
|
||||
// Perform byte test
|
||||
do
|
||||
{
|
||||
usleep(100);
|
||||
counter++;
|
||||
value = bcm2835_spi_read_32(ESC_CMD_BYTE_TEST);
|
||||
} while ((value != ESC_BYTE_TEST_OK) && (counter < timeout));
|
||||
|
||||
// Check hardware is ready
|
||||
do
|
||||
{
|
||||
usleep(100);
|
||||
counter++;
|
||||
value = bcm2835_spi_read_32(ESC_CMD_HW_CFG);
|
||||
} while (!(value & ESC_HW_CFG_READY) && (counter < timeout));
|
||||
|
||||
// Check if timeout occured
|
||||
if (counter < timeout)
|
||||
{
|
||||
// Read the chip identification and revision
|
||||
value = bcm2835_spi_read_32(ESC_CMD_ID_REV);
|
||||
DPRINT("Detected chip %x Rev %u \n", ((value >> 16) & 0xFFFF), (value & 0xFFFF));
|
||||
|
||||
// Set AL event mask
|
||||
value = (ESCREG_ALEVENT_CONTROL |
|
||||
ESCREG_ALEVENT_SMCHANGE |
|
||||
ESCREG_ALEVENT_SM0 |
|
||||
ESCREG_ALEVENT_SM1 );
|
||||
ESC_ALeventmaskwrite(value);
|
||||
}
|
||||
else
|
||||
{
|
||||
DPRINT("Timeout occurred during reset \n");
|
||||
bcm2835_spi_end();
|
||||
bcm2835_close();
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
DPRINT("bcm2835_spi_begin failed. Are you running as root?\n");
|
||||
bcm2835_close();
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
DPRINT("bcm2835_init failed. Are you running as root?\n");
|
||||
}
|
||||
}
|
||||
|
||||
void ESC_interrupt_enable (uint32_t mask)
|
||||
{
|
||||
// Enable interrupt for SYNC0 or SM2 or SM3
|
||||
uint32_t user_int_mask = ESCREG_ALEVENT_DC_SYNC0 |
|
||||
ESCREG_ALEVENT_SM2 |
|
||||
ESCREG_ALEVENT_SM3;
|
||||
if (mask & user_int_mask)
|
||||
{
|
||||
ESC_ALeventmaskwrite(ESC_ALeventmaskread() | (mask & user_int_mask));
|
||||
}
|
||||
|
||||
// Set LAN9252 interrupt pin driver as push-pull active high
|
||||
bcm2835_spi_write_32(ESC_CMD_IRQ_CFG, 0x00000111);
|
||||
|
||||
// Enable LAN9252 interrupt
|
||||
bcm2835_spi_write_32(ESC_CMD_INT_EN, 0x00000001);
|
||||
}
|
||||
|
||||
void ESC_interrupt_disable (uint32_t mask)
|
||||
{
|
||||
// Enable interrupt for SYNC0 or SM2 or SM3
|
||||
uint32_t user_int_mask = ESCREG_ALEVENT_DC_SYNC0 |
|
||||
ESCREG_ALEVENT_SM2 |
|
||||
ESCREG_ALEVENT_SM3;
|
||||
|
||||
if (mask & user_int_mask)
|
||||
{
|
||||
// Disable interrupt from SYNC0
|
||||
ESC_ALeventmaskwrite(ESC_ALeventmaskread() & ~(mask & user_int_mask));
|
||||
}
|
||||
|
||||
|
||||
// Disable LAN9252 interrupt
|
||||
bcm2835_spi_write_32(ESC_CMD_INT_EN, 0x00000000);
|
||||
}
|
|
@ -0,0 +1,17 @@
|
|||
/*
|
||||
* Licensed under the GNU General Public License version 2 with exceptions. See
|
||||
* LICENSE file in the project root for full license information
|
||||
*/
|
||||
|
||||
/** \file
|
||||
* \brief
|
||||
* ESC hardware specifoc EEPROM emulation functions.
|
||||
*/
|
||||
|
||||
#ifndef __esc_hw__
|
||||
#define __esc_hw__
|
||||
|
||||
void ESC_interrupt_enable (uint32_t mask);
|
||||
void ESC_interrupt_disable (uint32_t mask);
|
||||
|
||||
#endif
|
|
@ -10,7 +10,7 @@
|
|||
* Function to read and write commands to the ESC. Used to read/write ESC
|
||||
* registers and memory.
|
||||
*/
|
||||
#include <kern.h>
|
||||
#include <kern/kern.h>
|
||||
#include <bsp.h>
|
||||
#include <xmc4.h>
|
||||
#include <eru.h>
|
||||
|
@ -83,6 +83,25 @@ void ESC_enable(void)
|
|||
scu_put_peripheral_in_reset (SCU_PERIPHERAL_ECAT0);
|
||||
scu_ungate_clock_to_peripheral (SCU_PERIPHERAL_ECAT0);
|
||||
scu_release_peripheral_from_reset (SCU_PERIPHERAL_ECAT0);
|
||||
|
||||
/* Used to perform PHY reset after ECAT module have been released as
|
||||
* described in 16.3.2.3 final section;
|
||||
* "In some case PHYs may be released from reset after releasing the ECAT
|
||||
* module, the pin for nPHY_RESET can be used as an I/O and shell be
|
||||
* switched later to the alternate output function".
|
||||
* Works well with relax boards.
|
||||
*/
|
||||
static const gpio_cfg_t gpio_cfg[] =
|
||||
{
|
||||
{ ECAT0_PHY_RESET,
|
||||
ECAT0_PHY_RESET_GPIO_AF,
|
||||
GPIO_STRONG_SOFT,
|
||||
GPIO_PAD_ENABLED,
|
||||
GPIO_POWS_DISABLED,
|
||||
GPIO_SW },
|
||||
};
|
||||
/* Re-configure the pin to correct alternate output function */
|
||||
gpio_configure (gpio_cfg, NELEMENTS (gpio_cfg));
|
||||
}
|
||||
|
||||
/* EtherCAT module clock gating and assert reset API (Disables ECAT)*/
|
||||
|
@ -220,12 +239,11 @@ static void sync0_isr (void * arg)
|
|||
*/
|
||||
static void ecat_isr (void * arg)
|
||||
{
|
||||
ESC_read (ESCREG_LOCALTIME, (void *) &ESCvar.Time, sizeof (ESCvar.Time));
|
||||
ESCvar.Time = etohl (ESCvar.Time);
|
||||
CC_ATOMIC_SET(ESCvar.ALevent, etohl(ecat0->AL_EVENT_REQ));
|
||||
CC_ATOMIC_SET(ESCvar.Time, etohl(ecat0->READMode_DC_SYS_TIME[0]));
|
||||
|
||||
/* Handle SM2 interrupt */
|
||||
if(ESCvar.ALevent & ESCREG_ALEVENT_SM2)
|
||||
/* Handle SM2 & SM3 interrupt */
|
||||
if(ESCvar.ALevent & (ESCREG_ALEVENT_SM2 | ESCREG_ALEVENT_SM3))
|
||||
{
|
||||
/* Is DC active or not */
|
||||
if(ESCvar.dcsync == 0)
|
||||
|
@ -281,6 +299,8 @@ static void isr_run(void * arg)
|
|||
/* Do while to handle write of eeprom, the write to flash is delayed */
|
||||
do
|
||||
{
|
||||
/* Update time, used by emulated eeprom handler to measure idle time */
|
||||
CC_ATOMIC_SET(ESCvar.Time, etohl(ecat0->READMode_DC_SYS_TIME[0]));
|
||||
ecat_slv_worker(ESCREG_ALEVENT_CONTROL | ESCREG_ALEVENT_SMCHANGE
|
||||
| ESCREG_ALEVENT_SM0 | ESCREG_ALEVENT_SM1 | ESCREG_ALEVENT_EEP);
|
||||
|
||||
|
|
|
@ -11,7 +11,7 @@
|
|||
#ifndef __esc_hw__
|
||||
#define __esc_hw__
|
||||
|
||||
#include <kern.h>
|
||||
#include <kern/kern.h>
|
||||
/* ================================================================================ */
|
||||
/* ================ ECAT [ECAT0] ================ */
|
||||
/* ================================================================================ */
|
||||
|
|
|
@ -301,7 +301,7 @@ void PDI_Isr(void)
|
|||
alevent = bsp_read_word_isr(escHwPruIcssHandle,ESCREG_ALEVENT);
|
||||
CC_ATOMIC_SET(ESCvar.ALevent, etohs(alevent));
|
||||
|
||||
if(ESCvar.ALevent & ESCREG_ALEVENT_SM2)
|
||||
if(ESCvar.ALevent & (ESCREG_ALEVENT_SM2 & ESCREG_ALEVENT_SM3))
|
||||
{
|
||||
DIG_process(DIG_PROCESS_OUTPUTS_FLAG |
|
||||
DIG_PROCESS_APP_HOOK_FLAG |
|
||||
|
|
|
@ -14,6 +14,7 @@ extern "C"
|
|||
#include <assert.h>
|
||||
#include <stdint.h>
|
||||
#include <stddef.h>
|
||||
#include <inttypes.h>
|
||||
#include <sys/param.h>
|
||||
#ifdef __linux__
|
||||
#include <endian.h>
|
||||
|
@ -32,8 +33,10 @@ extern "C"
|
|||
#define CC_PACKED_BEGIN
|
||||
#define CC_PACKED_END
|
||||
#define CC_PACKED __attribute__((packed))
|
||||
#define CC_ALIGNED(n) __attribute__((aligned (n)))
|
||||
|
||||
#ifdef __rtk__
|
||||
#include <kern/assert.h>
|
||||
#define CC_ASSERT(exp) ASSERT (exp)
|
||||
#else
|
||||
#define CC_ASSERT(exp) assert (exp)
|
||||
|
@ -53,11 +56,11 @@ extern "C"
|
|||
#define CC_ATOMIC_OR(var,val) __atomic_or_fetch(&var,val,__ATOMIC_SEQ_CST)
|
||||
|
||||
#if BYTE_ORDER == BIG_ENDIAN
|
||||
#define htoes(x) CC_SWAP16 (x)
|
||||
#define htoel(x) CC_SWAP32 (x)
|
||||
#define htoes(x) CC_SWAP16 ((uint16_t)(x))
|
||||
#define htoel(x) CC_SWAP32 ((uint32_t)(x))
|
||||
#else
|
||||
#define htoes(x) (x)
|
||||
#define htoel(x) (x)
|
||||
#define htoes(x) ((uint16_t)(x))
|
||||
#define htoel(x) ((uint32_t)(x))
|
||||
#endif
|
||||
|
||||
#define etohs(x) htoes (x)
|
||||
|
@ -71,7 +74,7 @@ extern "C"
|
|||
|
||||
#ifdef ESC_DEBUG
|
||||
#ifdef __rtk__
|
||||
#include <rprint.h>
|
||||
#include <kern/rprint.h>
|
||||
#define DPRINT(...) rprintp ("soes: "__VA_ARGS__)
|
||||
#else
|
||||
#include <stdio.h>
|
||||
|
|
|
@ -31,6 +31,10 @@
|
|||
#define MBXBUFFERS 3
|
||||
#endif
|
||||
|
||||
#ifndef PREALLOC_FACTOR
|
||||
#define PREALLOC_FACTOR 3
|
||||
#endif
|
||||
|
||||
#ifndef MBX0_sma
|
||||
#define MBX0_sma 0x1000
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue