Merge branch 'master' into master

pull/165/head
Ivo Houtzager 2024-01-13 15:42:04 -08:00 committed by GitHub
commit 696141398c
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
29 changed files with 2663 additions and 352 deletions

View File

@ -4,7 +4,7 @@ env:
BUILD_TYPE: Release
jobs:
build:
runs-on: ubuntu-16.04
runs-on: ubuntu-20.04
steps:
- uses: actions/checkout@v2
with:

View File

@ -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)

View File

@ -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)

View File

@ -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 $?

View File

@ -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__ */

View File

@ -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.

View File

@ -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

View File

@ -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}
};

View File

@ -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__ */

View File

@ -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");

View File

@ -1,5 +1,15 @@
set(SOES_DEMO applications/raspberry_lan9252demo)
if(RPI_VARIANT)
set (SOES_DEMO applications/raspberry_lan9252demo_default)
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
@ -7,9 +17,5 @@ include_directories(
${SOES_SOURCE_DIR}/${SOES_DEMO}
)
set(HAL_SOURCES
${SOES_SOURCE_DIR}/soes/hal/raspberrypi-lan9252/esc_hw.c
)
# Common compile flags
add_compile_options(-DESC_DEBUG -Wall -Wextra -Wno-unused-parameter -Werror)
add_compile_options(-DESC_DEBUG -Wall -Wextra -Wconversion -Wno-unused-parameter -Werror)

View File

@ -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.
@ -202,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);
@ -226,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);
}
}

View File

@ -64,7 +64,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)
{
@ -138,7 +138,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
@ -150,7 +150,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).
@ -161,7 +161,7 @@ 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);
}
/** Write 0 to Bit0 in SM PDI control register 0x807(+ offset to SyncManager n) to Activate the Sync Manager n.
@ -172,7 +172,7 @@ 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);
}
/** Write 1 to Bit0 in SM PDI control register 0x807(+ offset to SyncManager n) to De-activte the Sync Manager n.
@ -416,9 +416,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);
@ -441,9 +441,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);
@ -489,7 +489,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;
@ -603,7 +603,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;
@ -690,13 +690,41 @@ uint8_t ESC_checkSM23 (uint8_t state)
_ESCsm2 *SM;
ESC_read (ESCREG_SM2, (void *) &ESCvar.SM[SM2_IDX], sizeof (ESCvar.SM[SM2_IDX]));
SM = (_ESCsm2 *) & ESCvar.SM[SM2_IDX];
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;
@ -705,8 +733,34 @@ uint8_t ESC_checkSM23 (uint8_t state)
}
ESC_read (ESCREG_SM3, (void *) &ESCvar.SM[SM3_IDX], sizeof (ESCvar.SM[SM3_IDX]));
SM = (_ESCsm2 *) & ESCvar.SM[SM3_IDX];
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 */
@ -729,7 +783,12 @@ uint8_t ESC_startinput (uint8_t state)
if (state != (ESCpreop | ESCerror))
{
ESC_SMenable (SM3_IDX);
/* If inputs > 0 , enable SM3 */
if (ESCvar.ESC_SM3_sml > 0)
{
ESC_SMenable (SM3_IDX);
}
/* Go to state input regardless of any inputs present */
CC_ATOMIC_SET(ESCvar.App.state, APPSTATE_INPUT);
}
else
@ -769,15 +828,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);
}
}
}
@ -800,7 +866,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);
}
}
@ -814,8 +881,12 @@ void ESC_stopinput (void)
*/
uint8_t ESC_startoutput (uint8_t state)
{
ESC_SMenable (SM2_IDX);
/* If outputs > 0 , enable SM2 */
if (ESCvar.ESC_SM2_sml > 0)
{
ESC_SMenable (SM2_IDX);
}
/* Go to state output regardless of any outputs present */
CC_ATOMIC_OR(ESCvar.App.state, APPSTATE_OUTPUT);
return state;
@ -933,6 +1004,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.
*
@ -980,7 +1120,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)
@ -1136,6 +1276,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 (SM3_IDX);
}
break;
}
case OP_TO_SAFEOP:
@ -1149,6 +1294,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 (SM3_IDX);
}
an = ESCsafeop;
}
if (as == ESCsafeop)
@ -1181,9 +1331,16 @@ void ESC_state (void)
#if USE_EMU
ESCvar.ALstatus = an;
#else
if (ESC_check_id_request (ESCvar.ALcontrol, &an))
{
an |= ESC_load_device_id ();
}
ESC_ALstatus (an);
#endif
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.
@ -1223,4 +1380,5 @@ void ESC_config (esc_cfg_t * cfg)
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;
}

View File

@ -17,9 +17,12 @@
#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_ALCONFIG 0x0141
#define ESCREG_ALEVENTMASK 0x0204
@ -69,6 +72,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
@ -217,9 +221,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
@ -362,6 +366,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
@ -486,8 +491,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;
@ -509,8 +515,8 @@ 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;
@ -526,7 +532,7 @@ 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];
@ -599,7 +605,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;
@ -611,7 +617,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;
@ -721,11 +727,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);

