trunk, tags und branches

This commit is contained in:
Florian Pose
2005-10-21 11:21:42 +00:00
commit 6efa13d714
49 changed files with 14582 additions and 0 deletions

1004
Doxyfile Normal file

File diff suppressed because it is too large Load Diff

38
Makefile Normal file
View File

@@ -0,0 +1,38 @@
#################################################################
#
# Globales Makefile
#
# IgH EtherCAT-Treiber
#
# $Id$
#
#################################################################
all: .rs232dbg .drivers .rt .mini
doc docs:
doxygen Doxyfile
#################################################################
.drivers:
$(MAKE) -C drivers
.rt:
$(MAKE) -C rt
.rs232dbg:
$(MAKE) -C rs232dbg
.mini:
$(MAKE) -C mini
#################################################################
clean:
$(MAKE) -C rt clean
$(MAKE) -C drivers clean
$(MAKE) -C rs232dbg clean
$(MAKE) -C mini clean
#################################################################

8
TODO Normal file
View File

@@ -0,0 +1,8 @@
TODO-Liste EtherCAT-Treiber
$Date$
$Author$
- Konfiguration SSI-/Inkrementalgeberklemmen
- Ethernet over EtherCAT (EoE)
- Retry bei Asynchroner Kommunikation

71
drivers/Makefile Normal file
View File

@@ -0,0 +1,71 @@
#################################################################
#
# Makefile
#
# IgH EtherCAT-Treiber
#
# $Date$
# $Author$
#
#################################################################
#KERNELDIR=/usr/src/linux
#KERNELDIR=/home/rich/linux-2.4.20.CX1100-rthal5
#KERNELDIR=./linux-2.4.20.CX1100-rthal5
#IgH
KERNELDIR = /vol/projekte/msr_messen_steuern_regeln/linux/kernel/2.4.20/include/linux-2.4.20.CX1100-rthal5
RTAIDIR = /vol/projekte/msr_messen_steuern_regeln/linux/kernel/2.4.20/include/rtai-24.1.13
RTLIBDIR = rt_lib
#euler-nottuln
#KERNELDIR = /usr/src/linux
#RTAIDIR = /usr/src/rtai
#patra
#KERNELDIR = /usr/src/linux-2.4.20.CX1100-rthal5
#RTAIDIR = /usr/src/rtai-24.1.13
#include $(KERNELDIR)/.config
ECAT_8139_OBJ = drv_8139too.o ec_device.o ec_master.o \
ec_slave.o ec_command.o ec_types.o
CFLAGS = -O2 -Wall -Wuninitialized -D__KERNEL__ -DMODULE \
-I$(KERNELDIR)/include -D_RTAI -I$(RTAIDIR)/include \
-I$(RTLIBDIR)/msr-include
ifdef CONFIG_SMP
CFLAGS += -D__SMP__ -DSMP
endif
#################################################################
all: .depend ecat_8139too.o
ecat_8139too.o: $(ECAT_8139_OBJ)
$(LD) -r $(ECAT_8139_OBJ) -o $@
.c.o:
$(CC) $(CFLAGS) -c -o $@ $<
doc docs:
$(MAKE) -C .. doc
#################################################################
.depend:
$(CC) $(CFLAGS) -M *.c > .depend
ifeq (.depend,$(wildcard .depend))
include .depend
endif
#################################################################
clean:
rm -f *.o *~ core .depend
#################################################################

2997
drivers/drv_8139too.c Normal file

File diff suppressed because it is too large Load Diff

58
drivers/ec_command.c Normal file
View File

@@ -0,0 +1,58 @@
/****************************************************************
*
* e c _ c o m m a n d . c
*
* Methoden für ein EtherCAT-Kommando.
*
* $Date$
* $Author$
*
***************************************************************/
#include <linux/slab.h>
#include "ec_command.h"
/***************************************************************/
/**
Kommando-Konstruktor.
Initialisiert alle Variablen innerhalb des Kommandos auf die
Default-Werte.
@param cmd Zeiger auf das zu initialisierende Kommando.
*/
void EtherCAT_command_init(EtherCAT_command_t *cmd)
{
cmd->type = ECAT_CMD_NONE;
cmd->address.logical = 0x00000000;
cmd->data_length = 0;
cmd->next = NULL;
cmd->state = ECAT_CS_READY;
cmd->index = 0;
cmd->working_counter = 0;
cmd->reserved = 0; //Hm
}
/***************************************************************/
/**
Kommando-Destruktor.
Setzt nur den Status auf ECAT_CS_READY und das
reserved-Flag auf 0.
@param cmd Zeiger auf das zu initialisierende Kommando.
*/
void EtherCAT_command_clear(EtherCAT_command_t *cmd)
{
cmd->state = ECAT_CS_READY;
cmd->reserved = 0;
}
/***************************************************************/

93
drivers/ec_command.h Normal file
View File

@@ -0,0 +1,93 @@
/****************************************************************
*
* e c _ c o m m a n d . h
*
* Struktur für ein EtherCAT-Kommando.
*
* $Date$
* $Author$
*
***************************************************************/
#ifndef _EC_COMMAND_H_
#define _EC_COMMAND_H_
#include "ec_globals.h"
/**
Status eines EtherCAT-Kommandos.
*/
typedef enum
{
ECAT_CS_READY, ECAT_CS_SENT, ECAT_CS_RECEIVED
}
EtherCAT_command_state_t;
/**
EtherCAT-Adresse.
Im EtherCAT-Rahmen sind 4 Bytes für die Adresse reserviert, die
ja nach Kommandoty eine andere bedeutung haben: Bei Autoinkrement-
befehlen sind die ersten zwei Bytes die (negative)
Autoinkrement-Adresse, bei Knoten-adressierten Befehlen entsprechen
sie der Knotenadresse. Das dritte und vierte Byte entspricht in
diesen Fällen der physikalischen Speicheradresse auf dem Slave.
Bei einer logischen Adressierung entsprechen alle vier Bytes
der logischen Adresse.
*/
typedef union
{
struct
{
union
{
short pos; /**< (Negative) Ring-Position des Slaves */
unsigned short node; /**< Konfigurierte Knotenadresse */
}
dev;
unsigned short mem; /**< Physikalische Speicheradresse im Slave */
}
phy;
unsigned long logical; /**< Logische Adresse */
unsigned char raw[4]; /**< Rohdaten für die generierung des Frames */
}
EtherCAT_address_t;
/***************************************************************/
/**
EtherCAT-Kommando.
*/
typedef struct EtherCAT_command
{
EtherCAT_cmd_type_t type; /**< Typ des Kommandos (APRD, NPWR, etc...) */
EtherCAT_address_t address; /**< Adresse des/der Empfänger */
unsigned int data_length; /**< Länge der zu sendenden und/oder empfangenen Daten */
struct EtherCAT_command *next; /**< (Für den Master) Zeiger auf nächstes Kommando
in der Liste */
EtherCAT_command_state_t state; /**< Zustand des Kommandos (bereit, gesendet, etc...) */
unsigned char index; /**< Kommando-Index, mit der das Kommando gesendet wurde (wird
vom Master beim Senden gesetzt. */
unsigned int working_counter; /**< Working-Counter bei Empfang (wird vom Master gesetzt) */
unsigned char data[ECAT_FRAME_BUFFER_SIZE]; /**< Kommandodaten */
unsigned char reserved; /**< Markiert, das das Kommando gerade benutzt wird */
}
EtherCAT_command_t;
/***************************************************************/
void EtherCAT_command_init(EtherCAT_command_t *);
void EtherCAT_command_clear(EtherCAT_command_t *);
/***************************************************************/
#endif

23
drivers/ec_dbg.h Normal file
View File

@@ -0,0 +1,23 @@
#ifndef ECDBG_H_
#define ECDBG_H_
//#define DEBUG_SEND_RECEIVE
#define ECMASTER_DEBUG
#include "../rs232dbg/rs232dbg.h"
#ifdef ECMASTER_DEBUG
/* note: prints function name for you */
//# define EC_DBG(fmt, args...) SDBG_print(fmt, ## args)
#define EC_DBG(fmt, args...) SDBG_print("%s: " fmt, __FUNCTION__ , ## args)
//#define EC_DBG(fmt, args...) printk(KERN_INFO fmt, ## args)
#else
#define EC_DBG(fmt, args...)
#endif
#endif

320
drivers/ec_device.c Normal file
View File

@@ -0,0 +1,320 @@
/****************************************************************
*
* e c _ d e v i c e . c
*
* Methoden für ein EtherCAT-Gerät.
*
* $Date$
* $Author$
*
***************************************************************/
#include <linux/skbuff.h>
#include <linux/if_ether.h>
#include <linux/netdevice.h>
#include <rtai.h>
#include "ec_device.h"
#include "ec_dbg.h"
/***************************************************************/
/**
EtherCAT-Geräte-Konstuktor.
Initialisiert ein EtherCAT-Gerät, indem es die Variablen
in der Struktur auf die Default-Werte setzt.
@param ecd Zu initialisierendes EtherCAT-Gerät
*/
void EtherCAT_device_init(EtherCAT_device_t *ecd)
{
ecd->dev = NULL;
ecd->tx_skb = NULL;
ecd->rx_skb = NULL;
ecd->tx_time = 0;
ecd->rx_time = 0;
ecd->tx_intr_cnt = 0;
ecd->rx_intr_cnt = 0;
ecd->intr_cnt = 0;
ecd->state = ECAT_DS_READY;
ecd->rx_data_length = 0;
ecd->lock = NULL;
}
/***************************************************************/
/**
EtherCAT-Geräte-Destuktor.
Gibt den dynamisch allozierten Speicher des
EtherCAT-Gerätes (die beiden Socket-Buffer) wieder frei.
@param ecd EtherCAT-Gerät
*/
void EtherCAT_device_clear(EtherCAT_device_t *ecd)
{
ecd->dev = NULL;
if (ecd->tx_skb)
{
dev_kfree_skb(ecd->tx_skb);
ecd->tx_skb = NULL;
}
if (ecd->rx_skb)
{
dev_kfree_skb(ecd->rx_skb);
ecd->rx_skb = NULL;
}
}
/***************************************************************/
/**
Weist einem EtherCAT-Gerät das entsprechende net_device zu.
Prüft das net_device, allokiert Socket-Buffer in Sende- und
Empfangsrichtung und weist dem EtherCAT-Gerät und den
Socket-Buffern das net_device zu.
@param ecd EtherCAT-Device
@param dev net_device
@return 0: Erfolg, < 0: Konnte Socket-Buffer nicht allozieren.
*/
int EtherCAT_device_assign(EtherCAT_device_t *ecd,
struct net_device *dev)
{
if (!dev)
{
EC_DBG("EtherCAT: Device is NULL!\n");
return -1;
}
if ((ecd->tx_skb = dev_alloc_skb(ECAT_FRAME_BUFFER_SIZE)) == NULL)
{
EC_DBG(KERN_ERR "EtherCAT: Could not allocate device tx socket buffer!\n");
return -1;
}
if ((ecd->rx_skb = dev_alloc_skb(ECAT_FRAME_BUFFER_SIZE)) == NULL)
{
dev_kfree_skb(ecd->tx_skb);
ecd->tx_skb = NULL;
EC_DBG(KERN_ERR "EtherCAT: Could not allocate device rx socket buffer!\n");
return -1;
}
ecd->dev = dev;
ecd->tx_skb->dev = dev;
ecd->rx_skb->dev = dev;
EC_DBG("EtherCAT: Assigned Device %X.\n", (unsigned) dev);
return 0;
}
/***************************************************************/
/**
Führt die open()-Funktion des Netzwerktreibers aus.
Dies entspricht einem "ifconfig up". Vorher wird der Zeiger
auf das EtherCAT-Gerät auf Gültigkeit geprüft und der
Gerätezustand zurückgesetzt.
@param ecd EtherCAT-Gerät
@return 0 bei Erfolg, < 0: Ungültiger Zeiger, oder open()
fehlgeschlagen
*/
int EtherCAT_device_open(EtherCAT_device_t *ecd)
{
if (!ecd)
{
EC_DBG(KERN_ERR "EtherCAT: Trying to open a NULL device!\n");
return -1;
}
if (!ecd->dev)
{
EC_DBG(KERN_ERR "EtherCAT: No device to open!\n");
return -1;
}
// Reset old device state
ecd->state = ECAT_DS_READY;
ecd->tx_intr_cnt = 0;
ecd->rx_intr_cnt = 0;
return ecd->dev->open(ecd->dev);
}
/***************************************************************/
/**
Führt die stop()-Funktion des net_devices aus.
@param ecd EtherCAT-Gerät
@return 0 bei Erfolg, < 0: Kein Gerät zum Schliessen
*/
int EtherCAT_device_close(EtherCAT_device_t *ecd)
{
if (!ecd->dev)
{
EC_DBG("EtherCAT: No device to close!\n");
return -1;
}
EC_DBG("EtherCAT: txcnt: %u, rxcnt: %u\n",
(unsigned int) ecd->tx_intr_cnt,
(unsigned int) ecd->rx_intr_cnt);
EC_DBG("EtherCAT: Stopping device at 0x%X\n",
(unsigned int) ecd->dev);
return ecd->dev->stop(ecd->dev);
}
/***************************************************************/
/**
Sendet einen Rahmen über das EtherCAT-Gerät.
Kopiert die zu sendenden Daten in den statischen Socket-
Buffer, fügt den Ethernat-II-Header hinzu und ruft die
start_xmit()-Funktion der Netzwerkkarte auf.
@param ecd EtherCAT-Gerät
@param data Zeiger auf die zu sendenden Daten
@param length Länge der zu sendenden Daten
@return 0 bei Erfolg, < 0: Vorheriger Rahmen noch
nicht empfangen, oder kein Speicher mehr vorhanden
*/
int EtherCAT_device_send(EtherCAT_device_t *ecd,
unsigned char *data,
unsigned int length)
{
unsigned char *frame_data;
struct ethhdr *eth;
if (ecd->state == ECAT_DS_SENT)
{
EC_DBG(KERN_ERR "EtherCAT: Trying to send frame while last was not received!\n");
return -1;
}
skb_trim(ecd->tx_skb, 0); // Clear transmit socket buffer
skb_reserve(ecd->tx_skb, ETH_HLEN); // Reserve space for Ethernet-II header
// Copy data to socket buffer
frame_data = skb_put(ecd->tx_skb, length);
memcpy(frame_data, data, length);
// Add Ethernet-II-Header
if ((eth = (struct ethhdr *) skb_push(ecd->tx_skb, ETH_HLEN)) == NULL)
{
EC_DBG(KERN_ERR "EtherCAT: device_send - Could not allocate Ethernet-II header!\n");
return -1;
}
eth->h_proto = htons(0x88A4); // Protocol type
memcpy(eth->h_source, ecd->dev->dev_addr, ecd->dev->addr_len); // Hardware address
memset(eth->h_dest, 0xFF, ecd->dev->addr_len); // Broadcast address
rdtscl(ecd->tx_time); // Get CPU cycles
// Start sending of frame
ecd->state = ECAT_DS_SENT;
ecd->dev->hard_start_xmit(ecd->tx_skb, ecd->dev);
return 0;
}
/***************************************************************/
/**
Holt einen empfangenen Rahmen von der Netzwerkkarte.
Zuerst wird geprüft, ob überhaupt ein Rahmen empfangen
wurde. Wenn ja, wird diesem mit Hilfe eines Spin-Locks
in den angegebenen Speicherbereich kopiert.
@param ecd EtherCAT-Gerät
@param data Zeiger auf den Speicherbereich, in den die
empfangenen Daten kopiert werden sollen
@param size Größe des angegebenen Speicherbereichs
@return Anzahl der kopierten Bytes bei Erfolg, sonst < 0
*/
int EtherCAT_device_receive(EtherCAT_device_t *ecd,
unsigned char *data,
unsigned int size)
{
int cnt;
// unsigned long flags;
if (ecd->state != ECAT_DS_RECEIVED)
{
EC_DBG(KERN_ERR "EtherCAT: receive - Nothing received!\n");
return -1;
}
// flags = rt_spin_lock_irqsave(ecd->lock);
cnt = min(ecd->rx_data_length, size);
memcpy(data,ecd->rx_data, cnt);
// rt_spin_unlock_irqrestore(ecd->lock, flags);
return cnt;
}
/***************************************************************/
/**
Gibt alle Informationen über das Device-Objekt aus.
@param ecd EtherCAT-Gerät
*/
void EtherCAT_device_debug(EtherCAT_device_t *ecd)
{
EC_DBG(KERN_DEBUG "---EtherCAT device information begin---\n");
if (ecd)
{
EC_DBG(KERN_DEBUG "Assigned net_device: %X\n", (unsigned) ecd->dev);
EC_DBG(KERN_DEBUG "Transmit socket buffer: %X\n", (unsigned) ecd->tx_skb);
EC_DBG(KERN_DEBUG "Receive socket buffer: %X\n", (unsigned) ecd->rx_skb);
EC_DBG(KERN_DEBUG "Time of last transmission: %u\n", (unsigned) ecd->tx_time);
EC_DBG(KERN_DEBUG "Time of last receive: %u\n", (unsigned) ecd->rx_time);
EC_DBG(KERN_DEBUG "Number of transmit interrupts: %u\n", (unsigned) ecd->tx_intr_cnt);
EC_DBG(KERN_DEBUG "Number of receive interrupts: %u\n", (unsigned) ecd->rx_intr_cnt);
EC_DBG(KERN_DEBUG "Total Number of interrupts: %u\n", (unsigned) ecd->intr_cnt);
EC_DBG(KERN_DEBUG "Actual device state: %i\n", (int) ecd->state);
EC_DBG(KERN_DEBUG "Receive buffer: %X\n", (unsigned) ecd->rx_data);
EC_DBG(KERN_DEBUG "Receive buffer fill state: %u/%u\n",
(unsigned) ecd->rx_data_length, ECAT_FRAME_BUFFER_SIZE);
EC_DBG(KERN_DEBUG "Lock: %X\n", (unsigned) ecd->lock);
}
else
{
EC_DBG(KERN_DEBUG "Device is NULL!\n");
}
EC_DBG(KERN_DEBUG "---EtherCAT device information end---\n");
}
/***************************************************************/

86
drivers/ec_device.h Normal file
View File

@@ -0,0 +1,86 @@
/****************************************************************
*
* e c _ d e v i c e . h
*
* Struktur für ein EtherCAT-Gerät.
*
* $Date$
* $Author$
*
***************************************************************/
#ifndef _EC_DEVICE_H_
#define _EC_DEVICE_H_
#include "ec_globals.h"
/**
Zustand eines EtherCAT-Gerätes.
Eine Für EtherCAT reservierte Netzwerkkarte kann bestimmte Zustände haben.
*/
typedef enum
{
ECAT_DS_READY, /**< Das Gerät ist bereit zum Senden */
ECAT_DS_SENT, /**< Das Gerät hat einen Rahmen abgesendet,
aber noch keine Antwort enpfangen */
ECAT_DS_RECEIVED, /**< Das Gerät hat eine Antwort auf einen
zuvor gesendeten Rahmen empfangen */
ECAT_DS_TIMEOUT, /**< Nach dem Senden eines Rahmens meldete
das Gerät einen Timeout */
ECAT_DS_ERROR /**< Nach dem Senden eines frames hat das
Gerät einen Fehler festgestellt. */
}
EtherCAT_device_state_t;
#define ECAT_BUS_TIME(ecd_ptr) ((((ecd_ptr)->rx_time - \
(ecd_ptr)->tx_time) * 1000) / cpu_khz)
/***************************************************************/
/**
EtherCAT-Gerät.
Ein EtherCAT-Gerät ist eine Netzwerkkarte, die vom
EtherCAT-Master dazu verwendet wird, um Frames zu senden
und zu empfangen.
*/
typedef struct
{
struct net_device *dev; /**< Zeiger auf das reservierte net_device */
struct sk_buff *tx_skb; /**< Zeiger auf Transmit-Socketbuffer */
struct sk_buff *rx_skb; /**< Zeiger auf Receive-Socketbuffer */
unsigned long tx_time; /**< Zeit des letzten Sendens */
unsigned long rx_time; /**< Zeit des letzten Empfangs */
unsigned long tx_intr_cnt; /**< Anzahl Tx-Interrupts */
unsigned long rx_intr_cnt; /**< Anzahl Rx-Interrupts */
unsigned long intr_cnt; /**< Anzahl Interrupts */
volatile EtherCAT_device_state_t state; /**< Gesendet, Empfangen,
Timeout, etc. */
unsigned char rx_data[ECAT_FRAME_BUFFER_SIZE]; /**< Puffer für
empfangene Rahmen */
volatile unsigned int rx_data_length; /**< Länge des zuletzt
empfangenen Rahmens */
spinlock_t *lock; /**< Zeiger auf das Spinlock des net_devices */
}
EtherCAT_device_t;
/***************************************************************/
void EtherCAT_device_init(EtherCAT_device_t *);
int EtherCAT_device_assign(EtherCAT_device_t *, struct net_device *);
void EtherCAT_device_clear(EtherCAT_device_t *);
int EtherCAT_device_open(EtherCAT_device_t *);
int EtherCAT_device_close(EtherCAT_device_t *);
int EtherCAT_device_send(EtherCAT_device_t *, unsigned char *, unsigned int);
int EtherCAT_device_receive(EtherCAT_device_t *, unsigned char *, unsigned int);
void EtherCAT_device_debug(EtherCAT_device_t *);
/***************************************************************/
#endif

77
drivers/ec_globals.h Normal file
View File

@@ -0,0 +1,77 @@
/****************************************************************
*
* e c _ g l o b a l s . h
*
* Globale Definitionen und Makros für das EtherCAT-Protokoll.
*
* $Date$
* $Author$
*
***************************************************************/
#ifndef _EC_GLOBALS_
#define _EC_GLOBALS_
/**
Maximale Größe eines EtherCAT-Frames
*/
#define ECAT_FRAME_BUFFER_SIZE 1600
/**
Anzahl der Kommandos in einem Master-Kommandoring
*/
#define ECAT_COMMAND_RING_SIZE 10
/**
Anzahl der Versuche beim Asynchronen Senden/Empfangen
*/
#define ECAT_NUM_RETRIES 10
/**
NULL-Define, falls noch nicht definiert.
*/
#ifndef NULL
#define NULL ((void *) 0)
#endif
/**
EtherCAT-Kommando-Typ
*/
typedef enum
{
ECAT_CMD_NONE = 0x00, /**< Dummy */
ECAT_CMD_APRD = 0x01, /**< Auto-increment physical read */
ECAT_CMD_APWR = 0x02, /**< Auto-increment physical write */
ECAT_CMD_NPRD = 0x04, /**< Node-addressed physical read */
ECAT_CMD_NPWR = 0x05, /**< Node-addressed physical write */
ECAT_CMD_BRD = 0x07, /**< Broadcast read */
ECAT_CMD_BWR = 0x08, /**< Broadcast write */
ECAT_CMD_LRW = 0x0C /**< Logical read/write */
}
EtherCAT_cmd_type_t;
/**
Zustand eines EtherCAT-Slaves
*/
typedef enum
{
ECAT_STATE_UNKNOWN = 0x00, /**< Status unbekannt */
ECAT_STATE_INIT = 0x01, /**< Init-Zustand (Keine Mailbox-
Kommunikation, Kein I/O) */
ECAT_STATE_PREOP = 0x02, /**< Pre-Operational (Mailbox-
Kommunikation, Kein I/O) */
ECAT_STATE_SAVEOP = 0x04, /**< Save-Operational (Mailbox-
Kommunikation und Input Update) */
ECAT_STATE_OP = 0x08, /**< Operational, (Mailbox-
Kommunikation und Input/Output Update) */
ECAT_ACK_STATE = 0x10 /**< Acknoledge-Bit beim Zustandswechsel
(dies ist kein eigener Zustand) */
}
EtherCAT_state_t;
/***************************************************************/
#endif

1767
drivers/ec_master.c Normal file

File diff suppressed because it is too large Load Diff

134
drivers/ec_master.h Normal file
View File

@@ -0,0 +1,134 @@
/****************************************************************
*
* e c _ m a s t e r . h
*
* Struktur für einen EtherCAT-Master.
*
* $Date$
* $Author$
*
***************************************************************/
#ifndef _EC_MASTER_H_
#define _EC_MASTER_H_
#include "ec_device.h"
#include "ec_slave.h"
#include "ec_command.h"
/***************************************************************/
/**
EtherCAT-Master
Verwaltet die EtherCAT-Slaves und kommuniziert mit
dem zugewiesenen EtherCAT-Gerät.
*/
typedef struct
{
EtherCAT_slave_t *slaves; /**< Zeiger auf statischen Speicher
mit Slave-Informationen */
unsigned int slave_count; /**< Anzahl der Slaves in slaves */
EtherCAT_command_t *first_command; /**< Zeiger auf das erste
Kommando in der Liste */
EtherCAT_command_t *process_data_command; /**< Zeiger Auf das Kommando
zum Senden und Empfangen
der Prozessdaten */
EtherCAT_device_t *dev; /**< Zeiger auf das zugewiesene EtherCAT-Gerät */
unsigned char command_index; /**< Aktueller Kommando-Index */
unsigned char tx_data[ECAT_FRAME_BUFFER_SIZE]; /**< Statischer Speicher
für zu sendende Daten */
unsigned int tx_data_length; /**< Länge der Daten im Sendespeicher */
unsigned char rx_data[ECAT_FRAME_BUFFER_SIZE]; /**< Statische Speicher für
eine Kopie des Rx-Buffers
im EtherCAT-Gerät */
unsigned char *process_data; /**< Zeiger auf Speicher mit Prozessdaten */
unsigned int process_data_length; /**< Länge der Prozessdaten */
EtherCAT_command_t cmd_ring[ECAT_COMMAND_RING_SIZE]; /** Statischer Kommandoring */
unsigned int cmd_ring_index; /**< Index des nächsten Kommandos im Ring */
}
EtherCAT_master_t;
/***************************************************************/
// Master creation and deletion
int EtherCAT_master_init(EtherCAT_master_t *, EtherCAT_device_t *);
void EtherCAT_master_clear(EtherCAT_master_t *);
// Slave management
int EtherCAT_check_slaves(EtherCAT_master_t *, EtherCAT_slave_t *, unsigned int);
void EtherCAT_clear_slaves(EtherCAT_master_t *);
int EtherCAT_activate_slave(EtherCAT_master_t *, EtherCAT_slave_t *);
int EtherCAT_deactivate_slave(EtherCAT_master_t *, EtherCAT_slave_t *);
int EtherCAT_activate_all_slaves(EtherCAT_master_t *);
int EtherCAT_deactivate_all_slaves(EtherCAT_master_t *);
// Sending and receiving
int EtherCAT_async_send_receive(EtherCAT_master_t *);
int EtherCAT_send(EtherCAT_master_t *);
int EtherCAT_receive(EtherCAT_master_t *);
int EtherCAT_write_process_data(EtherCAT_master_t *);
int EtherCAT_read_process_data(EtherCAT_master_t *);
/***************************************************************/
// Slave information interface
int EtherCAT_read_slave_information(EtherCAT_master_t *,
unsigned short int,
unsigned short int,
unsigned int *);
// EtherCAT commands
EtherCAT_command_t *EtherCAT_read(EtherCAT_master_t *,
unsigned short,
unsigned short,
unsigned int);
EtherCAT_command_t *EtherCAT_write(EtherCAT_master_t *,
unsigned short,
unsigned short,
unsigned int,
const unsigned char *);
EtherCAT_command_t *EtherCAT_position_read(EtherCAT_master_t *,
short,
unsigned short,
unsigned int);
EtherCAT_command_t *EtherCAT_position_write(EtherCAT_master_t *,
short,
unsigned short,
unsigned int,
const unsigned char *);
EtherCAT_command_t *EtherCAT_broadcast_read(EtherCAT_master_t *,
unsigned short,
unsigned int);
EtherCAT_command_t *EtherCAT_broadcast_write(EtherCAT_master_t *,
unsigned short,
unsigned int,
const unsigned char *);
EtherCAT_command_t *EtherCAT_logical_read_write(EtherCAT_master_t *,
unsigned int,
unsigned int,
unsigned char *);
void EtherCAT_remove_command(EtherCAT_master_t *, EtherCAT_command_t *);
// Slave states
int EtherCAT_state_change(EtherCAT_master_t *, EtherCAT_slave_t *, unsigned char);
/***************************************************************/
// Private functions
EtherCAT_command_t *alloc_cmd(EtherCAT_master_t *);
void add_command(EtherCAT_master_t *, EtherCAT_command_t *);
void set_byte(unsigned char *, unsigned int, unsigned char);
void set_word(unsigned char *, unsigned int, unsigned int);
/***************************************************************/
#endif

160
drivers/ec_slave.c Normal file
View File

@@ -0,0 +1,160 @@
/****************************************************************
*
* e c _ s l a v e . c
*
* Methoden für einen EtherCAT-Slave.
*
* $Date$
* $Author$
*
***************************************************************/
#include <linux/kernel.h>
#include "ec_globals.h"
#include "ec_slave.h"
#include "ec_dbg.h"
/***************************************************************/
/**
EtherCAT-Slave-Konstruktor.
Initialisiert einen EtherCAT-Slave.
@param slave Zeiger auf den zu initialisierenden Slave
*/
void EtherCAT_slave_init(EtherCAT_slave_t *slave)
{
slave->type = 0;
slave->revision = 0;
slave->build = 0;
slave->ring_position = 0;
slave->station_address = 0;
slave->vendor_id = 0;
slave->product_code = 0;
slave->revision_number = 0;
slave->desc = 0;
slave->logical_address0 = 0;
slave->current_state = ECAT_STATE_UNKNOWN;
slave->requested_state = ECAT_STATE_UNKNOWN;
}
/***************************************************************/
/**
EtherCAT-Slave-Destruktor.
Im Moment ohne Funktionalität.
@param slave Zeiger auf den zu zerstörenden Slave
*/
void EtherCAT_slave_clear(EtherCAT_slave_t *slave)
{
// Nothing yet...
}
/***************************************************************/
/**
Liest einen bestimmten Kanal des Slaves als Integer-Wert.
Prüft zuerst, ob der entsprechende Slave eine
bekannte Beschreibung besitzt, ob dort eine
read()-Funktion hinterlegt ist und ob die angegebene
Kanalnummer gültig ist. Wenn ja, wird der dekodierte
Wert zurückgegeben, sonst ist der Wert 0.
@param slave EtherCAT-Slave
@param channel Kanalnummer
@return Gelesener Wert bzw. 0
*/
int EtherCAT_read_value(EtherCAT_slave_t *slave,
unsigned int channel)
{
if (!slave->desc)
{
EC_DBG(KERN_WARNING "EtherCAT: Reading failed - "
"Slave %04X (at %0X) has no description.\n",
slave->station_address, (unsigned int) slave);
return 0;
}
if (!slave->desc->read)
{
EC_DBG(KERN_WARNING "EtherCAT: Reading failed - "
"Slave type (%s %s) has no read method.\n",
slave->desc->vendor_name, slave->desc->product_name);
return 0;
}
if (channel >= slave->desc->channels)
{
EC_DBG(KERN_WARNING "EtherCAT: Reading failed - "
"Slave %4X (%s %s) has no channel %i.\n",
slave->station_address, slave->desc->vendor_name,
slave->desc->product_name, channel);
return 0;
}
return slave->desc->read(slave->process_data, channel);
}
/***************************************************************/
/**
Schreibt einen bestimmten Kanal des Slaves als Integer-Wert .
Prüft zuerst, ob der entsprechende Slave eine
bekannte Beschreibung besitzt, ob dort eine
write()-Funktion hinterlegt ist und ob die angegebene
Kanalnummer gültig ist. Wenn ja, wird der Wert entsprechend
kodiert und geschrieben.
@param slave EtherCAT-Slave
@param channel Kanalnummer
@param value Zu schreibender Wert
*/
void EtherCAT_write_value(EtherCAT_slave_t *slave,
unsigned int channel,
int value)
{
if (!slave->desc)
{
EC_DBG(KERN_WARNING "EtherCAT: Writing failed - "
"Slave %04X (at %0X) has no description.\n",
slave->station_address, (unsigned int) slave);
return;
}
if (!slave->desc->write)
{
EC_DBG(KERN_WARNING "EtherCAT: Writing failed - "
"Slave type (%s %s) has no write method.\n",
slave->desc->vendor_name, slave->desc->product_name);
return;
}
if (channel >= slave->desc->channels)
{
EC_DBG(KERN_WARNING "EtherCAT: Writing failed - "
"Slave %4X (%s %s) has no channel %i.\n",
slave->station_address, slave->desc->vendor_name,
slave->desc->product_name, channel);
return;
}
slave->desc->write(slave->process_data, channel, value);
}
/***************************************************************/

67
drivers/ec_slave.h Normal file
View File

@@ -0,0 +1,67 @@
/****************************************************************
*
* e c _ s l a v e . h
*
* Struktur für einen EtherCAT-Slave.
*
* $Date$
* $Author$
*
***************************************************************/
#ifndef _EC_SLAVE_H_
#define _EC_SLAVE_H_
#include "ec_types.h"
/***************************************************************/
/**
EtherCAT-Slave
*/
typedef struct
{
// Base data
unsigned char type; /**< Slave-Typ */
unsigned char revision; /**< Revision */
unsigned short build; /**< Build-Nummer */
// Addresses
short ring_position; /**< (Negative) Position des Slaves im Bus */
unsigned short station_address; /**< Konfigurierte Slave-Adresse */
// Slave information interface
unsigned int vendor_id; /**< Identifikationsnummer des Herstellers */
unsigned int product_code; /**< Herstellerspezifischer Produktcode */
unsigned int revision_number; /**< Revisionsnummer */
const EtherCAT_slave_desc_t *desc; /**< Zeiger auf die Beschreibung
des Slave-Typs */
unsigned int logical_address0; /**< Konfigurierte, logische adresse */
EtherCAT_state_t current_state; /**< Aktueller Zustand */
EtherCAT_state_t requested_state; /**< Angeforderter Zustand */
unsigned char *process_data; /**< Zeiger auf den Speicherbereich
im Prozessdatenspeicher des Masters */
}
EtherCAT_slave_t;
#define ECAT_INIT_SLAVE(TYPE) {0, 0, 0, 0, 0, 0, 0, 0, \
TYPE, 0, ECAT_STATE_UNKNOWN, \
ECAT_STATE_UNKNOWN, NULL}
/***************************************************************/
// Slave construction and deletion
void EtherCAT_slave_init(EtherCAT_slave_t *);
void EtherCAT_slave_clear(EtherCAT_slave_t *);
int EtherCAT_read_value(EtherCAT_slave_t *, unsigned int);
void EtherCAT_write_value(EtherCAT_slave_t *, unsigned int, int);
/***************************************************************/
#endif

157
drivers/ec_types.c Normal file
View File