View File

@ -18,7 +18,8 @@
#include "esc.h"
#include "esc_coe.h"
#define BITS2BYTES(b) ((b + 7) >> 3)
#define BITS2BYTES(b) ((b + 7U) >> 3)
#define BITSPOS2BYTESOFFSET(b) (b >> 3)
/* Fetch value from object dictionary */
#define OBJ_VALUE_FETCH(v, o) \
@ -47,7 +48,7 @@ typedef enum { UPLOAD, DOWNLOAD } load_t;
* @param[in] subindex = value on sub-index of object we want to locate
* @return local array index if we succeed, -1 if we didn't find the index.
*/
int16_t SDO_findsubindex (int16_t nidx, uint8_t subindex)
int16_t SDO_findsubindex (int32_t nidx, uint8_t subindex)
{
const _objd *objd;
int16_t n = 0;
@ -117,9 +118,10 @@ int32_t SDO_findobject (uint16_t index)
uint16_t sizeOfPDO (uint16_t index, int * nmappings, _SMmap * mappings,
int max_mappings)
{
uint16_t offset = 0, hobj;
uint32_t offset = 0;
uint16_t hobj;
uint8_t si, sic, c;
int16_t nidx;
int32_t nidx;
const _objd *objd;
const _objd *objd1c1x;
int mapIx = 0;
@ -158,7 +160,7 @@ uint16_t sizeOfPDO (uint16_t index, int * nmappings, _SMmap * mappings,
if (max_mappings > 0)
{
uint16_t index = value >> 16;
uint16_t index = (uint16_t)(value >> 16);
uint8_t subindex = (value >> 8) & 0xFF;
const _objd * mapping;
@ -169,7 +171,10 @@ uint16_t sizeOfPDO (uint16_t index, int * nmappings, _SMmap * mappings,
return 0;
}
DPRINT ("%04x:%02x @ %d\n", index, subindex, offset);
DPRINT ("%04"PRIx32":%02"PRIx32" @ %"PRIu32"\n",
index,
subindex,
offset);
if (index == 0 && subindex == 0)
{
@ -202,6 +207,15 @@ uint16_t sizeOfPDO (uint16_t index, int * nmappings, _SMmap * mappings,
}
mappings[mapIx].obj = mapping;
/* Save object list reference */
if(mapping != NULL)
{
mappings[mapIx].objectlistitem = &SDOobjects[nidx];
}
else
{
mappings[mapIx].objectlistitem = NULL;
}
mappings[mapIx++].offset = offset;
}
@ -220,7 +234,7 @@ uint16_t sizeOfPDO (uint16_t index, int * nmappings, _SMmap * mappings,
*nmappings = 0;
}
return BITS2BYTES (offset);
return BITS2BYTES (offset) & 0xFFFF;
}
/** Copy to mailbox.
@ -229,7 +243,7 @@ uint16_t sizeOfPDO (uint16_t index, int * nmappings, _SMmap * mappings,
* @param[in] dest = pointer to destination
* @param[in] size = Size to copy
*/
static void copy2mbx (void *source, void *dest, uint16_t size)
static void copy2mbx (void *source, void *dest, size_t size)
{
memcpy (dest, source, size);
}
@ -287,7 +301,8 @@ static void SDO_upload (void)
_COEsdo *coesdo, *coeres;
uint16_t index;
uint8_t subindex;
int16_t nidx, nsub;
int32_t nidx;
int16_t nsub;
uint8_t MBXout;
uint32_t size;
uint8_t dss;
@ -335,14 +350,14 @@ static void SDO_upload (void)
}
coeres->index = htoes (index);
coeres->subindex = subindex;
coeres->command = COE_COMMAND_UPLOADRESPONSE +
coeres->command = COE_COMMAND_UPLOADRESPONSE |
COE_SIZE_INDICATOR;
/* convert bits to bytes */
size = BITS2BYTES(size);
if (size <= 4)
{
/* expedited response i.e. length<=4 bytes */
coeres->command += COE_EXPEDITED_INDICATOR + dss;
coeres->command |= (COE_EXPEDITED_INDICATOR | dss);
void *dataptr = ((objd + nsub)->data) ?
(objd + nsub)->data : (void *)&((objd + nsub)->value);
abort = ESC_upload_pre_objecthandler (index, subindex,
@ -430,7 +445,7 @@ static void SDO_upload (void)
}
static uint32_t complete_access_get_variables(_COEsdo *coesdo, uint16_t *index,
uint8_t *subindex, int16_t *nidx,
uint8_t *subindex, int32_t *nidx,
int16_t *nsub)
{
*index = etohs (coesdo->index);
@ -458,11 +473,11 @@ static uint32_t complete_access_get_variables(_COEsdo *coesdo, uint16_t *index,
}
static uint32_t complete_access_subindex_loop(const _objd *objd,
int16_t nidx,
int32_t nidx,
int16_t nsub,
uint8_t *mbxdata,
load_t load_type,
uint16_t max_bytes)
uint32_t max_bytes)
{
/* Objects with dynamic entries cannot be accessed with Complete Access */
if ((objd->datatype == DTYPE_VISIBLE_STRING) ||
@ -474,6 +489,12 @@ static uint32_t complete_access_subindex_loop(const _objd *objd,
uint32_t size = 0;
/* Clear padded mbxdata byte [1] on upload */
if ((load_type == UPLOAD) && (mbxdata != NULL))
{
mbxdata[1] = 0;
}
while (nsub <= SDOobjects[nidx].maxsub)
{
uint16_t bitlen = (objd + nsub)->bitlength;
@ -488,7 +509,7 @@ static uint32_t complete_access_subindex_loop(const _objd *objd,
if (bitoffset != 0)
{
/* move on to next byte boundary */
size += (8 - bitoffset);
size += (8U - bitoffset);
}
if (mbxdata != NULL)
{
@ -517,19 +538,21 @@ static uint32_t complete_access_subindex_loop(const _objd *objd,
else if ((load_type == UPLOAD) && (mbxdata != NULL))
{
/* copy a bit data type into correct position */
uint8_t bitmask = (1 << bitlen) - 1;
uint32_t bitmask = (1U << bitlen) - 1U;
uint32_t tempmask;
if (READ_ACCESS(access, state))
{
if (bitoffset == 0)
{
mbxdata[BITS2BYTES(size)] = 0;
mbxdata[BITSPOS2BYTESOFFSET(size)] = 0;
}
mbxdata[BITS2BYTES(size)] |=
(*(uint8_t *)ul_source & bitmask) << bitoffset;
tempmask = (*(uint8_t *)ul_source & bitmask) << bitoffset;
mbxdata[BITSPOS2BYTESOFFSET(size)] |= (uint8_t)tempmask;
}
else
{
mbxdata[BITS2BYTES(size)] &= ~(bitmask << bitoffset);
tempmask = ~(bitmask << bitoffset);
mbxdata[BITSPOS2BYTESOFFSET(size)] &= (uint8_t)tempmask;
}
}
@ -570,7 +593,8 @@ static void SDO_upload_complete_access (void)
_COEsdo *coesdo = (_COEsdo *) &MBX[0];
uint16_t index;
uint8_t subindex;
int16_t nidx, nsub;
int32_t nidx;
int16_t nsub;
uint32_t abortcode = complete_access_get_variables
(coesdo, &index, &subindex, &nidx, &nsub);
if (abortcode != 0)
@ -595,7 +619,7 @@ static void SDO_upload_complete_access (void)
uint32_t size = complete_access_subindex_loop(objd, nidx, nsub, NULL, UPLOAD, 0);
/* expedited bits used calculation */
uint8_t dss = (size > 24) ? 0 : (4 * (3 - ((size - 1) >> 3)));
uint8_t dss = (size > 24) ? 0 : (uint8_t)(4U * (3U - ((size - 1U) >> 3)));
/* convert bits to bytes */
size = BITS2BYTES(size);
@ -693,7 +717,7 @@ static void SDO_uploadsegment (void)
coeres = (_COEsdo *) &MBX[MBXout * ESC_MBXSIZE];
offset = ESCvar.fragsleft;
size = ESCvar.frags - ESCvar.fragsleft;
uint8_t command = COE_COMMAND_UPLOADSEGMENT +
uint8_t command = COE_COMMAND_UPLOADSEGMENT |
(coesdo->command & COE_TOGGLEBIT); /* copy toggle bit */
init_coesdo(coeres, COE_SDORESPONSE, command,
coesdo->index, coesdo->subindex);
@ -712,14 +736,14 @@ static void SDO_uploadsegment (void)
ESCvar.segmented = 0;
ESCvar.frags = 0;
ESCvar.fragsleft = 0;
coeres->command += COE_COMMAND_LASTSEGMENTBIT;
coeres->command |= COE_COMMAND_LASTSEGMENTBIT;
if (size >= 7)
{
coeres->mbxheader.length = htoes (COE_SEGMENTHEADERSIZE + size);
}
else
{
coeres->command += (7 - size) << 1;
coeres->command |= (uint8_t)((7U - size) << 1);
coeres->mbxheader.length = htoes (COE_DEFAULTLENGTH);
}
}
@ -752,9 +776,10 @@ static void SDO_download (void)
_COEsdo *coesdo, *coeres;
uint16_t index;
uint8_t subindex;
int16_t nidx, nsub;
int32_t nidx;
int16_t nsub;
uint8_t MBXout;
uint16_t size, actsize;
uint32_t size, actsize;
const _objd *objd;
uint32_t *mbxdata;
uint32_t abort;
@ -776,7 +801,7 @@ static void SDO_download (void)
/* expedited? */
if (coesdo->command & COE_EXPEDITED_INDICATOR)
{
size = 4 - ((coesdo->command & 0x0c) >> 2);
size = 4U - ((coesdo->command & 0x0CU) >> 2);
mbxdata = &(coesdo->size);
}
else
@ -865,13 +890,14 @@ static void SDO_download (void)
}
else
{
if (access == ATYPE_RWpre)
if (access == ATYPE_RO)
{
SDO_abort (0, index, subindex, ABORT_NOTINTHISSTATE);
SDO_abort (0, index, subindex, ABORT_READONLY);
}
else
{
SDO_abort (0, index, subindex, ABORT_READONLY);
SDO_abort (0, index, subindex, ABORT_NOTINTHISSTATE);
}
}
}
@ -897,7 +923,8 @@ static void SDO_download_complete_access (void)
_COEsdo *coesdo = (_COEsdo *) &MBX[0];
uint16_t index;
uint8_t subindex;
int16_t nidx, nsub;
int32_t nidx;
int16_t nsub;
uint32_t abortcode = complete_access_get_variables
(coesdo, &index, &subindex, &nidx, &nsub);
if (abortcode != 0)
@ -912,7 +939,7 @@ static void SDO_download_complete_access (void)
if (coesdo->command & COE_EXPEDITED_INDICATOR)
{
/* expedited download */
bytes = 4 - ((coesdo->command & 0x0c) >> 2);
bytes = 4U - ((coesdo->command & 0x0CU) >> 2);
}
else
{
@ -1013,46 +1040,58 @@ static void SDO_downloadsegment (void)
if (MBXout)
{
_COEsdo *coeres = (_COEsdo *) &MBX[MBXout * ESC_MBXSIZE];
uint32_t size = coesdo->mbxheader.length - 3;
uint32_t size = coesdo->mbxheader.length - 3U;
if (size == 7)
{
size = 7 - ((coesdo->command >> 1) & 7);
}
uint8_t command = COE_COMMAND_DOWNLOADSEGRESP +
(coesdo->command & COE_TOGGLEBIT); /* copy toggle bit */
uint8_t command = COE_COMMAND_DOWNLOADSEGRESP;
uint8_t command2 = (coesdo->command & COE_TOGGLEBIT); /* copy toggle bit */
command |= command2;
init_coesdo(coeres, COE_SDORESPONSE, command, 0, 0);
uint32_t *mbxdata = (uint32_t *)&(coesdo->index); /* data pointer */
copy2mbx (mbxdata, (uint8_t *)ESCvar.data, size);
void *mbxdata = &(coesdo->index); /* data pointer */
copy2mbx (mbxdata, ESCvar.data, size);
if (coesdo->command & COE_COMMAND_LASTSEGMENTBIT)
{
/* last segment */
ESCvar.segmented = 0;
if(ESCvar.flags == COMPLETE_ACCESS_FLAG)
{
int16_t nidx;
int32_t nidx;
int16_t nsub;
if(ESCvar.frags > ESCvar.fragsleft + size)
{
set_state_idle (0, ESCvar.index, ESCvar.subindex, ABORT_TYPEMISMATCH);
return;
}
nidx = SDO_findobject(ESCvar.index);
if (nidx < 0)
nsub = SDO_findsubindex (nidx, ESCvar.subindex);
if ((nidx < 0) || (nsub < 0))
{
set_state_idle (0, ESCvar.index, ESCvar.subindex, ABORT_NOOBJECT);
return;
}
/* copy download data to subindexes */
const _objd *objd = SDOobjects[nidx].objdesc;
complete_access_subindex_loop(objd,
ESCvar.index,
ESCvar.subindex,
(uint8_t *)ESCvar.data,
nidx,
nsub,
(uint8_t *)ESCvar.mbxdata,
DOWNLOAD,
ESCvar.frags);
}
/* external object write handler */
uint32_t abort = ESC_download_post_objecthandler
(ESCvar.index, ESCvar.subindex, ESCvar.flags);
/* last segment */
ESCvar.segmented = 0;
ESCvar.frags = 0;
ESCvar.fragsleft = 0;
/* external object write handler */
uint32_t abort = ESC_download_post_objecthandler
(ESCvar.index, ESCvar.subindex, ESCvar.flags);
if (abort != 0)
{
set_state_idle (MBXout, ESCvar.index, ESCvar.subindex, abort);
@ -1063,6 +1102,8 @@ static void SDO_downloadsegment (void)
{
/* more segmented transfer needed: increase offset */
ESCvar.data += size;
/* number of bytes done */
ESCvar.fragsleft += size;
}
MBXcontrol[MBXout].state = MBXstate_outreq;
@ -1083,7 +1124,7 @@ static void SDO_infoerror (uint32_t abortcode)
if (MBXout)
{
coeres = (_COEobjdesc *) &MBX[MBXout * ESC_MBXSIZE];
coeres->mbxheader.length = htoes ((uint16_t) COE_HEADERSIZE);
coeres->mbxheader.length = htoes (COE_HEADERSIZE);
coeres->mbxheader.mbxtype = MBXCOE;
coeres->coeheader.numberservice =
htoes ((0 & 0x01f) | (COE_SDOINFORMATION << 12));
@ -1100,14 +1141,14 @@ static void SDO_infoerror (uint32_t abortcode)
}
}
#define ODLISTSIZE ((ESC_MBX1_sml - ESC_MBXHSIZE - sizeof(_COEh) - sizeof(_INFOh) - 2) & 0xfffe)
#define ODLISTSIZE ((uint32_t)(ESC_MBX1_sml - ESC_MBXHSIZE - sizeof(_COEh) - sizeof(_INFOh) - 2U) & 0xfffe)
/** Function for handling incoming requested SDO Get OD List, validating the
* request and sending an response. On error an SDO Info Error will be sent.
*/
static void SDO_getodlist (void)
{
uint16_t frags;
uint32_t frags;
uint8_t MBXout = 0;
uint16_t entries = 0;
uint16_t i, n;
@ -1119,7 +1160,7 @@ static void SDO_getodlist (void)
entries++;
}
ESCvar.entries = entries;
frags = ((entries << 1) + ODLISTSIZE - 1);
frags = ((uint32_t)(entries << 1) + ODLISTSIZE - 1U);
frags /= ODLISTSIZE;
coer = (_COEobjdesc *) &MBX[0];
/* check for unsupported opcodes */
@ -1141,10 +1182,10 @@ static void SDO_getodlist (void)
/* number of objects request */
if (etohs (coer->index) == 0x00)
{
coel->index = htoes ((uint16_t) 0x00);
coel->index = htoes (0x00);
coel->infoheader.incomplete = 0;
coel->infoheader.reserved = 0x00;
coel->infoheader.fragmentsleft = htoes ((uint16_t) 0);
coel->infoheader.fragmentsleft = htoes (0);
MBXcontrol[0].state = MBXstate_idle;
ESCvar.xoe = 0;
ESCvar.frags = frags;
@ -1181,7 +1222,7 @@ static void SDO_getodlist (void)
ESCvar.frags = frags;
ESCvar.fragsleft = frags - 1;
coel->infoheader.fragmentsleft = htoes (ESCvar.fragsleft);
coel->index = htoes ((uint16_t) 0x01);
coel->index = htoes (0x01);
p = &(coel->datatype);
for (i = 0; i < n; i++)
@ -1211,13 +1252,13 @@ static void SDO_getodlistcont (void)
coel = (_COEobjdesc *) &MBX[MBXout * ESC_MBXSIZE];
coel->mbxheader.mbxtype = MBXCOE;
coel->coeheader.numberservice =
htoes ((0 & 0x01f) | (COE_SDOINFORMATION << 12));
htoes (COE_SDOINFORMATION << 12);
coel->infoheader.opcode = COE_GETODLISTRESPONSE;
s = (ESCvar.frags - ESCvar.fragsleft) * (ODLISTSIZE >> 1);
s = (uint16_t)((ESCvar.frags - ESCvar.fragsleft) * (ODLISTSIZE >> 1));
if (ESCvar.fragsleft > 1)
{
coel->infoheader.incomplete = 1;
n = s + (ODLISTSIZE >> 1);
n = (uint16_t)(s + (ODLISTSIZE >> 1));
}
else
{
@ -1228,7 +1269,7 @@ static void SDO_getodlistcont (void)
}
coel->infoheader.reserved = 0x00;
ESCvar.fragsleft--;
coel->infoheader.fragmentsleft = htoes (ESCvar.fragsleft);
coel->infoheader.fragmentsleft = htoes ((uint16_t)ESCvar.fragsleft);
/* pointer 2 bytes back to exclude index */
p = &(coel->index);
for (i = s; i < n; i++)
@ -1265,7 +1306,7 @@ static void SDO_getod (void)
coel = (_COEobjdesc *) &MBX[MBXout * ESC_MBXSIZE];
coel->mbxheader.mbxtype = MBXCOE;
coel->coeheader.numberservice =
htoes ((0 & 0x01f) | (COE_SDOINFORMATION << 12));
htoes (COE_SDOINFORMATION << 12);
coel->infoheader.opcode = COE_GETODRESPONSE;
coel->infoheader.incomplete = 0;
coel->infoheader.reserved = 0x00;
@ -1283,14 +1324,14 @@ static void SDO_getod (void)
int32_t nsub = SDO_findsubindex (nidx, 0);
const _objd *objd = SDOobjects[nidx].objdesc;
coel->datatype = htoes ((objd + nsub)->datatype);
coel->maxsub = SDOobjects[nidx].objdesc->value;
coel->maxsub = (uint8_t)SDOobjects[nidx].objdesc->value;
}
else
{
coel->datatype = htoes (0);
coel->maxsub = SDOobjects[nidx].objdesc->value;
coel->maxsub = (uint8_t)SDOobjects[nidx].objdesc->value;
}
coel->objectcode = SDOobjects[nidx].objtype;
coel->objectcode = (uint8_t)SDOobjects[nidx].objtype;
s = (uint8_t *) SDOobjects[nidx].name;
d = (uint8_t *) &(coel->name);
while (*s && (n < (ESC_MBXDSIZE - 0x0c)))
@ -1301,7 +1342,7 @@ static void SDO_getod (void)
d++;
}
*d = *s;
coel->mbxheader.length = htoes ((uint16_t) 0x0c + n);
coel->mbxheader.length = htoes (0x0C + n);
MBXcontrol[MBXout].state = MBXstate_outreq;
MBXcontrol[0].state = MBXstate_idle;
ESCvar.xoe = 0;
@ -1321,7 +1362,8 @@ static void SDO_geted (void)
{
uint8_t MBXout;
uint16_t index;
int32_t nidx, nsub;
int32_t nidx;
int16_t nsub;
uint8_t subindex;
uint8_t *d;
const uint8_t *s;
@ -1348,7 +1390,7 @@ static void SDO_geted (void)
coel->infoheader.opcode = COE_ENTRYDESCRIPTIONRESPONSE;
coel->infoheader.incomplete = 0;
coel->infoheader.reserved = 0x00;
coel->infoheader.fragmentsleft = htoes ((uint16_t) 0);
coel->infoheader.fragmentsleft = htoes (0);
coel->index = htoes (index);
coel->subindex = subindex;
coel->valueinfo = COE_VALUEINFO_ACCESS +
@ -1366,7 +1408,7 @@ static void SDO_geted (void)
d++;
}
*d = *s;
coel->mbxheader.length = htoes ((uint16_t) 0x10 + n);
coel->mbxheader.length = htoes (0x10 + n);
MBXcontrol[MBXout].state = MBXstate_outreq;
MBXcontrol[0].state = MBXstate_idle;
ESCvar.xoe = 0;
@ -1392,7 +1434,7 @@ void ESC_coeprocess (void)
_MBXh *mbh;
_COEsdo *coesdo;
_COEobjdesc *coeobjdesc;
uint8_t service;
uint16_t service;
if (ESCvar.MBXrun == 0)
{
return;
@ -1519,10 +1561,10 @@ void ESC_coeprocess (void)
* @param[in] length = number of bits to get
* @return bitslice value
*/
static uint64_t COE_bitsliceGet (uint64_t * bitmap, int offset, int length)
static uint64_t COE_bitsliceGet (uint64_t * bitmap, unsigned int offset, unsigned int length)
{
const int word_offset = offset / 64;
const int bit_offset = offset % 64;
const unsigned int word_offset = offset / 64;
const unsigned int bit_offset = offset % 64;
const uint64_t mask = (length == 64) ? UINT64_MAX : (1ULL << length) - 1;
uint64_t w0;
uint64_t w1 = 0;
@ -1552,11 +1594,11 @@ static uint64_t COE_bitsliceGet (uint64_t * bitmap, int offset, int length)
* @param[in] length = number of bits to set
* @param[in] value = value to set
*/
static void COE_bitsliceSet (uint64_t * bitmap, int offset, int length,
static void COE_bitsliceSet (uint64_t * bitmap, unsigned int offset, unsigned int length,
uint64_t value)
{
const int word_offset = offset / 64;
const int bit_offset = offset % 64;
const unsigned int word_offset = offset / 64;
const unsigned int bit_offset = offset % 64;
const uint64_t mask = (length == 64) ? UINT64_MAX : (1ULL << length) - 1;
const uint64_t mask0 = mask << bit_offset;
uint64_t v0 = value << bit_offset;
@ -1717,7 +1759,10 @@ void COE_initDefaultValues (void)
if (objd[i].data != NULL)
{
COE_setValue (&objd[i], objd[i].value);
DPRINT ("%04x:%02x = %x\n", SDOobjects[n].index, objd[i].subindex, objd[i].value);
DPRINT ("%04"PRIx32":%02"PRIx32" = %"PRIx32"\n",
SDOobjects[n].index,
objd[i].subindex,
objd[i].value);
}
} while (objd[i++].subindex < maxsub);
}
@ -1749,14 +1794,14 @@ void COE_pdoPack (uint8_t * buffer, int nmappings, _SMmap * mappings)
for (ix = 0; ix < nmappings; ix++)
{
const _objd * obj = mappings[ix].obj;
uint16_t offset = mappings[ix].offset;
uint32_t offset = mappings[ix].offset;
if (obj != NULL)
{
if (obj->bitlength > 64)
{
memcpy (
&buffer[BITS2BYTES (offset)],
&buffer[BITSPOS2BYTESOFFSET (offset)],
obj->data,
BITS2BYTES (obj->bitlength)
);
@ -1796,7 +1841,7 @@ void COE_pdoUnpack (uint8_t * buffer, int nmappings, _SMmap * mappings)
for (ix = 0; ix < nmappings; ix++)
{
const _objd * obj = mappings[ix].obj;
uint16_t offset = mappings[ix].offset;
uint32_t offset = mappings[ix].offset;
if (obj != NULL)
{
@ -1804,7 +1849,7 @@ void COE_pdoUnpack (uint8_t * buffer, int nmappings, _SMmap * mappings)
{
memcpy (
obj->data,
&buffer[BITS2BYTES (offset)],
&buffer[BITSPOS2BYTESOFFSET (offset)],
BITS2BYTES (obj->bitlength)
);
}
@ -1831,7 +1876,7 @@ void COE_pdoUnpack (uint8_t * buffer, int nmappings, _SMmap * mappings)
*/
uint8_t COE_maxSub (uint16_t index)
{
int nidx;
int32_t nidx;
uint8_t maxsub;
nidx = SDO_findobject (index);

View File

@ -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
@ -96,11 +96,15 @@ 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_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)
#if USE_MBX
#define TX_PDO_OBJIDX 0x1c13
@ -113,7 +117,7 @@ typedef struct
#define COMPLETE_ACCESS_FLAG (1 << 15)
void ESC_coeprocess (void);
int16_t SDO_findsubindex (int16_t nidx, uint8_t subindex);
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 COE_initDefaultValues (void);

View File

@ -53,7 +53,7 @@ void EEP_process (void)
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);
@ -63,7 +63,7 @@ void EEP_process (void)
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;

View File

@ -18,7 +18,7 @@
#define EEP_CMD_IDLE 0x0
#define EEP_CMD_READ 0x1
#define EEP_CMD_WRITE 0x2
#define EEP_CMD_RELOAD 0x3
#define EEP_CMD_RELOAD 0x4
/* read/write size */
#define EEP_READ_SIZE 8

View File

@ -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 */
@ -109,7 +109,7 @@
/** Ethernet address length not including VLAN */
#define EOE_ETHADDR_LENGTH 6
/** IPv4 address length */
#define EOE_IP4_LENGTH sizeof(uint32_t)
#define EOE_IP4_LENGTH 4U /* sizeof(uint32_t) */
/** EOE ip4 address in network order */
struct eoe_ip4_addr {
@ -135,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 */
@ -217,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;
@ -506,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];
@ -518,10 +518,11 @@ 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;
}
@ -539,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 */
@ -618,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;
@ -637,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;
}
@ -694,7 +694,7 @@ static void EOE_set_ip (void)
/* 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);
@ -712,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.
@ -731,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)
@ -763,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;
@ -806,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),
@ -824,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;
@ -836,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
{
@ -848,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*/
@ -866,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);
@ -904,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)
{

View File

@ -50,7 +50,7 @@ static _FOEvar FOEvar;
* @return 0= if we succeed, FOE_ERR_NOTFOUND something wrong with filename or
* password
*/
static 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;
@ -118,9 +118,9 @@ static int FOE_fopen (char *name, uint8_t num_chars, uint32_t pass, uint8_t op)
* @return Number of copied bytes.
*/
static 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))
{
@ -144,9 +144,9 @@ static uint16_t FOE_fread (uint8_t * data, uint16_t maxlength)
* @return Number of copied bytes.
*/
static 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");
@ -162,12 +162,19 @@ static 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;
}
@ -227,7 +234,7 @@ static 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 ();
}
@ -242,10 +249,10 @@ static 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.
*/
static 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 ();
@ -273,7 +280,7 @@ static int FOE_send_data_packet ()
* @return 0= or error number.
*/
static int FOE_send_ack ()
static uint32_t FOE_send_ack ()
{
_FOE *foembx;
uint8_t mbxhandle;
@ -309,9 +316,9 @@ static int FOE_send_ack ()
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)
{
@ -322,7 +329,7 @@ static 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);
@ -333,7 +340,7 @@ static 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;
}
@ -353,7 +360,7 @@ static void FOE_read ()
*/
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 @@ static 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;
}
@ -386,9 +393,9 @@ static void FOE_ack ()
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,7 +405,7 @@ static 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. */
@ -429,8 +436,8 @@ 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 @@ static 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 @@ static 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 ();

View File

@ -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);
}
}

View File

@ -3,7 +3,7 @@
* LICENSE file in the project root for full license information
*/
/** \file
/** \file
* \brief
* ESC hardware layer functions for LAN9252 through BCM2835 SPI on Raspberry PI.
*
@ -18,7 +18,7 @@
#include <unistd.h>
#include <bcm2835.h>
#define BIT(x) 1 << (x)
#define BIT(x) (1U << (x))
#define ESC_CMD_SERIAL_WRITE 0x02
#define ESC_CMD_SERIAL_READ 0x03
@ -46,7 +46,7 @@
#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_CMD_CNT(x) (((x) >> 8) & 0x1F)
#define ESC_PRAM_SIZE(x) ((x) << 16)
#define ESC_PRAM_ADDR(x) ((x) << 0)
@ -56,23 +56,23 @@
#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)
#define ESC_CSR_CMD_SIZE(x) ((x) << 16)
/* bcm2835 spi singel write */
/* bcm2835 spi single write */
static void bcm2835_spi_write_32 (uint16_t address, uint32_t val)
{
char data[7];
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);
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);
/* Write data */
bcm2835_spi_transfern(data, 7);
}
/* bcm2835 spi single read */
@ -83,7 +83,7 @@ static uint32_t bcm2835_spi_read_32 (uint16_t address)
data[0] = ESC_CMD_SERIAL_READ;
data[1] = ((address >> 8) & 0xFF);
data[2] = (address & 0xFF);
/* Read data */
bcm2835_spi_transfern(data, 7);
@ -135,7 +135,7 @@ static void ESC_read_pram (uint16_t address, void *buf, uint16_t len)
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
{
@ -145,12 +145,12 @@ static void ESC_read_pram (uint16_t address, void *buf, uint16_t len)
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)
{
@ -174,33 +174,33 @@ static void ESC_read_pram (uint16_t address, void *buf, uint16_t len)
{
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;
@ -211,7 +211,7 @@ static void ESC_read_pram (uint16_t address, void *buf, uint16_t len)
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;
@ -230,7 +230,7 @@ static void ESC_write_pram (uint16_t address, void *buf, uint16_t len)
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
{
@ -240,12 +240,12 @@ static void ESC_write_pram (uint16_t address, void *buf, uint16_t len)
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)
{
@ -269,25 +269,25 @@ static void ESC_write_pram (uint16_t address, void *buf, uint16_t len)
{
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)
{
@ -302,18 +302,18 @@ static void ESC_write_pram (uint16_t address, void *buf, uint16_t len)
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);
}
@ -450,7 +450,7 @@ void ESC_init (const esc_cfg_t * config)
strncpy(arg_str,user_arg,arg_len);
char * delim = " ,.-";
char * token = strtok(arg_str,delim);
// parse user arguments
while (token != NULL)
{
@ -465,7 +465,7 @@ void ESC_init (const esc_cfg_t * config)
token = strtok(NULL,delim);
}
free(arg_str);
// start initialization
if (bcm2835_init())
{
@ -473,7 +473,9 @@ void ESC_init (const esc_cfg_t * config)
{
// Set SPI bit order
bcm2835_spi_setBitOrder(BCM2835_SPI_BIT_ORDER_MSBFIRST);
// Set SPI data mode BCM2835_SPI_MODE0 = 0, CPOL = 0, CPHA = 0,
// 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)
@ -500,14 +502,15 @@ void ESC_init (const esc_cfg_t * config)
{
// Enable management of CS0 pin
bcm2835_spi_chipSelect(BCM2835_SPI_CS0);
// enable CS0 and set polarity
// 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
{
@ -523,7 +526,7 @@ void ESC_init (const esc_cfg_t * config)
counter++;
value = bcm2835_spi_read_32(ESC_CMD_BYTE_TEST);
} while ((value != ESC_BYTE_TEST_OK) && (counter < timeout));
// Check hardware is ready
do
{
@ -531,17 +534,17 @@ void ESC_init (const esc_cfg_t * config)
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 |
value = (ESCREG_ALEVENT_CONTROL |
ESCREG_ALEVENT_SMCHANGE |
ESCREG_ALEVENT_SM0 |
ESCREG_ALEVENT_SM1 );
ESC_ALeventmaskwrite(value);
@ -560,44 +563,42 @@ void ESC_init (const esc_cfg_t * config)
}
}
else
{
{
DPRINT("bcm2835_init failed. Are you running as root?\n");
}
}
void ESC_interrupt_enable (uint32_t mask)
{
if (ESCREG_ALEVENT_DC_SYNC0 & 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)
{
// Enable interrupt from SYNC0
ESC_ALeventmaskwrite(ESC_ALeventmaskread() | ESCREG_ALEVENT_DC_SYNC0);
ESC_ALeventmaskwrite(ESC_ALeventmaskread() | (mask & user_int_mask));
}
if (ESCREG_ALEVENT_SM2 & mask)
{
// Enable interrupt from SYNC0
ESC_ALeventmaskwrite(ESC_ALeventmaskread() | ESCREG_ALEVENT_SM2);
}
// 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)
{
if (ESCREG_ALEVENT_DC_SYNC0 & 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() & ~(ESCREG_ALEVENT_DC_SYNC0));
ESC_ALeventmaskwrite(ESC_ALeventmaskread() & ~(mask & user_int_mask));
}
if (ESCREG_ALEVENT_SM2 & mask)
{
// Disable interrupt from SM2
ESC_ALeventmaskwrite(ESC_ALeventmaskread() & ~(ESCREG_ALEVENT_SM2));
}
// Disable LAN9252 interrupt
bcm2835_spi_write_32(ESC_CMD_INT_EN, 0x00000000);
}

View File

@ -15,4 +15,3 @@ void ESC_interrupt_enable (uint32_t mask);
void ESC_interrupt_disable (uint32_t mask);
#endif

View File

@ -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>
@ -242,8 +242,8 @@ static void ecat_isr (void * arg)
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)

View File

@ -11,7 +11,7 @@
#ifndef __esc_hw__
#define __esc_hw__
#include <kern.h>
#include <kern/kern.h>
/* ================================================================================ */
/* ================ ECAT [ECAT0] ================ */
/* ================================================================================ */

View File

@ -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 |

View File

@ -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>