@@ -0,0 +1,157 @@
/****************************************************************
*
* e c _ t y p e s . c
*
* EtherCAT-Slave-Typen.
*
* $Date: 2005-09-07 17:50:50 +0200 (Mit, 07 Sep 2005) $
* $Author: fp $
*
***************************************************************/
#include "ec_globals.h"
#include "ec_types.h"
/***************************************************************/
unsigned char sm0_multi[] = {0x00, 0x18, 0xF6, 0x00, 0x26, 0x00, 0x01, 0x00};
unsigned char sm1_multi[] = {0xF6, 0x18, 0xF6, 0x00, 0x22, 0x00, 0x01, 0x00};
unsigned char sm0_1014[] = {0x00, 0x10, 0x01, 0x00, 0x00, 0x00, 0x01, 0x00};
unsigned char sm0_2004[] = {0x00, 0x0F, 0x01, 0x00, 0x46, 0x00, 0x01, 0x00};
unsigned char sm2_31xx[] = {0x00, 0x10, 0x04, 0x00, 0x24, 0x00, 0x00, 0x00};
unsigned char sm3_31xx[] = {0x00, 0x11, 0x06, 0x00, 0x20, 0x00, 0x01, 0x00};
unsigned char sm2_4102[] = {0x00, 0x10, 0x04, 0x00, 0x24, 0x00, 0x01, 0x00};
unsigned char fmmu0_1014[] = {0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x07,
0x00, 0x10, 0x00, 0x01, 0x01, 0x00, 0x00, 0x00};
unsigned char fmmu0_2004[] = {0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x07,
0x00, 0x0F, 0x00, 0x02, 0x01, 0x00, 0x00, 0x00};
unsigned char fmmu0_31xx[] = {0x00, 0x00, 0x00, 0x00, 0x06, 0x00, 0x00, 0x07,
0x00, 0x11, 0x00, 0x01, 0x01, 0x00, 0x00, 0x00};
unsigned char fmmu0_4102[] = {0x00, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, 0x07,
0x00, 0x10, 0x00, 0x02, 0x01, 0x00, 0x00, 0x00};
int read_1014(unsigned char *data, unsigned int channel)
{
return (data[0] >> channel) & 0x01;
}
void write_2004(unsigned char *data, unsigned int channel, int value)
{
if (value)
{
data[0] |= (1 << channel);
}
else
{
data[0] &= ~(1 << channel);
}
}
int read_31xx(unsigned char *data, unsigned int channel)
{
return (short int) ((data[channel * 3 + 2] << 8) | data[channel * 3 + 1]);
}
void write_4102(unsigned char *data, unsigned int channel, int value)
{
data[channel * 3 + 1] = (value & 0xFF00) >> 8;
data[channel * 3 + 2] = value & 0xFF;
}
/***************************************************************/
EtherCAT_slave_desc_t Beckhoff_EK1100[] =
{{
"Beckhoff", "EK1100", "Bus Coupler",
ECAT_ST_SIMPLE_NOSYNC,
NULL, NULL, NULL, NULL,
NULL,
0, 0,
NULL, NULL
}};
EtherCAT_slave_desc_t Beckhoff_EL1014[] =
{{
"Beckhoff", "EL1014", "4x Digital Input",
ECAT_ST_SIMPLE,
sm0_1014, NULL, NULL, NULL,
fmmu0_1014,
1, 4,
read_1014, NULL
}};
EtherCAT_slave_desc_t Beckhoff_EL2004[] =
{{
"Beckhoff", "EL2004", "4x Digital Output",
ECAT_ST_SIMPLE,
sm0_2004, NULL, NULL, NULL,
fmmu0_2004,
1, 4,
NULL, write_2004
}};
EtherCAT_slave_desc_t Beckhoff_EL3102[] =
{{
"Beckhoff", "EL3102", "2x Analog Input Diff",
ECAT_ST_MAILBOX,
sm0_multi, sm1_multi, sm2_31xx, sm3_31xx,
fmmu0_31xx,
6, 2,
read_31xx, NULL
}};
EtherCAT_slave_desc_t Beckhoff_EL3162[] =
{{
"Beckhoff", "EL3162", "2x Analog Input",
ECAT_ST_MAILBOX,
sm0_multi, sm1_multi, sm2_31xx, sm3_31xx,
fmmu0_31xx,
6, 2,
read_31xx, NULL
}};
EtherCAT_slave_desc_t Beckhoff_EL4102[] =
{{
"Beckhoff", "EL4102", "2x Analog Output",
ECAT_ST_MAILBOX,
sm0_multi, sm1_multi, sm2_4102, NULL,
fmmu0_4102,
4, 2,
NULL, write_4102
}};
EtherCAT_slave_desc_t Beckhoff_EL5001[] =
{{
"Beckhoff", "EL5001", "SSI-Interface",
ECAT_ST_SIMPLE,
NULL, NULL, NULL, NULL, // Noch nicht eingepflegt...
NULL,
0, 0,
NULL, NULL
}};
/***************************************************************/
unsigned int slave_idents_count = 7;
struct slave_ident slave_idents[] =
{
{0x00000002, 0x03F63052, Beckhoff_EL1014},
{0x00000002, 0x044C2C52, Beckhoff_EK1100},
{0x00000002, 0x07D43052, Beckhoff_EL2004},
{0x00000002, 0x0C1E3052, Beckhoff_EL3102},
{0x00000002, 0x0C5A3052, Beckhoff_EL3162},
{0x00000002, 0x10063052, Beckhoff_EL4102},
{0x00000002, 0x13893052, Beckhoff_EL5001}
};
/***************************************************************/

104
drivers/ec_types.h Normal file
View File

@@ -0,0 +1,104 @@
/****************************************************************
*
* e c _ t y p e s . h
*
* EtherCAT-Slave-Typen.
*
* $Date: 2005-09-07 17:50:50 +0200 (Mit, 07 Sep 2005) $
* $Author: fp $
*
***************************************************************/
#ifndef _EC_TYPES_H_
#define _EC_TYPES_H_
/**
Typ eines EtherCAT-Slaves.
Dieser Typ muss für die Konfiguration bekannt sein. Der
Master entscheidet danach, ober bspw. Mailboxes konfigurieren,
oder Sync-Manager setzen soll.
*/
typedef enum
{
ECAT_ST_SIMPLE, ECAT_ST_MAILBOX, ECAT_ST_SIMPLE_NOSYNC
}
EtherCAT_slave_type_t;
/***************************************************************/
/**
Beschreibung eines EtherCAT-Slave-Typs.
Diese Beschreibung dient zur Konfiguration einer bestimmten
Slave-Art. Sie enthält die Konfigurationsdaten für die
Slave-internen Sync-Manager und FMMU's.
*/
typedef struct slave_desc
{
const char *vendor_name; /**< Name des Herstellers */
const char *product_name; /**< Name des Slaves-Typs */
const char *product_desc; /**< Genauere Beschreibung des Slave-Typs */
const EtherCAT_slave_type_t type; /**< Art des Slave-Typs */
const unsigned char *sm0; /**< Konfigurationsdaten des
ersten Sync-Managers */
const unsigned char *sm1; /**< Konfigurationsdaten des
zweiten Sync-Managers */
const unsigned char *sm2; /**< Konfigurationsdaten des
dritten Sync-Managers */
const unsigned char *sm3; /**< Konfigurationsdaten des
vierten Sync-Managers */
const unsigned char *fmmu0; /**< Konfigurationsdaten
der ersten FMMU */
const unsigned int data_length; /**< Länge der Prozessdaten in Bytes */
const unsigned int channels; /**< Anzahl der Kanäle */
int (*read) (unsigned char *, unsigned int); /**< Funktion zum Dekodieren
und Lesen der Kanaldaten */
void (*write) (unsigned char *, unsigned int, int); /**< Funktion zum Kodieren
und Schreiben der
Kanaldaten */
}
EtherCAT_slave_desc_t;
/***************************************************************/
/**
Identifikation eines Slave-Typs.
Diese Struktur wird zur 1:n-Zuordnung von Hersteller- und
Produktcodes zu den einzelnen Slave-Typen verwendet.
*/
struct slave_ident
{
const unsigned int vendor_id; /**< Hersteller-Code */
const unsigned int product_code; /**< Herstellerspezifischer Produktcode */
const EtherCAT_slave_desc_t *desc; /**< Zeiger auf den dazugehörigen
Slave-Typ */
};
extern struct slave_ident slave_idents[]; /**< Statisches Array der
Slave-Identifikationen */
extern unsigned int slave_idents_count; /**< Anzahl der bekannten Slave-
Identifikationen */
/***************************************************************/
extern EtherCAT_slave_desc_t Beckhoff_EK1100[];
extern EtherCAT_slave_desc_t Beckhoff_EL1014[];
extern EtherCAT_slave_desc_t Beckhoff_EL2004[];
extern EtherCAT_slave_desc_t Beckhoff_EL3102[];
extern EtherCAT_slave_desc_t Beckhoff_EL3162[];
extern EtherCAT_slave_desc_t Beckhoff_EL4102[];
extern EtherCAT_slave_desc_t Beckhoff_EL5001[];
/***************************************************************/
#endif

41
mini/Makefile Normal file
View File

@@ -0,0 +1,41 @@
#----------------------------------------------------------------
#
# Makefile
#
# Minimales EtherCAT-Modul
#
# $Id$
#
#----------------------------------------------------------------
MSRDIR = /vol/projekte/msr_messen_steuern_regeln
KERNELDIR = $(MSRDIR)/linux/kernel/2.4.20/include/linux-2.4.20.CX1100-rthal5
CFLAGS = -O2 -Wall -Wuninitialized -D__KERNEL__ -DMODULE -I$(KERNELDIR)/include
MODULE = ec_mini_mod.o
SRC = ec_mini.c
OBJ = $(SRC:.c=.o)
#----------------------------------------------------------------
all: .depend Makefile $(MODULE)
$(MODULE): $(OBJ)
$(LD) -r $(OBJ) -o $@
#----------------------------------------------------------------
depend .depend dep:
$(CC) $(CFLAGS) -M $(SRC) > .depend
ifeq (.depend,$(wildcard .depend))
include .depend
endif
#----------------------------------------------------------------
clean:
rm -f *.o *~ core .depend
#----------------------------------------------------------------

345
mini/ec_mini.c Normal file
View File

@@ -0,0 +1,345 @@
/******************************************************************************
*
* ec_mini.c
*
* Minimalmodul für EtherCAT
*
* $Id$
*
******************************************************************************/
#include <linux/module.h>
#include <linux/tqueue.h>
#include <linux/slab.h>
#include <linux/delay.h>
#include "../drivers/ec_master.h"
#include "../drivers/ec_device.h"
#include "../drivers/ec_types.h"
#include "../drivers/ec_dbg.h"
extern EtherCAT_device_t rtl_ecat_dev;
//static EtherCAT_master_t *ecat_master = NULL;
#if 0
static EtherCAT_slave_t ecat_slaves[] =
{
// Block 1
ECAT_INIT_SLAVE(Beckhoff_EK1100),
ECAT_INIT_SLAVE(Beckhoff_EL4102),
ECAT_INIT_SLAVE(Beckhoff_EL3162),
ECAT_INIT_SLAVE(Beckhoff_EL1014),
ECAT_INIT_SLAVE(Beckhoff_EL2004),
ECAT_INIT_SLAVE(Beckhoff_EL3102),
ECAT_INIT_SLAVE(Beckhoff_EL4102),
ECAT_INIT_SLAVE(Beckhoff_EL4102),
ECAT_INIT_SLAVE(Beckhoff_EL4102),
ECAT_INIT_SLAVE(Beckhoff_EL3162),
ECAT_INIT_SLAVE(Beckhoff_EL3162),
ECAT_INIT_SLAVE(Beckhoff_EL3162),
ECAT_INIT_SLAVE(Beckhoff_EL3102),
ECAT_INIT_SLAVE(Beckhoff_EL3102),
ECAT_INIT_SLAVE(Beckhoff_EL2004),
ECAT_INIT_SLAVE(Beckhoff_EL2004),
ECAT_INIT_SLAVE(Beckhoff_EL2004),
ECAT_INIT_SLAVE(Beckhoff_EL2004),
// Block 2
ECAT_INIT_SLAVE(Beckhoff_EK1100),
ECAT_INIT_SLAVE(Beckhoff_EL4102),
ECAT_INIT_SLAVE(Beckhoff_EL1014),
ECAT_INIT_SLAVE(Beckhoff_EL3162),
ECAT_INIT_SLAVE(Beckhoff_EL2004),
ECAT_INIT_SLAVE(Beckhoff_EL3102),
// Block 3
ECAT_INIT_SLAVE(Beckhoff_EK1100),
ECAT_INIT_SLAVE(Beckhoff_EL1014),
ECAT_INIT_SLAVE(Beckhoff_EL1014),
ECAT_INIT_SLAVE(Beckhoff_EL1014),
ECAT_INIT_SLAVE(Beckhoff_EL1014),
ECAT_INIT_SLAVE(Beckhoff_EL1014),
ECAT_INIT_SLAVE(Beckhoff_EL2004),
ECAT_INIT_SLAVE(Beckhoff_EL2004),
ECAT_INIT_SLAVE(Beckhoff_EL2004),
ECAT_INIT_SLAVE(Beckhoff_EL2004),
ECAT_INIT_SLAVE(Beckhoff_EL1014),
ECAT_INIT_SLAVE(Beckhoff_EL1014),
ECAT_INIT_SLAVE(Beckhoff_EL1014)
};
#define ECAT_SLAVES_COUNT (sizeof(ecat_slaves) / sizeof(EtherCAT_slave_t))
#endif
double value;
int dig1;
/******************************************************************************
*
* Function: next2004
*
*****************************************************************************/
#if 0
static int next2004(int *wrap)
{
static int i = 0;
unsigned int j = 0;
*wrap = 0;
for (j = 0; j < ECAT_SLAVES_COUNT; j++)
{
i++;
i %= ECAT_SLAVES_COUNT;
if (i == 0) *wrap = 1;
if (ecat_slaves[i].desc == Beckhoff_EL2004)
{
return i;
}
}
return -1;
}
#endif
/******************************************************************************
*
* Function: msr_controller
*
* Beschreibung: Zyklischer Prozess
*
*****************************************************************************/
#if 0
void msr_controller()
{
static int ms = 0;
static int cnt = 0;
static unsigned long int k = 0;
static int firstrun = 1;
static int klemme = 12;
static int kanal = 0;
static int up_down = 0;
int wrap = 0;
ms++;
ms %= 1000;
#if 0
ecat_tx_delay = ((unsigned int) (100000 / HZ) * (ecat_master->dev->tx_time-k))
/ (current_cpu_data.loops_per_jiffy / 10);
ecat_rx_delay = ((unsigned int) (100000 / HZ) * (ecat_master->dev->rx_time-k))
/ (current_cpu_data.loops_per_jiffy / 10);
rx_intr = ecat_master->dev->rx_intr_cnt;
tx_intr = ecat_master->dev->tx_intr_cnt;
total_intr = ecat_master->dev->intr_cnt;
#endif
// Prozessdaten lesen
if (!firstrun)
{
EtherCAT_read_process_data(ecat_master);
// Daten lesen und skalieren
value = EtherCAT_read_value(&ecat_master->slaves[5], 0) / 3276.7;
dig1 = EtherCAT_read_value(&ecat_master->slaves[3], 0);
}
// Daten schreiben
EtherCAT_write_value(&ecat_master->slaves[4], 0, ms > 500 ? 1 : 0);
EtherCAT_write_value(&ecat_master->slaves[4], 1, ms > 500 ? 0 : 1);
EtherCAT_write_value(&ecat_master->slaves[4], 2, ms > 500 ? 0 : 1);
EtherCAT_write_value(&ecat_master->slaves[4], 3, ms > 500 ? 1 : 0);
if (cnt++ > 20)
{
cnt = 0;
if (++kanal > 3)
{
kanal = 0;
klemme = next2004(&wrap);
if (wrap == 1)
{
if (up_down == 1) up_down = 0;
else up_down = 1;
}
}
}
if (klemme >= 0)
EtherCAT_write_value(&ecat_master->slaves[klemme], kanal,up_down);
//EtherCAT_write_value(&ecat_master->slaves[13], 1, ms > 500 ? 0 : 1);
//EtherCAT_write_value(&ecat_master->slaves[14], 2, ms > 500 ? 0 : 1);
//EtherCAT_write_value(&ecat_master->slaves[15], 3, ms > 500 ? 1 : 0);
// Prozessdaten schreiben
rdtscl(k);
EtherCAT_write_process_data(ecat_master);
firstrun = 0;
}
#endif
/******************************************************************************
*
* Function: init
*
******************************************************************************/
//#define ECAT_OPEN
int init()
{
#ifdef ECAT_OPEN
int rv = -1;
#endif
EC_DBG(KERN_INFO "=== Starting Minimal EtherCAT environment... ===\n");
EtherCAT_device_debug(&rtl_ecat_dev);
//mdelay(5000);
#ifdef ECAT_OPEN
EC_DBG("Opening EtherCAT device.\n");
// HIER PASSIERT DER FEHLER:
if (EtherCAT_device_open(&rtl_ecat_dev) < 0)
{
EC_DBG(KERN_ERR "msr_modul: Could not initialize EtherCAT NIC.\n");
goto out_nothing;
}
if (!rtl_ecat_dev.dev) // Es gibt kein EtherCAT-Device
{
EC_DBG(KERN_ERR "msr_modul: No EtherCAT device!\n");
goto out_close;
}
#endif
#if 0
// EtherCAT-Master und Slaves initialisieren
EC_DBG("Initialising EtherCAT master\n");
if ((ecat_master = (EtherCAT_master_t *) kmalloc(sizeof(EtherCAT_master_t), GFP_KERNEL)) == 0)
{
EC_DBG(KERN_ERR "msr_modul: Could not alloc memory for EtherCAT master!\n");
goto out_close;
}
if (EtherCAT_master_init(ecat_master, &rtl_ecat_dev) < 0)
{
EC_DBG(KERN_ERR "EtherCAT could not init master!\n");
goto out_master;
}
#endif
#if 0
EC_DBG("Checking EtherCAT slaves.\n");
if (EtherCAT_check_slaves(ecat_master, ecat_slaves, ECAT_SLAVES_COUNT) != 0)
{
EC_DBG(KERN_ERR "EtherCAT: Could not init slaves!\n");
goto out_masterclear;
}
EC_DBG("Activating all EtherCAT slaves.\n");
if (EtherCAT_activate_all_slaves(ecat_master) != 0)
{
EC_DBG(KERN_ERR "EtherCAT: Could not activate slaves!\n");
goto out_masterclear;
}
// Zyklischen Aufruf starten
EC_DBG("Starting cyclic sample thread.\n");
EtherCAT_write_process_data(ecat_master);
EC_DBG("Initialised sample thread.\n");
#endif
EC_DBG(KERN_INFO "=== Minimal EtherCAT environment started. ===\n");
return 0;
#if 0
out_masterclear:
EC_DBG(KERN_INFO "Clearing EtherCAT master.\n");
EtherCAT_master_clear(ecat_master);
#endif
#if 0
out_master:
EC_DBG(KERN_INFO "Freeing EtherCAT master.\n");
kfree(ecat_master);
#endif
#ifdef ECAT_OPEN
out_close:
EC_DBG(KERN_INFO "Closing device.\n");
EtherCAT_device_close(&rtl_ecat_dev);
out_nothing:
return rv;
#endif
}
/******************************************************************************
*
* Function: cleanup
*
******************************************************************************/
void cleanup()
{
EC_DBG(KERN_INFO "=== Stopping Minimal EtherCAT environment... ===\n");
// Noch einmal lesen
//EC_DBG(KERN_INFO "Reading process data.\n");
//EtherCAT_read_process_data(ecat_master);
#if 0
if (ecat_master)
{
#if 0
EC_DBG(KERN_INFO "Deactivating slaves.\n");
EtherCAT_deactivate_all_slaves(ecat_master);
#endif
EC_DBG(KERN_INFO "Clearing EtherCAT master.\n");
EtherCAT_master_clear(ecat_master);
EC_DBG(KERN_INFO "Freeing EtherCAT master.\n");
kfree(ecat_master);
ecat_master = NULL;
}
#endif
#ifdef ECAT_OPEN
EC_DBG(KERN_INFO "Closing device.\n");
EtherCAT_device_close(&rtl_ecat_dev);
#endif
EC_DBG(KERN_INFO "=== Minimal EtherCAT environment stopped. ===\n");
}
/*****************************************************************************/
MODULE_LICENSE("GPL");
MODULE_AUTHOR ("Florian Pose <fp@igh-essen.com>");
MODULE_DESCRIPTION ("Minimal EtherCAT environment");
module_init(init);
module_exit(cleanup);
/*****************************************************************************/

82
rs232dbg/Makefile Normal file
View File

@@ -0,0 +1,82 @@
#IgH
KERNELDIR = /vol/projekte/msr_messen_steuern_regeln/linux/kernel/2.4.20/include/linux-2.4.20.CX1100-rthal5
RTAIDIR = /vol/projekte/msr_messen_steuern_regeln/linux/kernel/2.4.20/include/rtai-24.1.13
RTLIBDIR = rt_lib
#euler-nottuln
#KERNELDIR = /usr/src/linux
#RTAIDIR = /usr/src/rtai
#patra
#KERNELDIR = /usr/src/linux-2.4.20.CX1100-rthal5
#RTAIDIR = /usr/src/rtai-24.1.13
RTLIBDIR=rt_lib
#include $(KERNELDIR)/.config
#CFLAGS = -DRTAI -D__KERNEL__ -DMODULE -I$(KERNELDIR)/include -I$(RTAIDIR)/include -I$(RTLIBDIR)/msr-include \
# -Wall -Wstrict-prototypes -Wno-trigraphs -O2 -fno-strict-aliasing -fno-common -fomit-frame-pointer \
# -pipe -mpreferred-stack-boundary=2 -march=i686 -nostdinc -iwithprefix include
CFLAGS = -O2 -Wall -Wuninitialized -D__KERNEL__ -DMODULE -I$(KERNELDIR)/include -D_RTAI -I$(RTAIDIR)/include -I$(RTLIBDIR)/msr-include
#CFLAGS += -DSIMULATION
#LDFLAGS =
#VPATH = $(RTLIBDIR)/
TARGET = sdbg
MODULE = $(TARGET).o
SRC = rs232dbg.c aip_com.c
#Suchpfad für die Dateien aus dem RT-Lib-Verzeichnis
VPATH = $(RTLIBDIR)/msr-core:$(RTLIBDIR)/msr-control:$(RTLIBDIR)/msr-math:$(RTLIBDIR)/msr-misc:$(RTLIBDIR)/msr-utils
#Datei aus dem RT-Libverzeichnis für dies Projekt
RTSRC =
ALLSRC = $(SRC) $(RTSRC)
OBJS = $(ALLSRC:.c=.o)
all: .depend $(TARGET).o Makefile
$(TARGET).o: $(SRC:.c=.o) $(RTSRC:.c=.o)
$(LD) -r $(OBJS) -o $@ $(LDFLAGS)
install: msr_modul.o
lsmod | grep cif-rtai >/dev/null 2>&1 && sudo rmmod msr_modul || true
sudo insmod msr_modul.o
clean:
rm -f *.o *~ core .depend
depend .depend dep:
$(CC) $(CFLAGS) -M *.c > $@
ifeq (.depend,$(wildcard .depend))
include .depend
endif
#all: msr_module.o
#
#msr_io.o: msr_io.c msr_io.h
# $(CC) $(CFLAGS) -c -o $@ $<
#
#msr_module.o: msr_io.o
# $(LD) -r -o $@ $^
#
# $(CC) -c $(CFLAGS) $(CPPFLAGS) -o $@ $<
#clean:
# rm -f *.o *~ core

847
rs232dbg/aip_com.c Normal file

File diff suppressed because it is too large Load Diff

159
rs232dbg/aip_com.h Normal file
View File

@@ -0,0 +1,159 @@
/**************************************************************************************************
*
* aip_com.h
*
* Macros für Kommunikation über serielle Schnittstelle
* Basiert auf rt_com.h von rtai !! (siehe unten)
*
*
* Autor: Wilhelm Hagemeister
*
* (C) Copyright IgH 2002
* Ingenieurgemeinschaft IgH
* Heinz-Bäcker Str. 34
* D-45356 Essen
* Tel.: +49 201/61 99 31
* Fax.: +49 201/61 98 36
* E-mail: hm@igh-essen.com
*
*
* $RCSfile: aip_com.h,v $
* $Revision: 1.1 $
* $Author: hm $
* $Date: 2004/09/30 15:50:32 $
* $State: Exp $
*
*
*
*
*
*
*
*
*
**************************************************************************************************/
/** rt_com
* ======
*
* RT-Linux kernel module for communication across serial lines.
*
* Copyright (C) 1997 Jens Michaelsen
* Copyright (C) 1997-2000 Jochen Kupper
* Copyright (C) 2002 Giuseppe Renoldi
*
* This program is free software; you can redistribute it and/or
* modify it under the terms of the GNU General Public License as
* published by the Free Software Foundation; either version 2 of the
* License, or (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file License. if not, write to the
* Free Software Foundation, Inc., 59 Temple Place, Suite 330, Boston,
* MA 02111-1307, USA.
*
* $Id: aip_com.h,v 1.1 2004/09/30 15:50:32 hm Exp $ */
#ifndef AIP_COM_H
#define AIP_COM_H
/** This is the interface definition of the plain rt_com API.
*
* This should be all you need to use rt_com within your real-time
* kernel module.
*
* (When POSIX is done, we will reference the appropriate header
* here - probably depending on a flag.) */
int init_aip_com(void); //Hm, IgH
void cleanup_aip_com(void); //Hm, IgH
/** specify hardware parameters, set-up communication parameters */
extern int rt_com_hwsetup( unsigned int ttyS, int base, int irq );
extern int rt_com_setup( unsigned int ttyS, int baud, int mode,
unsigned int parity, unsigned int stopbits,
unsigned int wordlength, int fifotrig );
/** read/write from/to input/output buffer */
extern int rt_com_read( unsigned int, char *, int );
extern int rt_com_write( unsigned int ttyS, char *buffer, int count );
/** clear input or output buffer */
extern int rt_com_clear_input( unsigned int ttyS );
extern int rt_com_clear_output( unsigned int ttyS );
/** read input signal from modem (CTS,DSR,RI,DCD), set output signal
* for modem control (DTR,RTS) */
extern int rt_com_read_modem( unsigned int ttyS, int signal );
extern int rt_com_write_modem( unsigned int ttyS, int signal, int value );
/** functioning mode and fifo trigger setting */
extern int rt_com_set_mode( unsigned int ttyS, int mode);
extern int rt_com_set_fifotrig( unsigned int ttyS, int fifotrig);
/** return last error detected */
extern int rt_com_error( unsigned int ttyS );
/** size of internal queues, this is constant during module lifetime */
extern unsigned int rt_com_buffersize;
#define rt_com_set_param rt_com_hwsetup
#define rt_com_setup_old(a,b,c,d,e) rt_com_setup((a),(b),0,(c),(d),(e),-1)
/** functioning modes */
#define RT_COM_NO_HAND_SHAKE 0x00
#define RT_COM_DSR_ON_TX 0x01
#define RT_COM_HW_FLOW 0x02
/** parity flags */
#define RT_COM_PARITY_EVEN 0x18
#define RT_COM_PARITY_NONE 0x00
#define RT_COM_PARITY_ODD 0x08
#define RT_COM_PARITY_HIGH 0x28
#define RT_COM_PARITY_LOW 0x38
/* FIFO Control */
#define RT_COM_FIFO_DISABLE 0x00
#define RT_COM_FIFO_SIZE_1 0x00
#define RT_COM_FIFO_SIZE_4 0x40
#define RT_COM_FIFO_SIZE_8 0x80
#define RT_COM_FIFO_SIZE_14 0xC0
/** rt_com_write_modem masks */
#define RT_COM_DTR 0x01
#define RT_COM_RTS 0x02
/** rt_com_read_modem masks */
#define RT_COM_CTS 0x10
#define RT_COM_DSR 0x20
#define RT_COM_RI 0x40
#define RT_COM_DCD 0x80
/** rt_com_error masks */
#define RT_COM_BUFFER_FULL 0x01
#define RT_COM_OVERRUN_ERR 0x02
#define RT_COM_PARITY_ERR 0x04
#define RT_COM_FRAMING_ERR 0x08
#define RT_COM_BREAK 0x10
#endif /* RT_COM_H */
/**
* Local Variables:
* mode: C
* c-file-style: "Stroustrup"
* End:
*/

206
rs232dbg/aip_comP.h Normal file
View File

@@ -0,0 +1,206 @@
/**
* rt_com
* ======
*
* RT-Linux kernel module for communication across serial lines.
*
* Copyright (C) 1997 Jens Michaelsen
* Copyright (C) 1997-2000 Jochen Kupper
* Copyright (C) 1999 Hua Mao <hmao@nmt.edu>
*
* This program is free software; you can redistribute it and/or
* modify it under the terms of the GNU General Public License as
* published by the Free Software Foundation; either version 2 of the
* License, or (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file License. if not, write to the
* Free Software Foundation, Inc., 59 Temple Place, Suite 330, Boston,
* MA 02111-1307, USA.
*/
#ifndef AIP_COM_P_H
#define AIP_COM_P_H
#define RT_COM_NAME "rt_com(aip)" //Hm, IgH
/* input/ouput buffer (FIFO) sizes */
#define RT_COM_BUF_SIZ 2048 //256 // MUST BE ONLY POWER OF 2 !!
/* amount of free space on input buffer for RTS reset */
#define RT_COM_BUF_LOW (RT_COM_BUF_SIZ / 3)
/* amount of free space on input buffer for RTS set */
#define RT_COM_BUF_HI (RT_COM_BUF_SIZ * 2 / 3)
/* limit of free space on input buffer for buffer full error */
#define RT_COM_BUF_FULL 20
/* usage flags */
#define RT_COM_PORT_FREE 0x00
#define RT_COM_PORT_INUSE 0x01
#define RT_COM_PORT_SETUP 0x02
/* Some hardware description */
#define RT_COM_BASE_BAUD 115200
/** Interrupt Service Routines
* These are private functions */
static void rt_com0_isr( void );
static void rt_com1_isr( void );
/** Interrupt handling
*
* Define internal convinience macros for interrupt handling, so we
* get rid of the system dependencies.
*/
//#define rt_com_irq_off( state ) do{}while(0) //rt_global_save_flags( &state ); rt_global_cli() schreiben und lesen sowieso in IRQ Hm
//#define rt_com_irq_on(state) do{}while(0) //rt_global_restore_flags( state )
#define rt_com_irq_off( state ) rt_global_save_flags( &state ); rt_global_cli()
#define rt_com_irq_on(state) rt_global_restore_flags( state )
#define rt_com_request_irq( irq, isr ) rt_request_global_irq( irq, isr ); rt_enable_irq( irq );
#define rt_com_free_irq( irq ) rt_free_global_irq( irq )
/* port register offsets */
#define RT_COM_RXB 0x00
#define RT_COM_TXB 0x00
#define RT_COM_IER 0x01
#define RT_COM_IIR 0x02
#define RT_COM_FCR 0x02
#define RT_COM_LCR 0x03
#define RT_COM_MCR 0x04
#define RT_COM_LSR 0x05
#define RT_COM_MSR 0x06
#define RT_COM_DLL 0x00
#define RT_COM_DLM 0x01
/** MCR Modem Control Register masks */
#define MCR_DTR 0x01 // Data Terminal Ready
#define MCR_RTS 0x02 // Request To Send
#define MCR_OUT1 0x04
#define MCR_OUT2 0x08
#define MCR_LOOP 0x10
#define MCR_AFE 0x20 // AutoFlow Enable
/** IER Interrupt Enable Register masks */
#define IER_ERBI 0x01 // Enable Received Data Available Interrupt
#define IER_ETBEI 0x02 // Enable Transmitter Holding Register
// Empty Interrupt
#define IER_ELSI 0x04 // Enable Receiver Line Status Interrupt
#define IER_EDSSI 0x08 // Enable Modem Status Interrupt
/** MSR Modem Status Register masks */
#define MSR_DELTA_CTS 0x01
#define MSR_DELTA_DSR 0x02
#define MSR_TERI 0x04
#define MSR_DELTA_DCD 0x08
#define MSR_CTS 0x10
#define MSR_DSR 0x20
#define MSR_RI 0x40
#define MSR_DCD 0x80
/** LSR Line Status Register masks */
#define LSR_DATA_READY 0x01
#define LSR_OVERRUN_ERR 0x02
#define LSR_PARITY_ERR 0x04
#define LSR_FRAMING_ERR 0x08
#define LSR_BREAK 0x10
#define LSR_THRE 0x20 // Transmitter Holding Register
#define LSR_TEMT 0x40 // Transmitter Empty
/** FCR FIFO Control Register masks */
#define FCR_FIFO_ENABLE 0x01
#define FCR_INPUT_FIFO_RESET 0x02
#define FCR_OUTPUT_FIFO_RESET 0x04
/** data buffer
*
* Used for buffering of input and output data. Two buffers per port
* (one for input, one for output). Organized as a FIFO */
struct rt_buf_struct{
unsigned int head;
unsigned int tail;
char buf[ RT_COM_BUF_SIZ ];
};
/** Port data
*
* Internal information structure containing all data for a port. One
* structure for every port.
*
* Contains all current setup parameters and all data currently
* buffered by rt_com.
*
* mode (functioning mode)
* possible values:
* - RT_COM_DSR_ON_TX - for standard functioning mode (DSR needed on TX)
* - RT_COM_NO_HAND_SHAKE - for comunication without hand shake signals
* (only RXD-TXD-GND)
* - RT_COM_HW_FLOW - for hardware flow control (RTS-CTS)
* Of course RT_COM_DSR_ON_TX and RT_COM_NO_HAND_SHAKE cannot be
* sppecified at the same time.
*
* NOTE: When you select a mode that uses hand shake signals pay
* attention that no input signals (CTS,DSR,RI,DCD) must be
* floating.
*
* used (usage flag)
* possible values:
* - RT_COM_PORT_INUSE - port region requested by init_module
* - RT_COM_PORT_FREE - port region requested by rt_com_set_param
* - RT_COM_PORT_SETUP - port parameters are setup,
* don't specify at compile time !
*
* error
* last error detected
*
* ier (interrupt enable register)
* copy of IER chip register, last value set by rt_com.
*
* mcr (modem control register)
* copy of the MCR internal register
*/
struct rt_com_struct{
int baud_base;
int port;
int irq;
void (*isr)(void);
int baud;
unsigned int wordlength;
unsigned int parity;
unsigned int stopbits;
int mode;
int fifotrig;
int used;
int error;
int type;
int ier;
int mcr;
struct rt_buf_struct ibuf;
struct rt_buf_struct obuf;
};
#endif /* RT_COM_P_H */
/**
* Local Variables:
* mode: C
* c-file-style: "Stroustrup"
* End:
*/

136
rs232dbg/rs232dbg.c Normal file
View File

@@ -0,0 +1,136 @@
/******************************************************************************
*
* msr_io.c
*
* Debugging über Serielle Schnittstelle
*
* Autoren: Wilhelm Hagemeister
*
* $LastChangedDate: 2005-09-16 17:45:46 +0200 (Fri, 16 Sep 2005) $
* $Author: hm $
*
* (C) Copyright IgH 2005
* Ingenieurgemeinschaft IgH
* Heinz-Bäcker Str. 34
* D-45356 Essen
* Tel.: +49 201/61 99 31
* Fax.: +49 201/61 98 36
* E-mail: sp@igh-essen.com
*
* /bin/setserial /dev/ttyS0 uart none
* /bin/setserial /dev/ttyS1 uart none
*
*
******************************************************************************/
/*--Includes-----------------------------------------------------------------*/
#include <linux/module.h>
#include <linux/tqueue.h>
#include <linux/slab.h>
#include <linux/delay.h>
#include <linux/spinlock.h>
#include "aip_com.h"
#include "rs232dbg.h"
#include <rtai.h>
spinlock_t rs232wlock;
void SDBG_print(const char *format, ...)
{
va_list argptr;
static char buf[1024];
int len;
if(format != NULL) {
va_start(argptr,format);
len = vsnprintf(buf, sizeof(buf), format, argptr);
if (len > 0 && buf[len - 1] == '\n') len--; // fp
rt_com_write(0,buf,len);
rt_com_write(0,"\r\n",2);
va_end(argptr);
}
}
/*
void SDBG_print(unsigned char *buf)
{
static int counter = 0;
unsigned char cbuf[20];
unsigned long flags;
// flags = rt_spin_lock_irqsave (&rs232wlock);
sprintf(cbuf,"%0d -- ",counter);
rt_com_write(0,cbuf,strlen(cbuf));
rt_com_write(0,buf,strlen(buf));
rt_com_write(0,"\r\n",2);
counter++;
counter %= 10; //did we miss frames ??
// rt_spin_unlock_irqrestore (&rs232wlock,flags);
}
*/
/*
*******************************************************************************
*
* Function: msr_init
*
* Beschreibung: MSR initialisieren
*
* Parameter:
*
* Rückgabe:
*
* Status: exp
*
*******************************************************************************
*/
int msr_init(void)
{
spin_lock_init (&rs2323wlock);
printk("starting RS232 Setup\n");
if(init_aip_com())
{
printk("RS232 Setup failed\n");
return -1;
}
SDBG_print("Hello Word, Serial Debugger started...");
mdelay(10);
return 0;
}
/*
*******************************************************************************
*
* Function: msr_io_cleanup
*
* Beschreibung: Aufräumen
*
* Parameter:
*
* Rückgabe:
*
* Status: exp
*
*******************************************************************************
*/
void msr_io_cleanup(void)
{
cleanup_aip_com();
}
/*---Treiber-Einsprungspunkte etc.-------------------------------------------*/
MODULE_LICENSE("GPL");
module_init(msr_init);
module_exit(msr_io_cleanup);
/*---Ende--------------------------------------------------------------------*/

7
rs232dbg/rs232dbg.h Normal file
View File

@@ -0,0 +1,7 @@
#ifndef RS232DBG_H
#define RS232DBG_H
void SDBG_print(const char *format, ...);
#endif

83
rt/Makefile Normal file
View File

@@ -0,0 +1,83 @@
#IgH
KERNELDIR = /vol/projekte/msr_messen_steuern_regeln/linux/kernel/2.4.20/include/linux-2.4.20.CX1100-rthal5
RTAIDIR = /vol/projekte/msr_messen_steuern_regeln/linux/kernel/2.4.20/include/rtai-24.1.13
RTLIBDIR = rt_lib
#euler-nottuln
#KERNELDIR = /usr/src/linux
#RTAIDIR = /usr/src/rtai
#patra
#KERNELDIR = /usr/src/linux-2.4.20.CX1100-rthal5
#RTAIDIR = /usr/src/rtai-24.1.13
RTLIBDIR=rt_lib
#include $(KERNELDIR)/.config
#CFLAGS = -DRTAI -D__KERNEL__ -DMODULE -I$(KERNELDIR)/include -I$(RTAIDIR)/include -I$(RTLIBDIR)/msr-include \
# -Wall -Wstrict-prototypes -Wno-trigraphs -O2 -fno-strict-aliasing -fno-common -fomit-frame-pointer \
# -pipe -mpreferred-stack-boundary=2 -march=i686 -nostdinc -iwithprefix include
CFLAGS = -O2 -Wall -Wuninitialized -D__KERNEL__ -DMODULE -DSERIALDEBUG -DMSR_NO_PROC -I$(KERNELDIR)/include -D_RTAI -I$(RTAIDIR)/include -I$(RTLIBDIR)/msr-include
#CFLAGS += -DSIMULATION
#LDFLAGS =
#VPATH = $(RTLIBDIR)/
TARGET = msr_modul
MODULE = $(TARGET).o
SRC = msr_io.c
#Suchpfad für die Dateien aus dem RT-Lib-Verzeichnis
VPATH = $(RTLIBDIR)/msr-core:$(RTLIBDIR)/msr-control:$(RTLIBDIR)/msr-math:$(RTLIBDIR)/msr-misc:$(RTLIBDIR)/msr-utils
#Datei aus dem RT-Libverzeichnis für dies Projekt
RTSRC = msr_main.c msr_lists.c msr_charbuf.c msr_reg.c msr_interpreter.c msr_utils.c msr_messages.c msr_base64.c msr_proc.c msr_error_reg.c
ALLSRC = $(SRC) $(RTSRC)
OBJS = $(ALLSRC:.c=.o)
all: .depend $(TARGET).o Makefile
$(TARGET).o: $(SRC:.c=.o) $(RTSRC:.c=.o)
$(LD) -r $(OBJS) -o $@ $(LDFLAGS)
install: msr_modul.o
lsmod | grep cif-rtai >/dev/null 2>&1 && sudo rmmod msr_modul || true
sudo insmod msr_modul.o
clean:
rm -f *.o *~ core .depend
depend .depend dep:
$(CC) $(CFLAGS) -M *.c > $@
ifeq (.depend,$(wildcard .depend))
include .depend
endif
#all: msr_module.o
#
#msr_io.o: msr_io.c msr_io.h
# $(CC) $(CFLAGS) -c -o $@ $<
#
#msr_module.o: msr_io.o
# $(LD) -r -o $@ $^
#
# $(CC) -c $(CFLAGS) $(CPPFLAGS) -o $@ $<
#clean:
# rm -f *.o *~ core

57
rt/TAGS Normal file
View File

@@ -0,0 +1,57 @@
_msr_io.c,315
# define __KERNEL__44,1091
# define MODULE47,1134
spinlock_t data_lock 64,1449
#define PB_CARDS 79,1926
} card[91,2142
void x_PB_io(109,2505
int msr_io_init(151,3460
#define FIFO_BUF 157,3532
int msr_io_register(235,5684
int msr_io_write(261,6090
int msr_io_read(363,8522
void msr_io_cleanup(400,9200
_msr_io.h,100
#define _MSR_IO_H_119,3261
struct cif_in_t cif_in_t128,3512
struct cif_out_t cif_out_t135,3664
cif-rtai-io.h,0
msr_io.c,559
RT_TASK check_running;54,1293
RT_TASK process_image;55,1316
SEM data_lock;57,1340
#define PARAM_FILENO 60,1381
#define CVT_FILENO 61,1405
#define MSG_FILENO 62,1427
#define PB_CARDS 64,1449
} card[78,1692
int msr_print(80,1711
inline int msr_print_error(97,1982
inline int msr_print_info(106,2138
inline int msr_print_warn(115,2294
void x_PB_io(140,2830
void process_thread(145,2909
void check_thread(254,6015
void msr_io_cleanup(343,8029
int msr_init(374,8740
#define FIFO_BUF 389,9019
#define TIMERTICS 396,9180
#define MSG_BUF 397,9245
msr_io.h,363
#define _AIM_GLOBALS_H_35,698
struct P101_In P101_In37,723
struct P201_In P201_In45,859
struct P301_In P301_In50,940
struct P101_Out P101_Out56,1022
struct P201_Out P201_Out62,1120
struct P301_Out P301_Out65,1161
struct IMO_to_dSPACE IMO_to_dSPACE69,1203
struct dSPACE_to_IMO dSPACE_to_IMO76,1338
} IMO;99,1765
} cvt;128,2230
} param;131,2247

851
rt/aip_com.c Normal file

File diff suppressed because it is too large Load Diff

159
rt/aip_com.h Normal file
View File

@@ -0,0 +1,159 @@
/**************************************************************************************************
*
* aip_com.h
*
* Macros für Kommunikation über serielle Schnittstelle
* Basiert auf rt_com.h von rtai !! (siehe unten)
*
*
* Autor: Wilhelm Hagemeister
*
* (C) Copyright IgH 2002
* Ingenieurgemeinschaft IgH
* Heinz-Bäcker Str. 34
* D-45356 Essen
* Tel.: +49 201/61 99 31
* Fax.: +49 201/61 98 36
* E-mail: hm@igh-essen.com
*
*
* $RCSfile: aip_com.h,v $
* $Revision: 1.1 $
* $Author: hm $
* $Date: 2004/09/30 15:50:32 $
* $State: Exp $
*
*
*
*
*
*
*
*
*
**************************************************************************************************/
/** rt_com
* ======
*
* RT-Linux kernel module for communication across serial lines.
*
* Copyright (C) 1997 Jens Michaelsen
* Copyright (C) 1997-2000 Jochen Kupper
* Copyright (C) 2002 Giuseppe Renoldi
*
* This program is free software; you can redistribute it and/or
* modify it under the terms of the GNU General Public License as
* published by the Free Software Foundation; either version 2 of the
* License, or (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file License. if not, write to the
* Free Software Foundation, Inc., 59 Temple Place, Suite 330, Boston,
* MA 02111-1307, USA.
*
* $Id: aip_com.h,v 1.1 2004/09/30 15:50:32 hm Exp $ */
#ifndef AIP_COM_H
#define AIP_COM_H
/** This is the interface definition of the plain rt_com API.
*
* This should be all you need to use rt_com within your real-time
* kernel module.
*
* (When POSIX is done, we will reference the appropriate header
* here - probably depending on a flag.) */
int init_aip_com(void); //Hm, IgH
void cleanup_aip_com(void); //Hm, IgH
/** specify hardware parameters, set-up communication parameters */
extern int rt_com_hwsetup( unsigned int ttyS, int base, int irq );
extern int rt_com_setup( unsigned int ttyS, int baud, int mode,
unsigned int parity, unsigned int stopbits,
unsigned int wordlength, int fifotrig );
/** read/write from/to input/output buffer */
extern int rt_com_read( unsigned int, char *, int );
extern int rt_com_write( unsigned int ttyS, char *buffer, int count );
/** clear input or output buffer */
extern int rt_com_clear_input( unsigned int ttyS );
extern int rt_com_clear_output( unsigned int ttyS );
/** read input signal from modem (CTS,DSR,RI,DCD), set output signal
* for modem control (DTR,RTS) */
extern int rt_com_read_modem( unsigned int ttyS, int signal );
extern int rt_com_write_modem( unsigned int ttyS, int signal, int value );
/** functioning mode and fifo trigger setting */
extern int rt_com_set_mode( unsigned int ttyS, int mode);
extern int rt_com_set_fifotrig( unsigned int ttyS, int fifotrig);
/** return last error detected */
extern int rt_com_error( unsigned int ttyS );
/** size of internal queues, this is constant during module lifetime */
extern unsigned int rt_com_buffersize;
#define rt_com_set_param rt_com_hwsetup
#define rt_com_setup_old(a,b,c,d,e) rt_com_setup((a),(b),0,(c),(d),(e),-1)
/** functioning modes */
#define RT_COM_NO_HAND_SHAKE 0x00
#define RT_COM_DSR_ON_TX 0x01
#define RT_COM_HW_FLOW 0x02
/** parity flags */
#define RT_COM_PARITY_EVEN 0x18
#define RT_COM_PARITY_NONE 0x00
#define RT_COM_PARITY_ODD 0x08
#define RT_COM_PARITY_HIGH 0x28
#define RT_COM_PARITY_LOW 0x38
/* FIFO Control */
#define RT_COM_FIFO_DISABLE 0x00
#define RT_COM_FIFO_SIZE_1 0x00
#define RT_COM_FIFO_SIZE_4 0x40
#define RT_COM_FIFO_SIZE_8 0x80
#define RT_COM_FIFO_SIZE_14 0xC0
/** rt_com_write_modem masks */
#define RT_COM_DTR 0x01
#define RT_COM_RTS 0x02
/** rt_com_read_modem masks */
#define RT_COM_CTS 0x10
#define RT_COM_DSR 0x20
#define RT_COM_RI 0x40
#define RT_COM_DCD 0x80
/** rt_com_error masks */
#define RT_COM_BUFFER_FULL 0x01
#define RT_COM_OVERRUN_ERR 0x02
#define RT_COM_PARITY_ERR 0x04
#define RT_COM_FRAMING_ERR 0x08
#define RT_COM_BREAK 0x10
#endif /* RT_COM_H */
/**
* Local Variables:
* mode: C
* c-file-style: "Stroustrup"
* End:
*/

206
rt/aip_comP.h Normal file
View File

@@ -0,0 +1,206 @@
/**
* rt_com
* ======
*
* RT-Linux kernel module for communication across serial lines.
*
* Copyright (C) 1997 Jens Michaelsen
* Copyright (C) 1997-2000 Jochen Kupper
* Copyright (C) 1999 Hua Mao <hmao@nmt.edu>
*
* This program is free software; you can redistribute it and/or
* modify it under the terms of the GNU General Public License as
* published by the Free Software Foundation; either version 2 of the
* License, or (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file License. if not, write to the
* Free Software Foundation, Inc., 59 Temple Place, Suite 330, Boston,
* MA 02111-1307, USA.
*/
#ifndef AIP_COM_P_H
#define AIP_COM_P_H
#define RT_COM_NAME "rt_com(aip)" //Hm, IgH
/* input/ouput buffer (FIFO) sizes */
#define RT_COM_BUF_SIZ 256 // MUST BE ONLY POWER OF 2 !!
/* amount of free space on input buffer for RTS reset */
#define RT_COM_BUF_LOW (RT_COM_BUF_SIZ / 3)
/* amount of free space on input buffer for RTS set */
#define RT_COM_BUF_HI (RT_COM_BUF_SIZ * 2 / 3)
/* limit of free space on input buffer for buffer full error */
#define RT_COM_BUF_FULL 20
/* usage flags */
#define RT_COM_PORT_FREE 0x00
#define RT_COM_PORT_INUSE 0x01
#define RT_COM_PORT_SETUP 0x02
/* Some hardware description */
#define RT_COM_BASE_BAUD 115200
/** Interrupt Service Routines
* These are private functions */
static void rt_com0_isr( void );
static void rt_com1_isr( void );
/** Interrupt handling
*
* Define internal convinience macros for interrupt handling, so we
* get rid of the system dependencies.
*/
//#define rt_com_irq_off( state ) do{}while(0) //rt_global_save_flags( &state ); rt_global_cli() schreiben und lesen sowieso in IRQ Hm
//#define rt_com_irq_on(state) do{}while(0) //rt_global_restore_flags( state )
#define rt_com_irq_off( state ) rt_global_save_flags( &state ); rt_global_cli()
#define rt_com_irq_on(state) rt_global_restore_flags( state )
#define rt_com_request_irq( irq, isr ) rt_request_global_irq( irq, isr ); rt_enable_irq( irq );
#define rt_com_free_irq( irq ) rt_free_global_irq( irq )
/* port register offsets */
#define RT_COM_RXB 0x00
#define RT_COM_TXB 0x00
#define RT_COM_IER 0x01
#define RT_COM_IIR 0x02
#define RT_COM_FCR 0x02
#define RT_COM_LCR 0x03
#define RT_COM_MCR 0x04
#define RT_COM_LSR 0x05
#define RT_COM_MSR 0x06
#define RT_COM_DLL 0x00
#define RT_COM_DLM 0x01
/** MCR Modem Control Register masks */
#define MCR_DTR 0x01 // Data Terminal Ready
#define MCR_RTS 0x02 // Request To Send
#define MCR_OUT1 0x04
#define MCR_OUT2 0x08
#define MCR_LOOP 0x10
#define MCR_AFE 0x20 // AutoFlow Enable
/** IER Interrupt Enable Register masks */
#define IER_ERBI 0x01 // Enable Received Data Available Interrupt
#define IER_ETBEI 0x02 // Enable Transmitter Holding Register
// Empty Interrupt
#define IER_ELSI 0x04 // Enable Receiver Line Status Interrupt
#define IER_EDSSI 0x08 // Enable Modem Status Interrupt
/** MSR Modem Status Register masks */
#define MSR_DELTA_CTS 0x01
#define MSR_DELTA_DSR 0x02
#define MSR_TERI 0x04
#define MSR_DELTA_DCD 0x08
#define MSR_CTS 0x10
#define MSR_DSR 0x20
#define MSR_RI 0x40
#define MSR_DCD 0x80
/** LSR Line Status Register masks */
#define LSR_DATA_READY 0x01
#define LSR_OVERRUN_ERR 0x02
#define LSR_PARITY_ERR 0x04
#define LSR_FRAMING_ERR 0x08
#define LSR_BREAK 0x10
#define LSR_THRE 0x20 // Transmitter Holding Register
#define LSR_TEMT 0x40 // Transmitter Empty
/** FCR FIFO Control Register masks */
#define FCR_FIFO_ENABLE 0x01
#define FCR_INPUT_FIFO_RESET 0x02
#define FCR_OUTPUT_FIFO_RESET 0x04
/** data buffer
*
* Used for buffering of input and output data. Two buffers per port
* (one for input, one for output). Organized as a FIFO */
struct rt_buf_struct{
unsigned int head;
unsigned int tail;
char buf[ RT_COM_BUF_SIZ ];
};
/** Port data
*
* Internal information structure containing all data for a port. One
* structure for every port.
*
* Contains all current setup parameters and all data currently
* buffered by rt_com.
*
* mode (functioning mode)
* possible values:
* - RT_COM_DSR_ON_TX - for standard functioning mode (DSR needed on TX)
* - RT_COM_NO_HAND_SHAKE - for comunication without hand shake signals
* (only RXD-TXD-GND)
* - RT_COM_HW_FLOW - for hardware flow control (RTS-CTS)
* Of course RT_COM_DSR_ON_TX and RT_COM_NO_HAND_SHAKE cannot be
* sppecified at the same time.
*
* NOTE: When you select a mode that uses hand shake signals pay
* attention that no input signals (CTS,DSR,RI,DCD) must be
* floating.
*
* used (usage flag)
* possible values:
* - RT_COM_PORT_INUSE - port region requested by init_module
* - RT_COM_PORT_FREE - port region requested by rt_com_set_param
* - RT_COM_PORT_SETUP - port parameters are setup,
* don't specify at compile time !
*
* error
* last error detected
*
* ier (interrupt enable register)
* copy of IER chip register, last value set by rt_com.
*
* mcr (modem control register)
* copy of the MCR internal register
*/
struct rt_com_struct{
int baud_base;
int port;
int irq;
void (*isr)(void);
int baud;
unsigned int wordlength;
unsigned int parity;
unsigned int stopbits;
int mode;
int fifotrig;
int used;
int error;
int type;
int ier;
int mcr;
struct rt_buf_struct ibuf;
struct rt_buf_struct obuf;
};
#endif /* RT_COM_P_H */
/**
* Local Variables:
* mode: C
* c-file-style: "Stroustrup"
* End:
*/

43
rt/cif-rtai-io.h Normal file
View File

@@ -0,0 +1,43 @@
unsigned long cif_open_card(
unsigned int board_no,
unsigned int in_size,
unsigned int out_size,
void (*callback)(unsigned long priv_data),
unsigned long priv_data
);
void cif_close_card(
unsigned long fd
);
int cif_reset_card(
unsigned long fd,
unsigned int timeout,
unsigned int context // 1 = interrupt context
);
void cif_set_host_state(
unsigned long fd,
unsigned int state
);
int cif_exchange_io(
unsigned long fd,
void *recv_data,
void *send_data
);
int cif_read_io(
unsigned long fd,
void *recv_data
);
int cif_write_io(
unsigned long fd,
void *send_data
);
int cif_card_ready(
unsigned long fd
);

539
rt/msr_io.c Normal file

File diff suppressed because it is too large Load Diff

39
rt/msr_io.h Normal file
View File

@@ -0,0 +1,39 @@
/******************************************************************************
*
*
* Alle globalen Variabeln
*
* Autor: Richard Hacker
*
* (C) Copyright IgH 2005
* Ingenieurgemeinschaft IgH
* Heinz-Bäcker Str. 34
* D-45356 Essen
* Tel.: +49 201/61 99 31
* Fax.: +49 201/61 98 36
* E-mail: ha@igh-essen.com
*
*
* $RCSfile: msr_io.h,v $
* $Revision: 1.2 $
* $Author: hm $
* $Date: 2005/09/02 10:26:38 $
* $State: Exp $
*
*
*
*
*
*
*
*
*
******************************************************************************/
#ifndef _ETH_GLOBALS_H_
#define _ETH_GLOBALS_H_
#endif

36
rt/msr_load Executable file
View File

@@ -0,0 +1,36 @@
#!/bin/sh
module="msr_modul"
device="msr"
mode="664"
# Group: since distributions do it differently, look for wheel or use staff
if grep '^staff:' /etc/group > /dev/null; then
group="staff"
else
group="wheel"
fi
# invoke insmod with all arguments we got
# and use a pathname, as newer modutils don't look in . by default
/sbin/insmod -f ./$module.o $* || exit 1
major=`cat /proc/devices | awk "\\$2==\"$device\" {print \\$1}"`
echo $major
# Remove stale nodes and replace them, then give gid and perms
# Usually the script is shorter, it's scull that has several devices in it.
rm -f /dev/${device}
mknod /dev/${device} c $major 0
# ln -sf ${device}0 /dev/${device}
chgrp users /dev/${device}
chmod $mode /dev/${device}

16
rt/msr_unload Executable file
View File

@@ -0,0 +1,16 @@
#!/bin/sh
module="msr_modul"
device="msr"
# invoke rmmod with all arguments we got
/sbin/rmmod $module $* || exit 1
# Remove stale nodes
rm -f /dev/${device} /dev/${device}0

230
rt/msrserv.pl Executable file
View File

@@ -0,0 +1,230 @@
#!/usr/bin/perl -w
# Multithreaded Server
# according to the example from "Programming Perl"
#
# works with read/write on a device-file
#
# $Revision: 1.1 $
# $Date: 2002/07/09 10:10:59 $
# $RCSfile: msrserv.pl,v $
#
require 5.002;
use strict;
BEGIN { $ENV{PATH} = '/usr/bin:/bin' }
use Socket;
use Carp;
use FileHandle;
use Getopt::Std;
use Sys::Syslog qw(:DEFAULT setlogsock);
use vars qw (
$self $pid $dolog $port $dev %opts $selfbase
$len $offset $stream $written $read $log $blksize
$authfile %authhosts
);
# Do logging to local syslogd by unix-domain socket instead of inetd
setlogsock("unix");
# Prototypes and some little Tools
sub spawn;
sub logmsg {
my ($level, @text) = @_;
syslog("daemon|$level", @text) if $dolog;
# print STDERR "daemon|$level", @text, "\n" if $dolog;
}
sub out {
my $waitpid = wait;
logmsg("notice", "$waitpid exited");
unlink "$selfbase.pid";
exit 0;
}
sub help {
print "\n usage: $0 [-l og] [-h elp] [-p port] [-d device]\n";
exit;
}
# Process Options
%opts = (
"l" => 1,
"h" => 0,
"p" => 2345,
"d" => "/dev/msr"
);
getopts("lhp:d:", \%opts);
help if $opts{"h"};
( $self = $0 ) =~ s+.*/++ ;
( $selfbase = $self ) =~ s/\..*//;
$log = "$selfbase.log";
$dolog = $opts{"l"};
$port = $opts{"p"};
$dev = $opts{"d"};
$blksize = 1024; # try to write as much bytes
$authfile = "/opt/kbw/etc/hosts.auth";
# Start logging
openlog($self, 'pid');
# Flush Output, dont buffer
$| = 1;
# first fork and run in background
if ($pid = fork) {
# open LOG, ">$log" if $dolog;
# close LOG;
logmsg("notice", "forked process: $pid\n");
exit 0;
}
# Server tells about startup success
open (PID, ">$selfbase.pid");
print PID "$$\n";
close PID;
# Cleanup on exit (due to kill -TERM signal)
$SIG{TERM} = \&out;
# We use streams
my $proto = getprotobyname('tcp');
# Open Server socket
socket(Server, PF_INET, SOCK_STREAM, $proto) or die "socket: $!";
setsockopt(Server, SOL_SOCKET, SO_REUSEADDR, pack("l", 1))
or die "setsocketopt: $!";
bind (Server, sockaddr_in($port, INADDR_ANY))
or die "bind: $!";
listen (Server, SOMAXCONN)
or die "listen: $!";
%authhosts = ();
# get authorized hosts
open (AUTH, $authfile)
or logmsg ("notice", "Could not read allowed hosts file: $authfile");
while (<AUTH>) {
chomp;
my $host = lc $_;
logmsg ("notice", "Authorized host: $host");
$authhosts{$_} = 1 if $host =~ /^[\d\w]/;
}
close (AUTH);
# tell about open server socket
logmsg ("notice", "Server started at port $port");
my $waitpid = 0;
my $paddr;
# wait for children to return, thus avoiding zombies
sub REAPER {
$waitpid = wait;
$SIG{CHLD} = \&REAPER;
logmsg ("notice", "reaped $waitpid", ($? ? " with exit $?" : ""));
}
# also all sub-processes should wait for their children
$SIG{CHLD} = \&REAPER;
# start a new server for every incoming request
for ( ; $paddr = accept(Client, Server); close (Client)) {
my ($port, $iaddr) = sockaddr_in($paddr);
my $name = lc gethostbyaddr($iaddr, AF_INET);
my $ipaddr = inet_ntoa($iaddr);
my $n = 0;
# tell about the requesting client
logmsg ("info", "Connection from $ipaddr ($name) at port $port");
spawn sub {
my ($head, $hlen, $pos, $pegel, $typ, $siz, $nch, $nrec, $dat, $i, $j, $n, $llen);
my ($watchpegel, $shmpegel);
my ($rin, $rout, $in, $line, $data_requested, $oversample);
my (@channels);
# to use stdio on writing to Client
Client->autoflush();
# Open Device
sysopen (DEV, "$dev", O_RDWR | O_NONBLOCK, 0666) or die("can't open $dev");
# Bitmask to check for input on stdin
$rin = "";
vec($rin, fileno(Client), 1) = 1;
# check for authorized hosts
my $access = 'allow';
$access = 'allow' if $authhosts{$ipaddr};
$line = "<remote_host host=\"$ipaddr\" access=\"$access\">\n";
$len = length $line;
$offset = 0;
while ($len) {
$written = syswrite (DEV, $line, $len, $offset);
$len -= $written;
$offset += $written;
}
while ( 1 ) {
$in = select ($rout=$rin, undef, undef, 0.0); # poll client
# look for any Input from Client
if ($in) {
# exit on EOF
$len = sysread (Client, $line, $blksize) or exit;
logmsg("info", "got $len bytes: \"$line\"");
$offset = 0;
# copy request to device
while ($len) {
$written = syswrite (DEV, $line, $len, $offset);
$len -= $written;
$offset += $written;
}
}
# look for some output from device
if ($len = sysread DEV, $stream, $blksize) {
print Client $stream;
} else {
select undef, undef, undef, 0.1; # calm down if nothing on device
}
}
}
}
sub spawn {
my $coderef = shift;
unless (@_ == 0 && $coderef && ref($coderef) eq 'CODE') {
confess "usage: spawn CODEREF";
}
my $pid;
if (!defined($pid = fork)) {
logmsg ("notice", "fork failed: $!");
return;
} elsif ($pid) {
logmsg ("notice", "Request $pid");
return; # Parent
}
# do not use fdup as in the original example
# open (STDIN, "<&Client") or die "Can't dup client to stdin";
# open (STDOUT, ">&Client") or die "Can't dup client to stdout";
# STDOUT->autoflush();
exit &$coderef();
}

1
rt/rt_lib Symbolic link
View File

@@ -0,0 +1 @@
../../../linux/kernel_space/rt_lib-3.0.1-push

420
rt/tmp/_msr_io.c Executable file
View File

@@ -0,0 +1,420 @@
/**************************************************************************************************
*
* msr_io.c
*
* Verwaltung der IO-Karten
*
*
* Autor: Wilhelm Hagemeister
*
* (C) Copyright IgH 2002
* Ingenieurgemeinschaft IgH
* Heinz-Bäcker Str. 34
* D-45356 Essen
* Tel.: +49 201/61 99 31
* Fax.: +49 201/61 98 36
* E-mail: sp@igh-essen.com
*
*
* $RCSfile: msr_io.c,v $
* $Revision: 1.9 $
* $Author: ha $
* $Date: 2005/06/24 20:06:56 $
* $State: Exp $
*
*
* $Log: msr_io.c,v $
* Revision 1.9 2005/06/24 20:06:56 ha
* *** empty log message ***
*
* Revision 1.8 2005/06/24 17:39:05 ha
* *** empty log message ***
*
*
*
*
*
*
**************************************************************************************************/
/*--includes-------------------------------------------------------------------------------------*/
#ifndef __KERNEL__
# define __KERNEL__
#endif
#ifndef MODULE
# define MODULE
#endif
#include <linux/delay.h> /* mdelay() */
#include <linux/spinlock.h>
#include <linux/param.h> /* HZ */
#include <linux/sched.h> /* jiffies */
#include <linux/fs.h> /* everything... */
#include <rtai_fifos.h>
#include "msr_io.h"
#include <msr_messages.h>
#include "aim_globals.h"
spinlock_t data_lock = SPIN_LOCK_UNLOCKED;
#include "cif-rtai-io.h"
/*--defines--------------------------------------------------------------------------------------*/
/*--external functions---------------------------------------------------------------------------*/
/*--external data--------------------------------------------------------------------------------*/
/*--public data----------------------------------------------------------------------------------*/
#define PB_CARDS 4
struct {
unsigned int fd;
unsigned int timestamp;
unsigned int fault;
unsigned int active;
void *in_buf;
void *out_buf;
size_t in_buf_len;
size_t out_buf_len;
unsigned int reset_timeout;
} card[PB_CARDS];
/*
***************************************************************************************************
*
* Function: msr_io_init
*
* Beschreibung: Initialisieren der I/O-Karten
*
* Parameter:
*
* Rückgabe:
*
* Status: exp
*
***************************************************************************************************
*/
void x_PB_io(unsigned long card_no) {
int rv = 0;
unsigned int flags;
spin_lock_irqsave(&data_lock, flags);
switch (card_no) {
case 0:
rv = cif_exchange_io(card[0].fd,card[0].in_buf,card[0].out_buf);
if (!rv)
card[0].timestamp = jiffies;
break;
case 1:
rv = cif_exchange_io(card[1].fd,card[1].in_buf,card[1].out_buf);
// rv = cif_read_io(card[1].fd,card[1].in_buf);
// IMO.to_dSPACE.P101.HX_Stat = 51;
// IMO.from_dSPACE.P101.HX_Control |= IMO.to_dSPACE.P101.HX_Stat<<4;
// rv += cif_write_io(card[1].fd,card[1].out_buf);
if (!rv)
card[1].timestamp = jiffies;
break;
/*
case 2:
rv = cif_exchange_io(card[2].fd,&cif_in.P201,&cif_out.P201);
break;
*/
case 3:
rv = cif_exchange_io(card[3].fd,card[3].in_buf,card[3].out_buf);
if (!rv)
card[3].timestamp = jiffies;
break;
}
if (rv) {
msr_print_error("Error during exchange_io %i %i",
card_no, rv );
}
spin_unlock_irqrestore(&data_lock, flags);
}
int msr_io_init()
{
int rv;
memset(card, 0, sizeof(card));
#define FIFO_BUF 10000
if ((rv = rtf_create(0, FIFO_BUF)) < 0) {
msr_print_error("Could not open FIFO %i", rv);
return -1;
}
#ifndef _SIMULATION
/*
card[0].in_buf_len = sizeof(IMO.from_dSPACE);
card[0].out_buf_len = sizeof(IMO.to_dSPACE);
card[0].in_buf = &IMO.from_dSPACE;
card[0].out_buf = &IMO.to_dSPACE;
card[0].active = 1;
if (!(card[0].fd = cif_open_card(0, card[0].in_buf_len,
card[0].out_buf_len, x_PB_io, 0))) {
msr_print_error("Cannot open CIF card PB01");
return -1;
}
card[1].in_buf_len = sizeof(IMO.to_dSPACE.P101);
card[1].out_buf_len = sizeof(IMO.from_dSPACE.P101);
card[1].in_buf = &IMO.to_dSPACE.P101;
card[1].out_buf = &IMO.from_dSPACE.P101;
card[1].active = 1;
if (!(card[1].fd = cif_open_card(1, card[1].in_buf_len,
card[1].out_buf_len, x_PB_io, 1))) {
msr_print_error("Cannot open CIF card P101");
return -1;
}
card[2].in_buf_len = sizeof(IMO.to_dSPACE.P201);
card[2].out_buf_len = sizeof(IMO.from_dSPACE.P201);
card[2].in_buf = &IMO.to_dSPACE.P201;
card[2].out_buf = &IMO.from_dSPACE.P201;
if (!(card[2].fd = cif_open_card(2, card[2].in_buf_len,
card[2].out_buf_len, x_PB_io, 2))) {
msr_print_error("Cannot open CIF card P201");
return -1;
}
*/
card[3].in_buf_len = sizeof(dSPACE.in);
card[3].out_buf_len = sizeof(dSPACE.out);
card[3].in_buf = &dSPACE.in;
card[3].out_buf = &dSPACE.out;
card[3].active = 1;
if (!(card[3].fd = cif_open_card(0, card[3].in_buf_len,
card[3].out_buf_len, x_PB_io,3))) {
msr_print_error("Cannot open CIF card P301");
return -1;
}
//msr_reg_chk_failure(&int_cif_io_fail,TINT,T_CHK_HIGH,0,T_CRIT,"CIF Card was not ready to exchange data");
#endif
return 0;
}
/*
***************************************************************************************************
*
* Function: msr_io_register
*
* Beschreibung: Rohdaten als Kanaele registrieren
*
* Parameter:
*
* Rückgabe:
*
* Status: exp
*
***************************************************************************************************
*/
int msr_io_register()
{
#ifndef _SIMULATION
#endif
return 0;
}
/*
***************************************************************************************************
*
* Function: msr_io_write
*
* Beschreibung: Schreiben der Werte
*
* Parameter:
*
* Rückgabe:
*
* Status: exp
*
***************************************************************************************************
*/
int msr_io_write()
{
static int return_value = 0;
int rv;
int i = 0;
unsigned int flags;
unsigned int com_check_timestamp = 0;
static int COM_Up = 1;
if (jiffies - com_check_timestamp > HZ/20) {
if ( rtf_put_if(0,&IMO,sizeof(IMO)) != sizeof(IMO)) {
//msr_print_error("Could not output data");
}
com_check_timestamp = jiffies;
spin_lock_irqsave(&data_lock, flags);
for ( i=0; i < PB_CARDS; i++) {
// Ignore inactive and cards that already have a fault
if (!card[i].active || card[i].fault)
continue;
// For active cards, check timestamp value. Mark card
// as faulty if there was no data exchange in the last
// 50ms
if (jiffies - card[i].timestamp > HZ/20) {
COM_Up = 0;
card[i].fault = 1;
card[i].reset_timeout = jiffies;
msr_print_error("Card %i timed out", i);
}
}
spin_unlock_irqrestore(&data_lock, flags);
for ( i = 0; i < PB_CARDS; i++ ) {
if (!card[i].active || (card[i].active && !card[i].fault))
continue;
switch (card[i].fault) {
case 1:
rv = cif_write_io(card[i].fd,card[i].out_buf);
if (!rv) {
msr_print_error("Card %i online", i);
card[i].fault = 0;
card[i].timestamp = jiffies;
break;
}
msr_print_error("rv of cif_write_io(%i) = %i",
i, rv);
card[i].fault = 2;
cif_set_host_state(card[i].fd,0);
card[i].reset_timeout = jiffies;
case 2:
if (cif_card_ready(card[i].fd)) {
cif_set_host_state(card[i].fd,1);
card[i].fault = 0;
break;
}
if (jiffies < card[i].reset_timeout)
break;
rv = cif_reset_card(card[i].fd,10,1);
msr_print_error("rv of cif_reset_card(%i) = %i",
i, rv);
// Reset again in 10 seconds
card[i].reset_timeout += 10*HZ;
}
}
}
if (COM_Up)
IMO.to_dSPACE.Status = IMO.from_dSPACE.WatchDog;
// if (return_value)
// int_cif_io_fail = 1;
return return_value;
}
/*
***************************************************************************************************
*
* Function: msr_io_read
*
* Beschreibung: Lesen der Werte
*
* Parameter:
*
* Rückgabe:
*
* Status: exp
*
***************************************************************************************************
*/
int msr_io_read()
{
int return_value = 0;
#ifndef _SIMULATION
int_cif_io_fail = 0;
/*
return_value = cif_exchange_io(fd_PB01,
&cif_out,&cif_in,
sizeof(cif_out),sizeof(cif_in)
);
*/
/* if (return_value) */
/* int_cif_io_fail = 1; */
// printk("%i\n", return_value);
#endif
return return_value;
}
/*
***************************************************************************************************
*
* Function: msr_io_cleanup
*
* Beschreibung: Aufräumen
*
* Parameter:
*
* Rückgabe:
*
* Status: exp
*
***************************************************************************************************
*/
void msr_io_cleanup()
{
/*
cif_set_host_state(card[0].fd,0);
cif_close_card(card[0].fd);
cif_set_host_state(card[1].fd,0);
cif_close_card(card[1].fd);
cif_set_host_state(card[2].fd,0);
cif_close_card(card[2].fd);
*/
cif_set_host_state(card[3].fd,0);
cif_close_card(card[3].fd);
rtf_destroy(0);
}

236
rt/tmp/_msr_io.h Executable file
View File

@@ -0,0 +1,236 @@
/**************************************************************************************************
*
* msr_io.h
*
* Verwaltung der IO-Karten
*
* Autor: Wilhelm Hagemeister
*
* (C) Copyright IgH 2002
* Ingenieurgemeinschaft IgH
* Heinz-Bäcker Str. 34
* D-45356 Essen
* Tel.: +49 201/61 99 31
* Fax.: +49 201/61 98 36
* E-mail: sp@igh-essen.com
*
*
* $RCSfile: msr_io.h,v $
* $Revision: 1.5 $
* $Author: ha $
* $Date: 2005/06/24 20:08:15 $
* $State: Exp $
*
*
* $Log: msr_io.h,v $
* Revision 1.5 2005/06/24 20:08:15 ha
* *** empty log message ***
*
* Revision 1.4 2005/06/24 17:39:05 ha
* *** empty log message ***
*
* Revision 1.3 2005/02/28 17:11:48 hm
* *** empty log message ***
*
* Revision 1.1 2005/02/10 16:34:24 hm
* Initial revision
*
* Revision 1.4 2004/12/21 22:03:54 hm
* *** empty log message ***
*
* Revision 1.3 2004/12/16 15:44:01 hm
* *** empty log message ***
*
* Revision 1.2 2004/12/01 17:07:49 hm
* *** empty log message ***
*
* Revision 1.1 2004/11/26 15:14:21 hm
* Initial revision
*
* Revision 1.1 2004/11/01 11:05:20 hm
* Initial revision
*
* Revision 1.1 2004/10/21 12:09:23 hm
* Initial revision
*
* Revision 1.3 2004/09/21 18:10:58 hm
* *** empty log message ***
*
* Revision 1.2 2004/07/22 17:28:02 hm
* *** empty log message ***
*
* Revision 1.1 2004/06/21 08:46:52 hm
* Initial revision
*
* Revision 1.4 2004/06/02 20:38:42 hm
* *** empty log message ***
*
* Revision 1.3 2004/06/02 20:38:18 hm
* *** empty log message ***
*
* Revision 1.2 2004/06/02 12:15:17 hm
* *** empty log message ***
*
* Revision 1.5 2003/02/20 17:33:37 hm
* *** empty log message ***
*
* Revision 1.4 2003/02/14 18:17:28 hm
* *** empty log message ***
*
* Revision 1.3 2003/02/13 17:11:12 hm
* *** empty log message ***
*
* Revision 1.2 2003/01/30 15:05:58 hm
* *** empty log message ***
*
* Revision 1.1 2003/01/24 20:40:09 hm
* Initial revision
*
* Revision 1.1 2003/01/22 15:55:40 hm
* Initial revision
*
* Revision 1.1 2002/08/13 16:26:27 hm
* Initial revision
*
* Revision 1.4 2002/07/04 13:34:27 sp
* *** empty log message ***
*
* Revision 1.3 2002/07/04 12:08:34 sp
* *** empty log message ***
*
* Revision 1.2 2002/07/04 08:44:19 sp
* Änderung des Autors :) und des Datums
*
* Revision 1.1 2002/07/04 08:25:26 sp
* Initial revision
*
*
*
*
*
*
*
**************************************************************************************************/
/*--Schutz vor mehrfachem includieren------------------------------------------------------------*/
#ifndef _MSR_IO_H_
#define _MSR_IO_H_
/*--includes-------------------------------------------------------------------------------------*/
//#include "msr_control.h"
/*--defines--------------------------------------------------------------------------------------*/
struct cif_in_t { /* Von Feld nach dSPACE */
uint8_t CIM_stat;
uint8_t P101[91];
uint8_t P201[72];
uint8_t P301[72];
} __attribute__ ((packed));
struct cif_out_t { /* Von dSPACE zum Feld */
uint8_t WatchDog;
uint8_t P101[39];
uint8_t P201[32];
uint8_t P301[32];
} __attribute__ ((packed));
/*--external functions---------------------------------------------------------------------------*/
/*--external data--------------------------------------------------------------------------------*/
/*--public data----------------------------------------------------------------------------------*/
/*
***************************************************************************************************
*
* Function: msr_io_init
*
* Beschreibung: Initialisieren der I/O-Karten
*
* Parameter:
*
* Rückgabe:
*
* Status: exp
*
***************************************************************************************************
*/
int msr_io_init();
/*
***************************************************************************************************
*
* Function: msr_io_register
*
* Beschreibung: Kanaele oder Parameter registrieren
*
* Parameter:
*
* Rückgabe:
*
* Status: exp
*
***************************************************************************************************
*/
int msr_io_register();
/*
***************************************************************************************************
*
* Function: msr_io_write
*
* Beschreibung: Schreiben der Werte
*
* Parameter:
*
* Rückgabe:
*
* Status: exp
*
***************************************************************************************************
*/
int msr_io_write();
/*
***************************************************************************************************
*
* Function: msr_io_write
*
* Beschreibung: Lesen der Werte
*
* Parameter:
*
* Rückgabe:
*
* Status: exp
*
***************************************************************************************************
*/
int msr_io_read();
/*
***************************************************************************************************
*
* Function: msr_io_cleanup
*
* Beschreibung: Aufräumen
*
* Parameter:
*
* Rückgabe:
*
* Status: exp
*
***************************************************************************************************
*/
void msr_io_cleanup();
#endif

64
user/Makefile Normal file
View File

@@ -0,0 +1,64 @@
#----------------------------------------------------------------
#
# M a k e f i l e
#
# $LastChangedDate$
# $Author$
#
#----------------------------------------------------------------
LIBNET_DIR = ../../soft/libnet-install
LIBPCAP_DIR = ../../soft/libpcap-install
FLTK_DIR = ../../soft/fltk-2.0-install
CC = g++
CFLAGS = -Wall -g -I$(LIBNET_DIR)/include -I$(LIBPCAP_DIR)/include \
`$(FLTK_DIR)/bin/fltk-config --cflags`
TEST_EXE = ethercat-test
TEST_OBJ = main.o ec_master.o ec_command.o ec_slave.o
TEST_LDFLAGS = -L$(LIBNET_DIR)/lib -lnet -lpcap -lpthread
GUI_EXE = ethercat-gui
GUI_OBJ = main_gui.o ec_master.o ec_command.o ec_slave.o
GUI_LDFLAGS = -L$(LIBNET_DIR)/lib -lnet -lpcap -lpthread `$(FLTK_DIR)/bin/fltk-config --ldflags`
#----------------------------------------------------------------
first: $(TEST_EXE) $(GUI_EXE)
$(TEST_EXE): $(TEST_OBJ)
$(CC) $(TEST_OBJ) $(TEST_LDFLAGS) -o $@
$(GUI_EXE): $(GUI_OBJ)
$(CC) $(GUI_OBJ) $(GUI_LDFLAGS) -o $@
.c.o:
$(CC) $(CFLAGS) -c $< -o $@
.cpp.o:
$(CC) $(CFLAGS) -c $< -o $@
#----------------------------------------------------------------
main.o: main.c \
ec_globals.h ec_master.h ec_command.h ec_slave.h
main_gui.o: main_gui.cpp \
ec_globals.h ec_master.h ec_command.h ec_slave.h
ec_command.o: ec_command.c ec_command.h
ec_master.o: ec_master.c ec_master.h \
ec_globals.h ec_command.h ec_slave.h
ec_slave.o: ec_slave.c ec_slave.h \
ec_globals.h
#----------------------------------------------------------------
clean:
rm -f *.o $(TEST_EXE) $(GUI_EXE) *~
#----------------------------------------------------------------

61
user/ec_command.c Normal file
View File

@@ -0,0 +1,61 @@
//---------------------------------------------------------------
//
// e c _ c o m m a n d . c
//
// $LastChangedDate$
// $Author$
//
//---------------------------------------------------------------
#include <stdio.h>
#include <stdlib.h>
#include "ec_command.h"
//---------------------------------------------------------------
void EtherCAT_command_init(EtherCAT_command_t *cmd)
{
cmd->command_type = 0x00;
cmd->node_address = 0x0000;
cmd->ring_position = 0x0000;
cmd->mem_address = 0x0000;
cmd->logical_address = 0x00000000;
cmd->data_length = 0;
cmd->status = Waiting;
cmd->next = NULL;
cmd->working_counter = 0;
cmd->data = NULL;
}
//---------------------------------------------------------------
void EtherCAT_command_clear(EtherCAT_command_t *cmd)
{
if (cmd->data)
{
free(cmd->data);
}
EtherCAT_command_init(cmd);
}
//---------------------------------------------------------------
void EtherCAT_command_print_data(EtherCAT_command_t *cmd)
{
unsigned int i;
printf("[");
for (i = 0; i < cmd->data_length; i++)
{
printf("%02X", cmd->data[i]);
if (i < cmd->data_length - 1) printf(" ");
}
printf("]\n");
}
//---------------------------------------------------------------

42
user/ec_command.h Normal file
View File

@@ -0,0 +1,42 @@
//---------------------------------------------------------------
//
// e c _ c o m m a n d . h
//
// $LastChangedDate$
// $Author$
//
//---------------------------------------------------------------
typedef enum {Waiting, Sent, Received} EtherCAT_cmd_status_t;
//---------------------------------------------------------------
typedef struct EtherCAT_command
{
unsigned char command_type;
short ring_position;
unsigned short node_address;
unsigned short mem_address;
unsigned int logical_address;
unsigned int data_length;
struct EtherCAT_command *next;
EtherCAT_cmd_status_t status;
unsigned char command_index;
unsigned int working_counter;
unsigned char *data;
}
EtherCAT_command_t;
//---------------------------------------------------------------
void EtherCAT_command_init(EtherCAT_command_t *);
void EtherCAT_command_clear(EtherCAT_command_t *);
// Debug
void EtherCAT_command_print_data(EtherCAT_command_t *);
//---------------------------------------------------------------

26
user/ec_globals.h Normal file
View File

@@ -0,0 +1,26 @@
//---------------------------------------------------------------
//
// e c _ g l o b a l s . h
//
// $LastChangedDate$
// $Author$
//
//---------------------------------------------------------------
#define EC_CMD_APRD 0x01 // Auto-increment physical read
#define EC_CMD_APWR 0x02 // Auto-increment physical write
#define EC_CMD_NPRD 0x04 // Node-addressed physical read
#define EC_CMD_NPWR 0x05 // Node-addressed physical write
#define EC_CMD_BRD 0x07 // Broadcast read
#define EC_CMD_BWR 0x08 // Broadcast write
#define EC_CMD_LRW 0x0C // Logical read/write
#define EC_STATE_UNKNOWN 0x00
#define EC_STATE_INIT 0x01
#define EC_STATE_PREOP 0x02
#define EC_STATE_SAVEOP 0x04
#define EC_STATE_OP 0x08
#define EC_ACK_STATE 0x10
//---------------------------------------------------------------

1407
user/ec_master.c Normal file

File diff suppressed because it is too large Load Diff

120
user/ec_master.h Normal file
View File

@@ -0,0 +1,120 @@
//---------------------------------------------------------------
//
// e c _ m a s t e r . h
//
// $LastChangedDate$
// $Author$
//
//---------------------------------------------------------------
#include <pcap.h>
#include <libnet.h>
#include <pthread.h>
#include "ec_slave.h"
#include "ec_command.h"
//---------------------------------------------------------------
typedef struct
{
EtherCAT_slave_t *slaves; // Slaves array
unsigned int slave_count; // Number of slaves
EtherCAT_command_t *first_command; // List of commands
pcap_t *pcap_handle; // Handle for libpcap
libnet_t *net_handle; // Handle for libnet
unsigned char command_index; // Current command index
unsigned char *process_data;
unsigned int process_data_length;
void (*pre_cb)(unsigned char *);
void (*post_cb)(unsigned char *);
pthread_t thread;
int thread_continue;
unsigned int cycle_time;
double bus_time;
double last_jitter;
double last_cycle_time;
double last_cycle_work_time;
double last_cycle_busy_rate;
}
EtherCAT_master_t;
//---------------------------------------------------------------
// Master creation and deletion
int EtherCAT_master_init(EtherCAT_master_t *, char *);
void EtherCAT_master_clear(EtherCAT_master_t *);
// Checking for slaves
int EtherCAT_check_slaves(EtherCAT_master_t *, EtherCAT_slave_t *, unsigned int);
void EtherCAT_clear_slaves(EtherCAT_master_t *);
// Slave information interface
int EtherCAT_read_slave_information(EtherCAT_master_t *,
unsigned short int,
unsigned short int,
unsigned int *);
// EtherCAT commands
EtherCAT_command_t *EtherCAT_read(EtherCAT_master_t *,
unsigned short,
unsigned short,
unsigned int);
EtherCAT_command_t *EtherCAT_write(EtherCAT_master_t *,
unsigned short,
unsigned short,
unsigned int,
const unsigned char *);
EtherCAT_command_t *EtherCAT_position_read(EtherCAT_master_t *,
short,
unsigned short,
unsigned int);
EtherCAT_command_t *EtherCAT_position_write(EtherCAT_master_t *,
short,
unsigned short,
unsigned int,
const unsigned char *);
EtherCAT_command_t *EtherCAT_broadcast_read(EtherCAT_master_t *,
unsigned short,
unsigned int);
EtherCAT_command_t *EtherCAT_broadcast_write(EtherCAT_master_t *,
unsigned short,
unsigned int,
const unsigned char *);
EtherCAT_command_t *EtherCAT_logical_read_write(EtherCAT_master_t *,
unsigned int,
unsigned int,
unsigned char *);
void EtherCAT_remove_command(EtherCAT_master_t *, EtherCAT_command_t *);
// Slave states
int EtherCAT_state_change(EtherCAT_master_t *, EtherCAT_slave_t *, unsigned char);
int EtherCAT_broadcast_state_change(EtherCAT_master_t *, unsigned char);
int EtherCAT_activate_slave(EtherCAT_master_t *, EtherCAT_slave_t *);
int EtherCAT_deactivate_slave(EtherCAT_master_t *, EtherCAT_slave_t *);
// Sending and receiving
int EtherCAT_send_receive(EtherCAT_master_t *);
int EtherCAT_start(EtherCAT_master_t *,
unsigned int,
void (*)(unsigned char *),
void (*)(unsigned char *),
unsigned int);
int EtherCAT_stop(EtherCAT_master_t *);
// Private functions
void add_command(EtherCAT_master_t *, EtherCAT_command_t *);
void set_byte(unsigned char *, unsigned int, unsigned char);
void set_word(unsigned char *, unsigned int, unsigned int);
void *thread_function(void *);
//---------------------------------------------------------------

137
user/ec_slave.c Normal file
View File

@@ -0,0 +1,137 @@
//---------------------------------------------------------------
//
// e c _ s l a v e . c
//
// $LastChangedDate$
// $Author$
//
//---------------------------------------------------------------
#include <stdlib.h>
#include "ec_globals.h"
#include "ec_slave.h"
//---------------------------------------------------------------
void EtherCAT_slave_init(EtherCAT_slave_t *slave)
{
slave->type = 0;
slave->revision = 0;
slave->build = 0;
slave->ring_position = 0;
slave->station_address = 0;
slave->vendor_id = 0;
slave->product_code = 0;
slave->revision_number = 0;
slave->desc = NULL;
slave->logical_address0 = 0;
slave->current_state = EC_STATE_UNKNOWN;
slave->requested_state = EC_STATE_UNKNOWN;
}
//---------------------------------------------------------------
void EtherCAT_slave_clear(EtherCAT_slave_t *slave)
{
// Nothing yet...
}
//---------------------------------------------------------------
void EtherCAT_slave_print(EtherCAT_slave_t *slave)
{
}
//---------------------------------------------------------------
unsigned char sm0_multi[] = {0x00, 0x18, 0xF6, 0x00, 0x26, 0x00, 0x01, 0x00};
unsigned char sm1_multi[] = {0xF6, 0x18, 0xF6, 0x00, 0x22, 0x00, 0x01, 0x00};
unsigned char sm0_1014[] = {0x00, 0x10, 0x01, 0x00, 0x00, 0x00, 0x01, 0x00};
unsigned char sm0_2004[] = {0x00, 0x0F, 0x01, 0x00, 0x46, 0x00, 0x01, 0x00};
unsigned char sm2_31xx[] = {0x00, 0x10, 0x04, 0x00, 0x24, 0x00, 0x00, 0x00};
unsigned char sm3_31xx[] = {0x00, 0x11, 0x06, 0x00, 0x20, 0x00, 0x01, 0x00};
unsigned char sm2_4102[] = {0x00, 0x10, 0x04, 0x00, 0x24, 0x00, 0x01, 0x00};
unsigned char fmmu0_1014[] = {0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x07,
0x00, 0x10, 0x00, 0x01, 0x01, 0x00, 0x00, 0x00};
unsigned char fmmu0_2004[] = {0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x07,
0x00, 0x0F, 0x00, 0x02, 0x01, 0x00, 0x00, 0x00};
unsigned char fmmu0_31xx[] = {0x00, 0x00, 0x00, 0x00, 0x06, 0x00, 0x00, 0x07,
0x00, 0x11, 0x00, 0x01, 0x01, 0x00, 0x00, 0x00};
unsigned char fmmu0_4102[] = {0x00, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, 0x07,
0x00, 0x10, 0x00, 0x02, 0x01, 0x00, 0x00, 0x00};
//---------------------------------------------------------------
EtherCAT_slave_desc_t Beckhoff_EK1100[] = {"Beckhoff", "EK1100", "Bus Coupler",
SIMPLE,
NULL, NULL, NULL, NULL, // Noch nicht eingepflegt...
NULL,
0};
EtherCAT_slave_desc_t Beckhoff_EL1014[] = {"Beckhoff", "EL1014", "4x Digital Input",
SIMPLE,
sm0_1014, NULL, NULL, NULL,
fmmu0_1014,
1};
EtherCAT_slave_desc_t Beckhoff_EL2004[] = {"Beckhoff", "EL2004", "4x Digital Output",
SIMPLE,
sm0_2004, NULL, NULL, NULL,
fmmu0_2004,
1};
EtherCAT_slave_desc_t Beckhoff_EL3102[] = {"Beckhoff", "EL3102", "2x Analog Input Diff",
MAILBOX,
sm0_multi, sm1_multi, sm2_31xx, sm3_31xx,
fmmu0_31xx,
6};
EtherCAT_slave_desc_t Beckhoff_EL3162[] = {"Beckhoff", "EL3162", "2x Analog Input",
MAILBOX,
sm0_multi, sm1_multi, sm2_31xx, sm3_31xx,
fmmu0_31xx,
6};
EtherCAT_slave_desc_t Beckhoff_EL4102[] = {"Beckhoff", "EL4102", "2x Analog Output",
MAILBOX,
sm0_multi, sm1_multi, sm2_4102, NULL,
fmmu0_4102,
4};
EtherCAT_slave_desc_t Beckhoff_EL5001[] = {"Beckhoff", "EL5001", "SSI-Interface",
SIMPLE,
NULL, NULL, NULL, NULL, // Noch nicht eingepflegt...
NULL,
0};
//---------------------------------------------------------------
unsigned int slave_idents_count = 7;
struct slave_ident slave_idents[] =
{
{0x00000002, 0x03F63052, Beckhoff_EL1014},
{0x00000002, 0x044C2C52, Beckhoff_EK1100},
{0x00000002, 0x07D43052, Beckhoff_EL2004},
{0x00000002, 0x0C1E3052, Beckhoff_EL3102},
{0x00000002, 0x0C5A3052, Beckhoff_EL3162},
{0x00000002, 0x10063052, Beckhoff_EL4102},
{0x00000002, 0x13893052, Beckhoff_EL5001}
};
//---------------------------------------------------------------

96
user/ec_slave.h Normal file
View File

@@ -0,0 +1,96 @@
//---------------------------------------------------------------
//
// e c _ s l a v e . h
//
// $LastChangedDate$
// $Author$
//
//---------------------------------------------------------------
#define SIMPLE 0
#define MAILBOX 1
//---------------------------------------------------------------
typedef struct slave_desc EtherCAT_slave_desc_t;
typedef struct
{
// Base data
unsigned char type;
unsigned char revision;
unsigned short build;
// Addresses
short ring_position;
unsigned short station_address;
// Slave information interface
unsigned int vendor_id;
unsigned int product_code;
unsigned int revision_number;
const EtherCAT_slave_desc_t *desc;
unsigned int logical_address0;
unsigned int current_state;
unsigned int requested_state;
unsigned char *process_data;
}
EtherCAT_slave_t;
#define ECAT_INIT_SLAVE(TYPE) {0, 0, 0, 0, 0, 0, 0, 0, TYPE, 0, 0, 0, NULL}
//---------------------------------------------------------------
// Slave construction and deletion
void EtherCAT_slave_init(EtherCAT_slave_t *);
void EtherCAT_slave_clear(EtherCAT_slave_t *);
// Debug
void EtherCAT_slave_print(EtherCAT_slave_t *);
//---------------------------------------------------------------
typedef struct slave_desc
{
const char *vendor_name;
const char *product_name;
const char *product_desc;
const int type;
const unsigned char *sm0;
const unsigned char *sm1;
const unsigned char *sm2;
const unsigned char *sm3;
const unsigned char *fmmu0;
const unsigned int data_length;
}
EtherCAT_slave_desc_t;
extern EtherCAT_slave_desc_t Beckhoff_EK1100[];
extern EtherCAT_slave_desc_t Beckhoff_EL1014[];
extern EtherCAT_slave_desc_t Beckhoff_EL2004[];
extern EtherCAT_slave_desc_t Beckhoff_EL3102[];
extern EtherCAT_slave_desc_t Beckhoff_EL3162[];
extern EtherCAT_slave_desc_t Beckhoff_EL4102[];
extern EtherCAT_slave_desc_t Beckhoff_EL5001[];
//---------------------------------------------------------------
struct slave_ident
{
const unsigned int vendor_id;
const unsigned int product_code;
const EtherCAT_slave_desc_t *desc;
};
extern struct slave_ident slave_idents[];
extern unsigned int slave_idents_count;
//---------------------------------------------------------------

439
user/main.c Normal file
View File

@@ -0,0 +1,439 @@
//---------------------------------------------------------------
//
// m a i n . c
//
// $LastChangedDate$
// $Author$
//
//---------------------------------------------------------------
#include <stdio.h>
#include <string.h> // memset()
#include <unistd.h> // usleep()
#include <signal.h>
#include "ec_globals.h"
#include "ec_master.h"
//---------------------------------------------------------------
void signal_handler(int);
void write_data(unsigned char *);
int continue_running;
unsigned short int word;
//---------------------------------------------------------------
int main(int argc, char **argv)
{
EtherCAT_master_t master;
EtherCAT_command_t *cmd, *cmd2;
unsigned char data[256];
unsigned int i, number;
struct sigaction sa;
sa.sa_handler = signal_handler;
sigaction(SIGINT, &sa, NULL);
printf("CatEther-Testprogramm.\n");
EtherCAT_master_init(&master, "eth1");
if (EtherCAT_check_slaves(&master, NULL, 0) != 0)
{
fprintf(stderr, "ERROR while searching for slaves!\n");
return -1;
}
if (master.slave_count == 0)
{
fprintf(stderr, "ERROR: No slaves found!\n");
return -1;
}
for (i = 0; i < master.slave_count; i++)
{
printf("Slave found: Type %02X, Revision %02X, Build %04X\n",
master.slaves[i].type, master.slaves[i].revision, master.slaves[i].build);
}
printf("Writing Station addresses.\n");
for (i = 0; i < master.slave_count; i++)
{
data[0] = i & 0x00FF;
data[1] = (i & 0xFF00) >> 8;
cmd = EtherCAT_position_write(&master, 0 - i, 0x0010, 2, data);
EtherCAT_send_receive(&master);
if (cmd->working_counter != 1)
{
fprintf(stderr, "ERROR: Slave did'n repond!\n");
return -1;
}
EtherCAT_remove_command(&master, cmd);
}
//----------
for (i = 0; i < master.slave_count; i++)
{
printf("\nKlemme %i:\n", i);
EtherCAT_read_slave_information(&master, i, 0x0008, &number);
printf("Vendor ID: 0x%04X (%i)\n", number, number);
EtherCAT_read_slave_information(&master, i, 0x000A, &number);
printf("Product Code: 0x%04X (%i)\n", number, number);
EtherCAT_read_slave_information(&master, i, 0x000E, &number);
printf("Revision Number: 0x%04X (%i)\n", number, number);
}
//----------
printf("\nResetting FMMU's.\n");
memset(data, 0x00, 256);
cmd = EtherCAT_broadcast_write(&master, 0x0600, 256, data);
EtherCAT_send_receive(&master);
if (cmd->working_counter != master.slave_count)
{
fprintf(stderr, "ERROR: Not all slaves responded (%i of %i)!\n",
cmd->working_counter, master.slave_count);
return -1;
}
EtherCAT_remove_command(&master, cmd);
//----------
printf("Resetting Sync Manager channels.\n");
memset(data, 0x00, 256);
cmd = EtherCAT_broadcast_write(&master, 0x0800, 256, data);
EtherCAT_send_receive(&master);
if (cmd->working_counter != master.slave_count)
{
fprintf(stderr, "ERROR: Not all slaves responded (%i of %i)!\n",
cmd->working_counter, master.slave_count);
return -1;
}
EtherCAT_remove_command(&master, cmd);
//----------
printf("Setting INIT state for devices.\n");
if (EtherCAT_broadcast_state_change(&master, EC_STATE_INIT) != 0)
{
fprintf(stderr, "ERROR: Could not set INIT state!\n");
return -1;
}
//----------
printf("Setting PREOP state for bus coupler.\n");
if (EtherCAT_state_change(&master, &master.slaves[0], EC_STATE_PREOP) != 0)
{
fprintf(stderr, "ERROR: Could not set state!\n");
return -1;
}
//----------
printf("Setting Sync managers 0 and 1 of device 1.\n");
data[0] = 0x00;
data[1] = 0x18;
data[2] = 0xF6;
data[3] = 0x00;
data[4] = 0x26;
data[5] = 0x00;
data[6] = 0x01;
data[7] = 0x00;
cmd = EtherCAT_write(&master, 0x0001, 0x0800, 8, data);
data[0] = 0xF6;
data[1] = 0x18;
data[2] = 0xF6;
data[3] = 0x00;
data[4] = 0x22;
data[5] = 0x00;
data[6] = 0x01;
data[7] = 0x00;
cmd2 = EtherCAT_write(&master, 0x0001, 0x0808, 8, data);
EtherCAT_send_receive(&master);
if (cmd->working_counter != 1 || cmd2->working_counter != 1)
{
fprintf(stderr, "ERROR: Not all slaves responded!\n");
return -1;
}
EtherCAT_remove_command(&master, cmd);
EtherCAT_remove_command(&master, cmd2);
//----------
printf("Setting PREOP state for device 1.\n");
if (EtherCAT_state_change(&master, &master.slaves[1], EC_STATE_PREOP))
{
fprintf(stderr, "ERROR: Could not set state!\n");
return -1;
}
//----------
printf("Setting PREOP state for device 4.\n");
if (EtherCAT_state_change(&master, &master.slaves[4], EC_STATE_PREOP))
{
fprintf(stderr, "ERROR: Could not set state!\n");
return -1;
}
//----------
#if 1
printf("Setting FMMU 0 of device 1.\n");
data[0] = 0x00; // Logical start address [4]
data[1] = 0x00;
data[2] = 0x00;
data[3] = 0x00;
data[4] = 0x04; // Length [2]
data[5] = 0x00;
data[6] = 0x00; // Start bit
data[7] = 0x07; // End bit
data[8] = 0x00; // Physical start address [2]
data[9] = 0x10;
data[10] = 0x00; // Physical start bit
data[11] = 0x02; // Read/write enable
data[12] = 0x01; // channel enable [2]
data[13] = 0x00;
data[14] = 0x00; // Reserved [2]
data[15] = 0x00;
cmd = EtherCAT_write(&master, 0x0001, 0x0600, 16, data);
EtherCAT_send_receive(&master);
if (cmd->working_counter != 1)
{
fprintf(stderr, "ERROR: Not all slaves responded (%i of 1)!\n",
cmd->working_counter);
return -1;
}
EtherCAT_remove_command(&master, cmd);
#endif
//----------
#if 1
printf("Setting FMMU 0 of device 4.\n");
data[0] = 0x04; // Logical start address [4]
data[1] = 0x00;
data[2] = 0x00;
data[3] = 0x00;
data[4] = 0x01; // Length [2]
data[5] = 0x00;
data[6] = 0x00; // Start bit
data[7] = 0x07; // End bit
data[8] = 0x00; // Physical start address [2]
data[9] = 0x0F;
data[10] = 0x00; // Physical start bit
data[11] = 0x02; // Read/write enable
data[12] = 0x01; // channel enable [2]
data[13] = 0x00;
data[14] = 0x00; // Reserved [2]
data[15] = 0x00;
cmd = EtherCAT_write(&master, 0x0004, 0x0600, 16, data);
EtherCAT_send_receive(&master);
if (cmd->working_counter != 1)
{
fprintf(stderr, "ERROR: Not all slaves responded (%i of 1)!\n",
cmd->working_counter);
return -1;
}
EtherCAT_remove_command(&master, cmd);
#endif
//----------
printf("Setting Sync manager 2 of device 1.\n");
data[0] = 0x00;
data[1] = 0x10;
data[2] = 0x04;
data[3] = 0x00;
data[4] = 0x24;
data[5] = 0x00;
data[6] = 0x01;
data[7] = 0x00;
cmd = EtherCAT_write(&master, 0x0001, 0x0810, 8, data);
EtherCAT_send_receive(&master);
if (cmd->working_counter != 1)
{
fprintf(stderr, "ERROR: Not all slaves responded (%i of 1)!\n", cmd->working_counter);
return -1;
}
EtherCAT_remove_command(&master, cmd);
//----------
printf("Setting Sync manager 0 for device 4.\n");
data[0] = 0x00;
data[1] = 0x0F;
data[2] = 0x01;
data[3] = 0x00;
data[4] = 0x46; // 46
data[5] = 0x00;
data[6] = 0x01;
data[7] = 0x00;
cmd = EtherCAT_write(&master, 0x0004, 0x0800, 8, data);
EtherCAT_send_receive(&master);
if (cmd->working_counter != 1)
{
fprintf(stderr, "ERROR: Not all slaves responded!\n");
return -1;
}
EtherCAT_remove_command(&master, cmd);
//----------
printf("Setting SAVEOP state for bus coupler.\n");
if (EtherCAT_state_change(&master, 0x0000, EC_STATE_SAVEOP) != 0)
{
fprintf(stderr, "ERROR: Could not set state!\n");
return -1;
}
//----------
printf("Setting SAVEOP state for device 1.\n");
if (EtherCAT_state_change(&master, &master.slaves[1], EC_STATE_SAVEOP) != 0)
{
fprintf(stderr, "ERROR: Could not set state!\n");
return -1;
}
//----------
printf("Setting SAVEOP state for device 4.\n");
if (EtherCAT_state_change(&master, &master.slaves[4], EC_STATE_SAVEOP) != 0)
{
fprintf(stderr, "ERROR: Could not set state!\n");
return -1;
}
//----------
printf("Setting OP state for bus coupler.\n");
if (EtherCAT_state_change(&master, &master.slaves[0], EC_STATE_OP) != 0)
{
fprintf(stderr, "ERROR: Could not set state!\n");
return -1;
}
//----------
printf("Setting OP state for device 1.\n");
if (EtherCAT_state_change(&master, &master.slaves[1], EC_STATE_OP) != 0)
{
fprintf(stderr, "ERROR: Could not set state!\n");
return -1;
}
//----------
printf("Setting OP state for device 4.\n");
if (EtherCAT_state_change(&master, &master.slaves[4], EC_STATE_OP) != 0)
{
fprintf(stderr, "ERROR: Could not set state!\n");
return -1;
}
//----------
word = 0;
printf("Starting thread...\n");
if (EtherCAT_start(&master, 5, write_data, NULL, 10000) != 0)
{
return -1;
}
continue_running = 1;
while (continue_running)
{
usleep(200000);
word += 1000;
word = word & 0x7FFF;
}
//----------
printf("Stopping master thread...\n");
EtherCAT_stop(&master);
EtherCAT_master_clear(&master);
printf("Finished.\n");
return 0;
}
//---------------------------------------------------------------
void write_data(unsigned char *data)
{
data[0] = word & 0xFF;
data[1] = (word & 0xFF00) >> 8;
data[2] = word & 0xFF;
data[3] = (word & 0xFF00) >> 8;
data[4] = 0x01;
}
//---------------------------------------------------------------
void signal_handler(int signum)
{
if (signum == SIGINT || signum == SIGTERM)
{
continue_running = 0;
}
}
//---------------------------------------------------------------

287
user/main_gui.cpp Normal file
View File

@@ -0,0 +1,287 @@
//---------------------------------------------------------------
//
// m a i n _ g u i . c p p
//
// $LastChangedDate$
// $Author$
//
//---------------------------------------------------------------
#include <stdio.h>
#include <string.h> // memset()
#include <unistd.h> // usleep()
#include <signal.h>
#include <fltk/Window.h>
#include <fltk/Slider.h>
#include <fltk/ValueOutput.h>
#include <fltk/FillSlider.h>
#include <fltk/CheckButton.h>
#include <fltk/run.h>
using namespace fltk;
#include "ec_globals.h"
#include "ec_master.h"
#define SLIDER_UPDATE_CYCLE 0.02
#define VALUES_UPDATE_CYCLE 0.50
//---------------------------------------------------------------
unsigned short int write_value;
signed short int read_value;
unsigned char dig_value;
void write_data(unsigned char *);
void read_data(unsigned char *);
void slider_write_callback(Widget *, void *);
void slider_read_timeout(void *);
void values_timeout(void *);
Window *window;
Slider *slider_read, *slider_write;
ValueOutput *output_cycle, *output_jitter, *output_work, *output_busy, *output_bus;
CheckButton *check1, *check2, *check3, *check4;
EtherCAT_master_t master;
double max_cycle, max_jitter, max_work, max_busy, max_bus;
//---------------------------------------------------------------
#define SLAVE_COUNT 7
EtherCAT_slave_t slaves[SLAVE_COUNT] =
{
ECAT_INIT_SLAVE(Beckhoff_EK1100),
ECAT_INIT_SLAVE(Beckhoff_EL4102),
ECAT_INIT_SLAVE(Beckhoff_EL3162),
ECAT_INIT_SLAVE(Beckhoff_EL1014),
ECAT_INIT_SLAVE(Beckhoff_EL5001),
ECAT_INIT_SLAVE(Beckhoff_EL2004),
ECAT_INIT_SLAVE(Beckhoff_EL3102)
};
//---------------------------------------------------------------
int main(int argc, char **argv)
{
//unsigned int i;
EtherCAT_slave_t *buskoppler, *input, *output, *dig_in, *dig_out;
struct sched_param sched;
printf("CatEther-Testprogramm.\n\n");
//----------
#if 1
printf("Setting highest task priority...\n");
sched.sched_priority = sched_get_priority_max(SCHED_RR);
if (sched_setscheduler(0, SCHED_RR, &sched) == -1)
{
fprintf(stderr, "ERROR: Could not set priority: %s\n", strerror(errno));
return -1;
}
#endif
//----------
printf("Initializing master...\n");
EtherCAT_master_init(&master, "eth1");
printf("Checking slaves...\n");
if (EtherCAT_check_slaves(&master, slaves, SLAVE_COUNT) != 0)
{
fprintf(stderr, "ERROR while searching for slaves!\n");
return -1;
}
//----------
// Check for slaves
buskoppler = &slaves[0];
output = &slaves[1];
dig_in = &slaves[3];
dig_out = &slaves[5];
input = &slaves[6];
// Set Mapping addresses
output->logical_address0 = 0x00000000;
input->logical_address0 = 0x00000004;
dig_in->logical_address0 = 0x0000000F;
dig_out->logical_address0 = 0x0000000E;
//----------
printf("Init output slave...\n");
if (EtherCAT_activate_slave(&master, output) != 0)
{
fprintf(stderr, "ERROR: Could not init slave!\n");
return -1;
}
printf("Init input slave...\n");
if (EtherCAT_activate_slave(&master, input) != 0)
{
fprintf(stderr, "ERROR: Could not init slave!\n");
return -1;
}
printf("Init digital input slave...\n");
if (EtherCAT_activate_slave(&master, dig_in) != 0)
{
fprintf(stderr, "ERROR: Could not init slave!\n");
return -1;
}
printf("Init digital output slave...\n");
if (EtherCAT_activate_slave(&master, dig_out) != 0)
{
fprintf(stderr, "ERROR: Could not init slave!\n");
return -1;
}
//----------
printf("Starting FLTK window...\n");
window = new Window(300, 300);
window->begin();
slider_read = new FillSlider(50, 10, 40, 280);
slider_read->set_vertical();
slider_read->buttoncolor(BLUE);
slider_read->deactivate();
slider_write = new Slider(110, 10, 40, 280);
slider_write->set_vertical();
slider_write->callback(slider_write_callback, NULL);
output_cycle = new ValueOutput(200, 50, 90, 25, "Cycle time [µs]");
output_cycle->align(ALIGN_LEFT | ALIGN_TOP);
output_jitter = new ValueOutput(200, 90, 90, 25, "Jitter [%]");
output_jitter->align(ALIGN_LEFT | ALIGN_TOP);
output_work = new ValueOutput(200, 130, 90, 25, "Work time [µs]");
output_work->align(ALIGN_LEFT | ALIGN_TOP);
output_busy = new ValueOutput(200, 170, 90, 25, "Busy rate [%]");
output_busy->align(ALIGN_LEFT | ALIGN_TOP);
output_bus = new ValueOutput(200, 210, 90, 25, "Bus time [µs]");
output_bus->align(ALIGN_LEFT | ALIGN_TOP);
check1 = new CheckButton(200, 240, 30, 25, "1");
check2 = new CheckButton(250, 240, 30, 25, "2");
check3 = new CheckButton(200, 270, 30, 25, "3");
check4 = new CheckButton(250, 270, 30, 25, "4");
// output_cycle = new Output(200, 35, 90, 25);
window->end();
window->show();
add_timeout(SLIDER_UPDATE_CYCLE, slider_read_timeout, NULL);
add_timeout(VALUES_UPDATE_CYCLE, values_timeout, NULL);
printf("Starting thread...\n");
if (EtherCAT_start(&master, 20, write_data, read_data, 10000) != 0)
{
return -1;
}
run(); // Start FLTK loop
remove_timeout(slider_read_timeout, NULL);
remove_timeout(values_timeout, NULL);
printf("Stopping master thread...\n");
EtherCAT_stop(&master);
printf("Deactivating slaves...\n");
EtherCAT_deactivate_slave(&master, dig_out);
EtherCAT_deactivate_slave(&master, dig_in);
EtherCAT_deactivate_slave(&master, input);
EtherCAT_deactivate_slave(&master, output);
EtherCAT_deactivate_slave(&master, buskoppler);
EtherCAT_master_clear(&master);
printf("Finished.\n");
return 0;
}
//---------------------------------------------------------------
void write_data(unsigned char *data)
{
data[0] = write_value & 0xFF;
data[1] = (write_value & 0xFF00) >> 8;
data[14] = (write_value * 16 / 32767) & 0x0F;
}
//---------------------------------------------------------------
void read_data(unsigned char *data)
{
read_value = data[5] | data[6] << 8;
dig_value = data[15];
}
//---------------------------------------------------------------
void slider_read_timeout(void *data)
{
slider_read->value((double) read_value / 65536 + 0.5);
slider_read->redraw();
check1->value(dig_value & 1);
check2->value(dig_value & 2);
check3->value(dig_value & 4);
check4->value(dig_value & 8);
if (max_cycle < master.last_cycle_time) max_cycle = master.last_cycle_time;
if (max_jitter < master.last_jitter) max_jitter = master.last_jitter;
if (max_work < master.last_cycle_work_time) max_work = master.last_cycle_work_time;
if (max_busy < master.last_cycle_busy_rate) max_busy = master.last_cycle_busy_rate;
if (max_bus < master.bus_time) max_bus = master.bus_time;
repeat_timeout(SLIDER_UPDATE_CYCLE, slider_read_timeout, NULL);
}
//---------------------------------------------------------------
void values_timeout(void *data)
{
output_cycle->value(max_cycle * 1000000.0);
output_jitter->value(max_jitter);
output_work->value(max_work * 1000000.0);
output_busy->value(max_busy);
output_bus->value(max_bus * 1000000.0);
max_cycle = max_jitter = max_work = max_busy = max_bus = 0.0;
repeat_timeout(VALUES_UPDATE_CYCLE, values_timeout, NULL);
}
//---------------------------------------------------------------
void slider_write_callback(Widget *sender, void *data)
{
write_value = (short unsigned int) (32767 * slider_write->value() + 0.5);
}
//---------------------------------------------------------------