]> rtime.felk.cvut.cz Git - eurobot/public.git/commitdiff
Pridan build a aplikace pro testovani CANu na h8canusb.
authorsojka <sojka@78ed6b52-5822-0410-8084-884f26da6e90>
Tue, 27 Mar 2007 17:04:36 +0000 (17:04 +0000)
committersojka <sojka@78ed6b52-5822-0410-8084-884f26da6e90>
Tue, 27 Mar 2007 17:04:36 +0000 (17:04 +0000)
git-svn-id: svn+ssh://rtime.felk.cvut.cz/var/svn/eurobot/trunk/soft@130 78ed6b52-5822-0410-8084-884f26da6e90

94 files changed:
app/cantest/Makefile [new file with mode: 0644]
app/cantest/Makefile.omk [new file with mode: 0644]
app/cantest/can_drive/Makefile [new file with mode: 0644]
app/cantest/can_drive/Makefile.omk [new file with mode: 0644]
app/cantest/can_drive/can_fn.c [new file with mode: 0644]
app/cantest/can_drive/can_fn.h [new file with mode: 0644]
app/cantest/can_drive/can_odpad.c [new file with mode: 0644]
app/cantest/can_drive/can_queue.c [new file with mode: 0644]
app/cantest/can_drive/can_queue.h [new file with mode: 0644]
app/cantest/can_drive/can_test.c [new file with mode: 0644]
app/cantest/can_drive/canmsg.h [new file with mode: 0644]
app/cantest/can_drive/constants.h [new file with mode: 0644]
app/cantest/can_drive/rs_test.c [new file with mode: 0644]
app/cantest/can_drive/rs_test2.c [new file with mode: 0644]
app/cantest/canfestival/Makefile [new file with mode: 0644]
app/cantest/canfestival/Makefile.omk [new file with mode: 0644]
app/cantest/canfestival/applislave/Makefile [new file with mode: 0644]
app/cantest/canfestival/applislave/Makefile.omk [new file with mode: 0644]
app/cantest/canfestival/applislave/appli.c [new file with mode: 0644]
app/cantest/canfestival/applislave/example_objdict.c [new file with mode: 0644]
app/cantest/canfestival/applislave/muj_objdict.c [new file with mode: 0644]
app/cantest/canfestival/applislave/objdict-sync.c [new file with mode: 0644]
app/cantest/canfestival/applislave/objdict.c [new file with mode: 0644]
app/cantest/canfestival/applislave/objdict.h [new file with mode: 0644]
app/cantest/canfestival/applislave/objdict.html [new file with mode: 0644]
app/cantest/canfestival/applislave/objdict.xml [new file with mode: 0644]
app/cantest/canfestival/driver/Makefile [new file with mode: 0644]
app/cantest/canfestival/driver/Makefile.omk [new file with mode: 0644]
app/cantest/canfestival/driver/canOpenDriver.c [new file with mode: 0644]
app/cantest/canfestival/driver/interrupt.c [new file with mode: 0644]
app/cantest/canfestival/driver/timerhw.c [new file with mode: 0644]
app/cantest/canfestival/driver/variahw.c [new file with mode: 0644]
app/cantest/canfestival/include/Makefile [new file with mode: 0644]
app/cantest/canfestival/include/Makefile.omk [new file with mode: 0644]
app/cantest/canfestival/include/can.h [new file with mode: 0644]
app/cantest/canfestival/include/config.h [new file with mode: 0644]
app/cantest/canfestival/include/data.h [new file with mode: 0644]
app/cantest/canfestival/include/def.h [new file with mode: 0644]
app/cantest/canfestival/include/hc12/Makefile [new file with mode: 0644]
app/cantest/canfestival/include/hc12/Makefile.omk [new file with mode: 0644]
app/cantest/canfestival/include/hc12/applicfg.h [new file with mode: 0644]
app/cantest/canfestival/include/hc12/canOpenDriver.h [new file with mode: 0644]
app/cantest/canfestival/include/hc12/candriver.h [new file with mode: 0644]
app/cantest/canfestival/include/hc12/error.h [new file with mode: 0644]
app/cantest/canfestival/include/hc12/interrupt.h [new file with mode: 0644]
app/cantest/canfestival/include/hc12/timerhw.h [new file with mode: 0644]
app/cantest/canfestival/include/led.h [new file with mode: 0644]
app/cantest/canfestival/include/lifegrd.h [new file with mode: 0644]
app/cantest/canfestival/include/lss.h [new file with mode: 0644]
app/cantest/canfestival/include/nmtMaster.h [new file with mode: 0644]
app/cantest/canfestival/include/nmtSlave.h [new file with mode: 0644]
app/cantest/canfestival/include/nvram.h [new file with mode: 0644]
app/cantest/canfestival/include/objacces.h [new file with mode: 0644]
app/cantest/canfestival/include/objdictdef.h [new file with mode: 0644]
app/cantest/canfestival/include/pdo.h [new file with mode: 0644]
app/cantest/canfestival/include/peak/applicfg.h [new file with mode: 0644]
app/cantest/canfestival/include/peak/linuxCan.h [new file with mode: 0644]
app/cantest/canfestival/include/peak/timerhw.h [new file with mode: 0644]
app/cantest/canfestival/include/sdo.h [new file with mode: 0644]
app/cantest/canfestival/include/states.h [new file with mode: 0644]
app/cantest/canfestival/include/sync.h [new file with mode: 0644]
app/cantest/canfestival/include/timer.h [new file with mode: 0644]
app/cantest/canfestival/odstraneni-potize.txt [new file with mode: 0644]
app/cantest/canfestival/src/Makefile [new file with mode: 0644]
app/cantest/canfestival/src/Makefile.omk [new file with mode: 0644]
app/cantest/canfestival/src/lifegrd.c [new file with mode: 0644]
app/cantest/canfestival/src/lss.c [new file with mode: 0644]
app/cantest/canfestival/src/nmtMaster.c [new file with mode: 0644]
app/cantest/canfestival/src/nmtSlave.c [new file with mode: 0644]
app/cantest/canfestival/src/objacces.c [new file with mode: 0644]
app/cantest/canfestival/src/pdo.c [new file with mode: 0644]
app/cantest/canfestival/src/sdo.c [new file with mode: 0644]
app/cantest/canfestival/src/states.c [new file with mode: 0644]
app/cantest/canfestival/src/sync.c [new file with mode: 0644]
app/cantest/canfestival/src/timer.c [new file with mode: 0644]
app/cantest/timer/Makefile [new file with mode: 0644]
app/cantest/timer/Makefile.omk [new file with mode: 0644]
app/cantest/timer/timer_tst_cmd.c [new file with mode: 0644]
app/cantest/timer/timerhw.c [new file with mode: 0644]
app/cantest/timer/timerhw.h [new file with mode: 0644]
build/h8canusb/Makefile [new symlink]
build/h8canusb/Makefile.omk [new symlink]
build/h8canusb/Makefile.rules [new symlink]
build/h8canusb/README.makerules [new symlink]
build/h8canusb/app [new symlink]
build/h8canusb/arch [new symlink]
build/h8canusb/board [new symlink]
build/h8canusb/cantest [new symlink]
build/h8canusb/common [new symlink]
build/h8canusb/config.omk [new symlink]
build/h8canusb/hello [new symlink]
build/h8canusb/libcan [new symlink]
build/h8canusb/libs4c [new symlink]
build/prepare_infrastructure

diff --git a/app/cantest/Makefile b/app/cantest/Makefile
new file mode 100644 (file)
index 0000000..f595272
--- /dev/null
@@ -0,0 +1,14 @@
+# Generic directory or leaf node makefile for OCERA make framework
+
+ifndef MAKERULES_DIR
+MAKERULES_DIR := $(shell ( old_pwd="" ;  while [ ! -e Makefile.rules ] ; do if [ "$$old_pwd" == `pwd`  ] ; then exit 1 ; else old_pwd=`pwd` ; cd -L .. 2>/dev/null ; fi ; done ; pwd ) )
+endif
+
+ifeq ($(MAKERULES_DIR),)
+all : default
+.DEFAULT::
+       @echo -e "\nThe Makefile.rules has not been found in this or partent directory\n"
+else   
+include $(MAKERULES_DIR)/Makefile.rules
+endif
+
diff --git a/app/cantest/Makefile.omk b/app/cantest/Makefile.omk
new file mode 100644 (file)
index 0000000..5baf5ed
--- /dev/null
@@ -0,0 +1,3 @@
+# -*- makefile -*-
+
+SUBDIRS = $(ALL_OMK_SUBDIRS)
diff --git a/app/cantest/can_drive/Makefile b/app/cantest/can_drive/Makefile
new file mode 100644 (file)
index 0000000..f595272
--- /dev/null
@@ -0,0 +1,14 @@
+# Generic directory or leaf node makefile for OCERA make framework
+
+ifndef MAKERULES_DIR
+MAKERULES_DIR := $(shell ( old_pwd="" ;  while [ ! -e Makefile.rules ] ; do if [ "$$old_pwd" == `pwd`  ] ; then exit 1 ; else old_pwd=`pwd` ; cd -L .. 2>/dev/null ; fi ; done ; pwd ) )
+endif
+
+ifeq ($(MAKERULES_DIR),)
+all : default
+.DEFAULT::
+       @echo -e "\nThe Makefile.rules has not been found in this or partent directory\n"
+else   
+include $(MAKERULES_DIR)/Makefile.rules
+endif
+
diff --git a/app/cantest/can_drive/Makefile.omk b/app/cantest/can_drive/Makefile.omk
new file mode 100644 (file)
index 0000000..ffd8952
--- /dev/null
@@ -0,0 +1,18 @@
+# -*- makefile -*-
+
+bin_PROGRAMS  = can_test 
+#rs_test2
+
+can_test_SOURCES = can_test.c can_fn.c
+#cant_test_LIBS = can_fn
+
+can_test_LIBS = boot_fn arch_drivers sci_channels excptvec misc cmdproc cmdprocio
+can_test_MOREOBJS = $(USER_LIB_DIR)/system_stub.o
+
+
+#rs_test2_SOURCES = rs_test2.c
+
+#rs_test2_LIBS = boot_fn arch_drivers sci_channels excptvec
+#rs_test2_MOREOBJS = $(USER_LIB_DIR)/system_stub.o
+
+link_VARIANTS = ram flash
diff --git a/app/cantest/can_drive/can_fn.c b/app/cantest/can_drive/can_fn.c
new file mode 100644 (file)
index 0000000..e8ff980
--- /dev/null
@@ -0,0 +1,726 @@
+/* procesor H8S/2638 version:zacatek */
+/* function for H8S/2638 HCAN module */
+#include "can_fn.h"
+#include <types.h>
+#include <cpu_def.h>
+#include <h8s2638h.h>
+#include <system_def.h>
+#include <string.h>
+//#include <boot_fn.h>
+#include <stdio.h>
+
+#define DEBUG 1
+#define DEBUG_LOW 0
+#define PRINT_BAUD 1
+
+#define NUMBER_OF_CAN_CHANELS 2
+#define HCAN_SHIFT (HCAN1_MCR-HCAN0_MCR) /* shift between hcan chanels */
+
+extern uint16_t info[10];
+extern zasobnik_zprav_t zpravy_zas_hcan0,zpravy_zas_hcan1;
+
+#if DEBUG
+ #ifndef DEB_LED_OUT
+  #define DEB_LED_OUT
+  static void deb_led_out(char val)
+  {
+    if (val&1)
+      DEB_LED_ON(0);
+    else
+      DEB_LED_OFF(0);
+    if (val&2)
+      DEB_LED_ON(1);
+    else
+      DEB_LED_OFF(1);
+    if (val&4)
+      DEB_LED_ON(2);
+    else
+      DEB_LED_OFF(2);
+    if (val&8)
+      DEB_LED_ON(3);
+    else
+      DEB_LED_OFF(3);
+   }
+ #endif
+#endif
+
+/* ---- handling interupt vectors */
+void test_unhandled_isr(void)
+{
+  #if DEBUG
+  deb_led_out(2);
+  #endif
+  /*sgm_lcd_gotoxy(0,0);*/
+  /*sgm_lcd_wrstr("Unhandled ISR");*/
+  while(1);
+}
+
+__u16 prevod_mask[16]=
+{0x0100, 0x0200, 0x0400, 0x0800, 0x1000, 0x2000, 0x4000, 0x8000,
+ 0x0001, 0x0002, 0x0004, 0x0008, 0x0010, 0x0020, 0x0040, 0x0080};
+
+/* match betwen bit and mailbox number represented by this bit */
+__u8 bit2name[16]=
+{8, 9, 10, 11, 12, 13, 14, 15,
+ 0, 1, 2, 3, 4, 5, 6, 7};
+
+void hcan0_isr(void)
+{
+  uint16_t mask;
+  int idx;
+
+  #if DEBUG
+    prerus_hcan0++;
+  #endif
+  if (*HCAN0_IRR&IRR_IRR0m) ;
+    *HCAN0_IRR |= IRR_IRR0m; /* set register to handled */
+//  deb_led_out(1);
+//  FlWait(10*100000);
+  if (*HCAN0_IRR&IRR_IRR1m)
+  {
+    /* a message stored in  a mailbox */
+    for (idx=0, mask=1;*HCAN0_RXPR;idx++,mask<<=1) {
+      if (!(mask&*HCAN0_RXPR)) 
+        continue;
+      *HCAN0_RXPR|=mask; /* clear RXPR */
+      if(idx<8)
+        can_recive_msg(0, idx+8, 0); /* move message to buffer */
+      else
+        can_recive_msg(0, idx-8, 0); /* move message to buffer */
+    }
+  };
+//  deb_led_out(2);
+//  FlWait(10*100000);
+  if(*HCAN0_IRR&IRR_IRR8m) { /* a message send from mailbox */
+    for (idx=0, mask=1;*HCAN0_TXACK;idx++,mask<<=1) {
+      if (!(mask&*HCAN0_TXACK)) continue;
+        *HCAN0_TXACK|=mask; /* clear TXACK */
+    };
+    *HCAN0_IRR|=IRR_IRR8m;
+  };
+
+  #if 0
+  if (*HCAN0_IRR&IRR_IRR2m) ;
+  #endif
+  //printf("register IRR:0x%X \n",*HCAN0_IRR);
+  #if DEBUG
+    deb_led_out(0);
+  #endif
+  deb_led_out(3);
+}
+
+void hcan1_isr(void)
+{
+  uint16_t mask;
+  int idx;
+
+  #if DEBUG
+    prerus_hcan1++;
+  #endif
+  if (*HCAN1_IRR&IRR_IRR0m)
+    *HCAN1_IRR |= IRR_IRR0m; /* set register to handled */
+
+  if (*HCAN1_IRR&IRR_IRR1m)
+  {
+    /* a message stored in  a mailbox */
+    for (idx=0, mask=1;*HCAN1_RXPR;idx++,mask<<=1) {
+      if (!(mask&*HCAN1_RXPR)) 
+        continue;
+      *HCAN1_RXPR|=mask; /* clear RXPR */
+      if(idx<8)
+        can_recive_msg(1, idx+8, 0); /* move message to buffer */
+      else
+        can_recive_msg(1, idx-8, 0); /* move message to buffer */
+    }
+  };
+
+  if(*HCAN1_IRR&IRR_IRR8m) { /* a message send from mailbox */
+    for (idx=0, mask=1;*HCAN1_TXACK;idx++,mask<<=1) {
+      if (!(mask&*HCAN1_TXACK)) continue;
+        *HCAN1_TXACK|=mask; /* clear TXACK */
+    };
+    *HCAN1_IRR|=IRR_IRR8m;
+  };
+
+  #if 0
+  if (*HCAN0_IRR&IRR_IRR2m) ;
+  #endif
+  //printf("register IRR:0x%X \n",*HCAN0_IRR);
+
+  #if DEBUG
+  deb_led_out(1);
+  #endif
+  //while(1);
+}
+
+
+/* ------------------------------------------------------------------------------------------------------------------*/
+/* Function ReadRegistersCan prints registers values by standart function "printf".
+   chanel - number of HCAN chanel,
+   param - -1 .. registers MCR - LAFM, MSTPCRC 
+           0-16  .. MC0-15 and MD0-15 */
+void ReadRegistersCan(int chanel, int param) {
+      volatile __u8  *hcan_mc, *hcan_md;
+      int can_mailbox_c_offset,can_mailbox_d_offset;
+
+      printf("ReadRegistersCan chanel:%d param:%d\n", chanel, param);
+        //printf("chanel:%d\n", chanel);
+        //printf("addr:0x%x, HCAN_BCR_o:0x%x\n", (uint16_t) (HCAN0_BCR+chanel*HCAN_BCR_o), (uint16_t) HCAN_BCR_o);
+      if (param<0) {
+       printf("register MCR:0x%X,register GSR:0x%X \n",*(HCAN0_MCR+chanel*HCAN_MCR_o),*(HCAN0_GSR+chanel*HCAN_GSR_o));
+       printf("register BCR:0x%X,register MBCR:0x%X \n",*(HCAN0_BCR+chanel*HCAN_BCR_o),*(HCAN0_MBCR+chanel*HCAN_MBCR_o));
+       printf("register TXPR:0x%X,register TXCR:0x%X \n",*(HCAN0_TXPR+chanel*HCAN_TXPR_o),*(HCAN0_TXCR+chanel*HCAN_TXCR_o));
+       printf("register TXACK:0x%X,register ABACK:0x%X \n",*(HCAN0_TXACK+chanel*HCAN_TXACK_o),*(HCAN0_ABACK+chanel*HCAN_ABACK_o));
+       printf("register RXPR:0x%X,register RFPR:0x%X \n",*(HCAN0_RXPR+chanel*HCAN_RXPR_o),*(HCAN0_RFPR+chanel*HCAN_RFPR_o));
+       printf("register IRR:0x%X,register MBIMR:0x%X \n",*(HCAN0_IRR+chanel*HCAN_IRR_o),*(HCAN0_MBIMR+chanel*HCAN_MBIMR_o));
+       printf("register IMR:0x%X,register REC:0x%X \n",*(HCAN0_IMR+chanel*HCAN_IMR_o),*(HCAN0_REC+chanel*HCAN_REC_o));
+       printf("register TEC:0x%X,register UMSR:0x%X \n",*(HCAN0_TEC+chanel*HCAN_TEC_o),*(HCAN0_UMSR+chanel*HCAN_UMSR_o));
+       printf("register LAFML:0x%X,register LAFMH:0x%X \n",*(HCAN0_LAFML+chanel*HCAN_LAFML_o),*(HCAN0_LAFMH+chanel*HCAN_LAFMH_o));
+       printf("register MSTPCRC:0x%X \n",*SYS_MSTPCRC);
+      };
+      if (param>=0) {
+        can_mailbox_c_offset=param*HCAN_MC_LENGTH;
+        can_mailbox_d_offset=param*HCAN_MD_LENGTH;
+//        hcan_mc=(HCAN0_MC0+chanel*HCAN_MC_o+can_mailbox_c_offset);
+//        hcan_md=(HCAN0_MD0+chanel*HCAN_MD_o+can_mailbox_d_offset);
+
+        printf("HCAN%d MC%d bytes 0-8: ", chanel, param);
+        printf("0x %02x%02x %02x%02x %02x%02x %02x%02x\n",
+               *(hcan_mc+0),*(hcan_mc+1),*(hcan_mc+2),*(hcan_mc+3),
+               *(hcan_mc+4), *(hcan_mc+5), *(hcan_mc+6), *(hcan_mc+7));
+        printf("HCAN%d MD%d bytes 0-8: ", chanel, param);
+        printf("0x %02x%02x %02x%02x %02x%02x %02x%02x\n",
+               *(hcan_md+0),*(hcan_md+1),*(hcan_md+2),*(hcan_md+3),
+               *(hcan_md+4), *(hcan_md+5), *(hcan_md+6), *(hcan_md+7));
+        //printf("\n");
+      };
+}
+/* ------------------------------------------------------------------------------------------------------------------*/
+/*  Init intetrrupts vectors 
+     0 - HCAN0 module, 1 - HCAN1 module
+    return 1 if OK
+*/
+int Can_Enable(int can_chanel)
+{
+   /* set interrupts vectors for HCAN module*/
+   if (can_chanel==0)
+   {
+     if(!(*SYS_MSTPCRC&MSTPCRC_MSTPC3m))
+       printf("Warning try to enable hcan%d which is not in module stop\n", can_chanel);
+     excptvec_set(108,hcan0_isr);
+     excptvec_set(109,hcan0_isr);
+     *SYS_MSTPCRC&=~MSTPCRC_MSTPC3m;   /* enable HCAN power */
+     #if DEBUG
+       printf("HCAN0 isr set:\n");
+     #endif
+   };
+   if (can_chanel==1)
+   {
+     if(!(*SYS_MSTPCRC&MSTPCRC_MSTPC2m))
+       printf("Warning try to enable hcan%d which is not in module stop\n", can_chanel);
+     excptvec_set(106,hcan1_isr);
+     excptvec_set(107,hcan1_isr);
+     *SYS_MSTPCRC&=~MSTPCRC_MSTPC2m;   /* enable HCAN power */
+     #if DEBUG
+       printf("HCAN1 isr set:\n");
+     #endif
+   };
+   return(1); /* selected HCAN chanel is in bit configuration mode */
+};
+
+/* -------------------------------- Working on functions --------------------------------------- */
+/*  wake_up_mode - set to 1 for wake up by CAN bus operation
+*/
+int can_sleep(can_chanel,wake_up_mode)
+{
+  __u8 *hcan_mcr;
+
+  switch(can_chanel) {
+    case 0:
+      hcan_mcr=(__u8 *) HCAN0_MCR;
+      if(*SYS_MSTPCRC&MSTPCRC_MSTPC3m) {
+        printf("Error unable to sleep hcan%d is in module stop\n", can_chanel);
+        return 1;
+      }
+      break;
+    case 1:
+      hcan_mcr=(__u8 *) HCAN1_MCR;
+      if(*SYS_MSTPCRC&MSTPCRC_MSTPC2m) {
+        printf("Error unable to sleep hcan%d is in module stop\n", can_chanel);
+        return 1;
+      }
+      break;
+    default:
+      return 1;
+  };
+  if(wake_up_mode)
+    *hcan_mcr|=MCR_MCR7m; /* set wake up mode, wake by CAN bus activity */
+  else
+    *hcan_mcr&=~MCR_MCR7m;
+  *hcan_mcr|=MCR_MCR5m; /* sleep chanel */
+  return 0;
+};
+/* --------------------------------------------------------------------------------- */
+
+int can_wake(can_chanel)
+{
+  __u8 *hcan_mcr;
+
+  switch(can_chanel) {
+    case 0:
+      hcan_mcr=(__u8 *) HCAN0_MCR;
+      if(*SYS_MSTPCRC&MSTPCRC_MSTPC3m) {
+        printf("Error unable to wake hcan%d is in module stop\n", can_chanel);
+        return 1;
+      }
+      break;
+    case 1:
+      hcan_mcr=(__u8 *) HCAN1_MCR;
+      if(*SYS_MSTPCRC&MSTPCRC_MSTPC2m) {
+        printf("Error unable to wake hcan%d is in module stop\n", can_chanel);
+        return 1;
+      }
+      break;
+    default:
+      return 1;
+  };
+  *hcan_mcr&=~MCR_MCR5m; /* wake chanel */
+  return 0;
+};
+/* --------------------------------------------------------------------------------- */
+int ClearMessages(zasobnik_zprav_t *pstack,int count_mes)
+{
+  if(pstack->obs_cnt>=count_mes)
+  {
+    pstack->obs_cnt-=count_mes;
+    return(count_mes);
+  };
+  return(-pstack->obs_cnt);
+};
+/* --------------------------------------------------------------------------------------------- */ 
+int can_set_registers(int can_chanel, can_settings_t *can_settings_hcan)
+{  /* Seting HCAN registers */
+  unsigned int hcanChS,i,bank;
+
+  printf("can_set_registers HCAN%d\n", can_chanel);
+  hcanChS=can_chanel;
+  if(can_chanel<NUMBER_OF_CAN_CHANELS) {
+   /* ** Bit Configuration mode ** */
+   /* bit configuration mode - setting BCR */
+     *(HCAN0_BCR+hcanChS*HCAN_BCR_o)=((*(HCAN0_BCR+hcanChS*HCAN_BCR_o)&~BCR_BRPm)
+                                     |CAN_BRP2BRPM(can_settings_hcan->bcr_brp));//0x00
+     *(HCAN0_BCR+hcanChS*HCAN_BCR_o)=((*(HCAN0_BCR+hcanChS*HCAN_BCR_o)&~BCR_SJWm)
+                                     |CAN_SJW2SJWM(can_settings_hcan->bcr_sjw));//0x02
+     *(HCAN0_BCR+hcanChS*HCAN_BCR_o)=((*(HCAN0_BCR+hcanChS*HCAN_BCR_o)&~BCR_TSEG1m)
+                                     |CAN_TSEG12TSEG1M(can_settings_hcan->bcr_tseg1));//0x04
+     *(HCAN0_BCR+hcanChS*HCAN_BCR_o)=((*(HCAN0_BCR+hcanChS*HCAN_BCR_o)&~BCR_TSEG2m)
+                                     |CAN_TSEG22TSEG2M(can_settings_hcan->bcr_tseg2));//0x03
+     *(HCAN0_BCR+hcanChS*HCAN_BCR_o)=((*(HCAN0_BCR+hcanChS*HCAN_BCR_o)&~BCR_BCR15m)
+                                     |(BCR_BCR15m&((can_settings_hcan->bcr_bsp)<<7)));
+   /* bit configuration mode - setting MBCR */
+     *(HCAN0_MBCR+hcanChS*HCAN_MBCR_o) &= ~(MBCR_MBCR14m|MBCR_MBCR15m); /* mailbox set for transmission */
+     *(HCAN0_MBCR+hcanChS*HCAN_MBCR_o) |= (MBCR_MBCR1m|MBCR_MBCR2m); /* mailbox set for reception */
+   /* mailbox RAM initialization - crear all registers MC and MD */
+     for(bank=0;bank<16;bank++) {
+       for(i=0;i<8;i++) {
+         *(HCAN0_MC0+hcanChS*HCAN_MC_o+bank*HCAN_MC_LENGTH+i)=0x00;
+         *(HCAN0_MD0+hcanChS*HCAN_MD_o+bank*HCAN_MD_LENGTH+i)=0x00;
+       };
+     };
+   /* set Message transmission Method */
+     //*HCAN0_MCR &= ~MCR_MCR2m /* by message identifier priority -> 0 (initial value) */
+   /* Exit bit configuration mode */
+     *(HCAN0_MCR+hcanChS*HCAN_MCR_o)&=~MCR_MCR0m; /* Transition into normal operation mode */
+     while(*(HCAN0_GSR+hcanChS*HCAN_GSR_o)&GSR_GSR3m); /* Wait for transition end */
+   /* ** Normal configuration mode ** */
+   /* setting communication */
+     *(HCAN0_IMR+hcanChS*HCAN_IMR_o)&=~(IMR_IMR1m|IMR_IMR8m); /* (initial=0xffff) */ /* interrupt mask register */
+     *(HCAN0_MBIMR+hcanChS*HCAN_MBIMR_o)&=~(MBIMR_MBIMR0m|MBIMR_MBIMR1m|MBIMR_MBIMR14m|MBIMR_MBIMR15m); 
+               /* 1 - disable individual interrupt requests (initial 0xffff) */
+   /* MC[x], MD[x] settings */
+
+   /* Local acceptance filter masks */
+     *(HCAN0_LAFML+hcanChS*HCAN_LAFML_o)=can_settings_hcan->lafml;
+     *(HCAN0_LAFMH+hcanChS*HCAN_LAFMH_o)=can_settings_hcan->lafmh;
+  }
+  #if DEBUG
+    printf("can_set_registers finished\n");
+  #endif
+  return(1);
+};
+/* ---------------------------------------------------------------------------------------------------------------- */
+int can_change_registers(int can_chanel,can_settings_t *new_set, can_settings_t *can_settings_hcan)
+{
+  /* save new settings in the chanels structure */
+  can_settings_hcan->bcr_sjw=new_set->bcr_sjw;
+  can_settings_hcan->bcr_brp=new_set->bcr_brp;
+  can_settings_hcan->bcr_bsp=new_set->bcr_bsp;
+  can_settings_hcan->bcr_tseg1=new_set->bcr_tseg1;
+  can_settings_hcan->bcr_tseg2=new_set->bcr_tseg2;
+
+  /* sets CAN chanels registers  */
+  switch(can_chanel) {
+    case 0:
+      if(*SYS_MSTPCRC&MSTPCRC_MSTPC3m) {
+        printf("Warning try to change settings hcan%d which is in module stop\n", can_chanel);
+        return -2;
+      };
+      *HCAN0_MCR|=MCR_MCR0m; /* software reset HCAN chanel */
+      break;
+    case 1:
+      if(*SYS_MSTPCRC&MSTPCRC_MSTPC2m) {
+        printf("Warning try to change settings hcan%d which is in module stop\n", can_chanel);
+        return -2;
+      };
+      *HCAN1_MCR|=MCR_MCR0m; /* software reset HCAN chanel */
+      break;
+  };
+  can_set_registers(can_chanel,can_settings_hcan);
+  return 0;
+};
+
+/*---------------------------------------------------------------------------------------------------------------------------------------------- */
+int can_auto_baud(long baud_rate, int *pbrp, int *ptseg1, int *ptseg2, int  sampl_pt, can_calc_const_t *c)
+{
+       long best_error = 1000000000, error;
+       int best_tseg=0, best_brp=0, brp=0;
+        long best_rate=0, best_rate_h8s=0;
+       int tseg=0, tseg1=0, tseg2=0;
+        long clock;
+       
+       clock=CPU_REF_HZ;  /* CPU_SYS_HZ */ /* get system clock */
+       //clock /= c->brp_min;//c->fix_div;
+
+       /* tseg even = round down, odd = round up */
+       for (tseg=(c->sync+c->tseg1_min+c->tseg2_min)*2; tseg<=(c->sync+c->tseg1_max+c->tseg2_max)*2+1; tseg++) 
+        { /* Compute all posibilities of tseg choices (tseg=tseg1+tseg2) */
+               brp = clock/((1+tseg/2)*baud_rate)+tseg%2;
+               brp=(brp/c->brp_inc)*c->brp_inc; /* chose brp step which is possible in system */
+               if ((brp < c->brp_min) || (brp > c->brp_max))
+                       continue;
+               error = baud_rate - clock/(brp*(1+tseg/2));
+               if (error < 0)
+                       error = -error;
+               if (error <= best_error) {
+                       best_error = error;
+                       best_tseg = tseg/2;
+                       best_brp = brp;
+                       best_rate = clock/(brp*(1+tseg/2));
+               }
+       }
+       if (best_error && (baud_rate/best_error < 10)) {
+               printf("baud rate %ld is not possible with %ld Hz clock\n",
+                                                               baud_rate, clock);
+//             printf("%d bps. brp=%d, best_tseg=%d, tseg1=%d, tseg2=%d\n",
+//                             best_rate, best_brp, best_tseg, tseg1, tseg2);
+               return -1;
+       }
+       tseg2 = best_tseg-(sampl_pt*(best_tseg+1))/100;
+       if (tseg2 < c->tseg2_min)
+               tseg2 = c->tseg2_min;
+       if (tseg2 > c->tseg2_max)
+               tseg2 = c->tseg2_max;
+       tseg1 = best_tseg-tseg2;
+       if (tseg1>c->tseg1_max) {
+               tseg1 = c->tseg1_max;
+               tseg2 = best_tseg-tseg1;
+       }
+       #if PRINT_BAUD
+//       printf("Setting %ld bps, rate error %f%%.\n", best_rate, (float) 100*(baud_rate-best_rate)/baud_rate);
+//       printf("brp=%d, best_tseg=%d, tseg1=%d, tseg2=%d, sampl_pt=%d\n",
+//                                     best_brp, best_tseg, tseg1, tseg2,
+//                                     (100*(best_tseg-tseg2)/(best_tseg+1)));
+
+       /* Example for H8S/2638 */
+       best_rate_h8s = clock/(2*(best_brp/2-1+1)*(3+(tseg1-1)+(tseg2-1)));
+        /* This is speed computed from equation in H8S/2638 manual. */
+       /* best_brp ... real brp in system, (int) (best_brp/2-1) ... value in register of brp
+                  tseg1 ... real tseg1 in system, (tseg1-1) ... value in register of tseg1
+          tseg2 ... real tseg2 in system, (tseg2-1) ... value in register of tseg2 */
+       printf("Setting %ld bps. for H8S2638 (register values) \n", best_rate_h8s);
+       printf("brp=%d, best_tseg=%d, tseg1=%d, tseg2=%d, sampl_pt=%d\n",
+                                       best_brp/2-1, best_tseg, tseg1-1, tseg2-1,
+                                       (100*(best_tseg-tseg2-1)/(best_tseg+1)));
+       #endif /* PRINT_BAUD */
+       /* Get settings for H8S/2638. */
+       *pbrp=best_brp/2-1; //brp;
+       *ptseg1=tseg1-1;
+       *ptseg2=tseg2-1;
+
+       return 0;
+};
+
+/*zpravy_zasob ------------------------------------------------------------------------------------------------------------------------------------------------ */
+int can_test_function(int can_chanel)
+{
+  can_msg_buf zprava_pok;
+  zasobnik_zprav_t *zpravy_zas=NULL;
+  int i;
+
+  /* Choose right chanel. */
+  if(can_chanel==0)
+    zpravy_zas=&zpravy_zas_hcan0;
+  if(can_chanel==1)
+    zpravy_zas=&zpravy_zas_hcan1;
+  if(zpravy_zas==NULL) return -CANERR_BADCHANEL;
+  zprava_pok.id.std.id=0x005;
+    printf("cislo:0x%04X%04X, hwid:0x%04X%04X\n",(int)((0x005&0xffff0000)>>16),(int) (0x005&0xffff),
+                              (int)((CAN_ID_FLG2HWID(0x005,0,0)&0xffff0000)>>16),(int) (CAN_ID_FLG2HWID(0x005,0,0)&0xffff) );
+  zprava_pok.id.hwid=CAN_ID_FLG2HWID(0x005,0,0);
+
+    printf("\n");
+  __u32 cislo;
+  cislo=zprava_pok.id.hwid; //CAN_ID_STD2HWID(0x005);
+  for(i=0;i<4;i++) {
+   *(HCAN1_MC1+0+4+(3-i))=cislo;//zprava->id.hwid;
+   cislo=(cislo>>8);
+  };
+    printf("*** HCAN1\n");
+    printf("reg. MC15:0-3:0x%02x:%02x:%02x:%02x\n", *(HCAN1_MC1+0), *(HCAN1_MC1+1), *(HCAN1_MC1+2), *(HCAN1_MC1+3));
+    printf("reg. MC15:4-7:0x%x:%x:%x:%x\n",         *(HCAN1_MC1+4), *(HCAN1_MC1+5), *(HCAN1_MC1+6), *(HCAN1_MC1+7));
+    printf("reg. MD15:0-3:0x%02x:%02x:%02x:%02x\n", *(HCAN1_MD1+0), *(HCAN1_MD1+1), *(HCAN1_MD1+2), *(HCAN1_MD1+3));
+    printf("reg. MD15:4-7:0x%x:%x:%x:%x\n",         *(HCAN1_MD1+4), *(HCAN1_MD1+5), *(HCAN1_MD1+6), *(HCAN1_MD1+7));
+    printf("\n");
+
+  printf("zpravy_zasob - obs_cnt:0x%x\n", zpravy_zas->obs_cnt);
+  printf("preruseni, hcan0:0x%x, hcan1:0x%x\n", prerus_hcan0, prerus_hcan1);
+  printf("HCAN0_TEC:0x%x\n", *HCAN0_TEC);
+  for(i=0;i<8;i++)
+    zprava_pok.data[i]=i;
+  can_send_msg(0,15,zprava_pok);
+  printf("zpravy_zasob - obs_cnt:0x%x\n", zpravy_zas->obs_cnt);
+  printf("preruseni, hcan0:0x%x, hcan1:0x%x\n", prerus_hcan0, prerus_hcan1);
+  printf("HCAN0_TEC:0x%x\n", *HCAN0_TEC);
+  can_send_msg(0,15,zprava_pok);
+  printf("zpravy_zasob - obs_cnt:0x%x\n", zpravy_zas->obs_cnt);
+  printf("preruseni, hcan0:0x%x, hcan1:0x%x\n", prerus_hcan0, prerus_hcan1);
+  printf("HCAN0_TEC:0x%x\n", *HCAN0_TEC);
+  //printf("budu cpat ID:0x%04x, HWID:0x%04x\n", 0x005, CAN_IDE2HWID(0x005));
+  //*(HCAN1_MC0+3)=0;
+  return(1);
+};
+
+/* ------------------------------------------------------------------------------------------------------------------------------------------------ */
+int can_send_msg(int can_chanel, int can_mailbox, can_msg_buf zprava_k_odesl)
+{
+  int i,can_mailbox_c_offset,can_mailbox_d_offset;
+  __u32 cislo;
+
+
+  //printf("zprava_k_odesl:0x%x, &zprava_k_odesl:0x%x \n", zprava_k_odesl, &zprava_k_odesl);
+  /* Set addres of HCAN message and msg. buffer - not used */
+  can_mailbox_c_offset=can_mailbox*HCAN_MC_LENGTH;
+  can_mailbox_d_offset=can_mailbox*HCAN_MD_LENGTH;
+  /* send message */
+  /* setting Mailbox control */
+  /* write msg id */
+  if((zprava_k_odesl.id.hwid)==0) {/* if hwid=0 then use non zero id */
+    if((zprava_k_odesl.id.std.id)!=0)
+      zprava_k_odesl.id.hwid=CAN_ID_FLG2HWID(zprava_k_odesl.id.std.id,0,0);
+    else
+      zprava_k_odesl.id.hwid=CAN_ID_FLG2HWID(zprava_k_odesl.id.ext.id,1,0);
+  };
+  cislo=zprava_k_odesl.id.hwid;
+  #if DEBUG
+    printf("std.id:0x%x, data[0]:0x%x ", zprava_k_odesl.id.std.id, zprava_k_odesl.data[0]);
+    printf("cislo:0x%04X%04X, hwid:0x%04X%04X\n",(uint16_t)((cislo&0xffff0000)>>16),(uint16_t) (cislo&0xffff),
+                                (int)((zprava_k_odesl.id.hwid&0xffff0000)>>16),(int) (zprava_k_odesl.id.hwid&0xffff));
+  #endif
+  for(i=0;i<4;i++) {
+   *(HCAN0_MC0+can_chanel*HCAN_MC_o+can_mailbox_c_offset+4+(3-i))=cislo&0xff; //zprava_k_odesl.id.hwid;
+   cislo=(cislo>>8);
+  };
+   /* set data length */
+   *(HCAN0_MC0+can_chanel*HCAN_MC_o+can_mailbox_c_offset+0)=0x08; /* eight data bytes  */
+  /* setting msg. data */
+  for(i=0;i<8;i++)
+    *(HCAN0_MD0+can_chanel*HCAN_MD_o+can_mailbox_d_offset+i)=zprava_k_odesl.data[i];
+  /* send TXPR setting */
+  #if DEBUG_LOW
+    printf("reg. MC15:0-3:0x%02x:%02x:%02x:%02x\n", *(HCAN0_MC15+0), *(HCAN0_MC15+1), *(HCAN0_MC15+2), *(HCAN0_MC15+3));
+    printf("reg. MC15:4-7:0x%x:%x:%x:%x\n",         *(HCAN0_MC15+4), *(HCAN0_MC15+5), *(HCAN0_MC15+6), *(HCAN0_MC15+7));
+    printf("reg. MD15:0-3:0x%02x:%02x:%02x:%02x\n", *(HCAN0_MD15+0), *(HCAN0_MD15+1), *(HCAN0_MD15+2), *(HCAN0_MD15+3));
+    printf("reg. MD15:4-7:0x%x:%x:%x:%x\n",         *(HCAN0_MD15+4), *(HCAN0_MD15+5), *(HCAN0_MD15+6), *(HCAN0_MD15+7));
+  #endif
+  //*HCAN0_TXPR|=TXPR_TXPR15m;
+  *(HCAN0_TXPR+can_chanel*HCAN_TXPR_o)|=prevod_mask[can_mailbox];
+  return(0);
+};
+/* ------------------------------------------------------------------------------------------------------------------------------------------------ */
+int can_recive_msg(int can_chanel, int can_mailbox, int idx)
+{ /* !Caled in interrupt routine ! */
+  //int rel_addr,id_byte;
+  int i,can_mailbox_c_offset,can_mailbox_d_offset;
+  zasobnik_zprav_t *zpravy_zas=NULL;
+  can_msg_buf zprava;
+  uint32_t temp32;
+
+  /* Choose right chanel. */
+  if(can_chanel==0)
+    zpravy_zas=&zpravy_zas_hcan0;
+  if(can_chanel==1)
+    zpravy_zas=&zpravy_zas_hcan1;
+  if(zpravy_zas==NULL) return -CANERR_BADCHANEL;
+  /* Set addres of HCAN message and msg. buffer - not used */
+  can_mailbox_c_offset=can_mailbox*HCAN_MC_LENGTH;
+  can_mailbox_d_offset=can_mailbox*HCAN_MD_LENGTH;
+
+  /* read message */
+  if(zpravy_zas->obs_cnt<zpravy_zas->obs_max) {
+    //zprava=zpravy_zasob.zpravy[zpravy_zasob.obs_cnt];
+    #if 1
+    for(i=0,temp32=0;i<4;i++) {
+      temp32<<=8;
+      temp32|=(*(HCAN0_MC0+can_chanel*HCAN_MC_o+can_mailbox_c_offset+4+i));//zprava->id.hwid;
+    };
+    zprava.id.hwid=temp32;
+    #else
+    hw_0=*(HCAN0_MC0+can_chanel*HCAN_MC_o+can_mailbox_c_offset+4+0);
+    hw_1=*(HCAN0_MC0+can_chanel*HCAN_MC_o+can_mailbox_c_offset+4+1);
+    hw_2=*(HCAN0_MC0+can_chanel*HCAN_MC_o+can_mailbox_c_offset+4+2);
+    hw_3=*(HCAN0_MC0+can_chanel*HCAN_MC_o+can_mailbox_c_offset+4+3);
+    zprava.id.hwid=0x01000000*hw_0+0x10000*hw_1+0x100*hw_2+1*hw_3;
+    hard_id=0x01000000*hw_0+0x10000*hw_1+0x100*hw_2+1*hw_3;
+    #endif
+    //zprava_glob.id.hwid=temp32;
+    if(CAN_HWID_IDE&zprava.id.hwid) {
+      zprava.id.ext.id=CAN_HWID2IDE(zprava.id.hwid);
+      zprava.id.std.id=0;
+      klasika_id=0x20;
+    }
+    else {
+      zprava.id.std.id=CAN_HWID2ID_STD(zprava.id.hwid);
+      zprava.id.ext.id=0;
+      klasika_id=0x40;
+    };
+    for(i=0;i<8;i++) {
+      zprava.data[i]=*(HCAN0_MD0+can_chanel*HCAN_MD_o+can_mailbox_d_offset+i);
+    };
+    zpravy_zas->zpravy[zpravy_zas->obs_cnt]=zprava;
+    zpravy_zas->obs_cnt++;
+    return(0);
+
+  };
+  //rel_addr=idx*8;
+  //for (id_byte=0;;)
+  //*(HCAN0_MD0+rel_addr+0)
+  return(-1);
+};
+
+/* ------------------------------------------------------------------------------------------------------------------------------------------------ */
+int test_can_print_m(can_msg_buf *z_print)
+{
+  int i;
+
+  /* vypis zpravu */
+  printf("id:0x%04x, ide:0x%04x%04x",
+      z_print->id.std.id, (int) ((z_print->id.ext.id&0xffff0000)>>16), (int) (z_print->id.ext.id&0xffff));
+  printf(", hwid:0x%04x%04x\n", (int) ((z_print->id.hwid&0xffff0000)>>16), (int) (z_print->id.hwid&0xffff));
+  printf("data:");
+  for(i=0;i<8;i++)
+    printf(" 0x%x", z_print->data[i]);
+  printf("\n");
+  return(0);
+};
+/* ------------------------------------------------------------------------------------------------------------------------------------------------ */
+#if 0 /* debug, and test code for setting registers */
+int can_set_registers(int can_chanel, can_settings_t *can_settings_hcan)
+{  /* Seting HCAN registers */
+  unsigned int hcanChS,i,bank;
+
+  printf("can_set_registers HCAN%d\n", can_chanel);
+  hcanChS=can_chanel;
+  if(can_chanel<NUMBER_OF_CAN_CHANELS) {
+      //printf("\treg. BCR adr:0x%p, HCAN_SHIFT:0x%x, hcanChS:0x%x\n", (HCAN0_BCR+hcanChS/sizeof(*HCAN0_BCR)), HCAN_SHIFT, hcanChS);
+    /* bit configuration mode - setting BCR */
+     //printf("\treg. BCR:0x%04x - puv. stav\n", *(HCAN0_BCR+hcanChS*HCAN_BCR_o));
+     *(HCAN0_BCR+hcanChS*HCAN_BCR_o)=((*(HCAN0_BCR+hcanChS*HCAN_BCR_o)&~BCR_BRPm)
+                                     |CAN_BRP2BRPM(can_settings_hcan->bcr_brp));//0x00
+     //printf("\treg. BCR:0x%04x - BRP\n", *(HCAN0_BCR+hcanChS*HCAN_BCR_o));
+     *(HCAN0_BCR+hcanChS*HCAN_BCR_o)=((*(HCAN0_BCR+hcanChS*HCAN_BCR_o)&~BCR_SJWm)
+                                     |CAN_SJW2SJWM(can_settings_hcan->bcr_sjw));//0x02
+     //printf("\treg. BCR:0x%04x - SJW\n", *(HCAN0_BCR+hcanChS*HCAN_BCR_o));
+     //*HCAN0_BCR=(*HCAN0_BCR|BCR_BCR15m); /* BSP */
+     *(HCAN0_BCR+hcanChS*HCAN_BCR_o)=((*(HCAN0_BCR+hcanChS*HCAN_BCR_o)&~BCR_TSEG1m)
+                                     |CAN_TSEG12TSEG1M(can_settings_hcan->bcr_tseg1));//0x04
+     //printf("\treg. BCR:0x%04x - TSEG1\n", *(HCAN0_BCR+hcanChS*HCAN_BCR_o));
+     *(HCAN0_BCR+hcanChS*HCAN_BCR_o)=((*(HCAN0_BCR+hcanChS*HCAN_BCR_o)&~BCR_TSEG2m)
+                                     |CAN_TSEG22TSEG2M(can_settings_hcan->bcr_tseg2));//0x03
+     //printf("\treg. BCR:0x%04x - TSEG2\n", *(HCAN0_BCR+hcanChS*HCAN_BCR_o));
+    /* bit configuration mode - setting MBCR */
+     *(HCAN0_MBCR+hcanChS*HCAN_MBCR_o) &= ~(MBCR_MBCR14m|MBCR_MBCR15m); /* mailbox set for transmission */
+     *(HCAN0_MBCR+hcanChS*HCAN_MBCR_o) |= (MBCR_MBCR1m|MBCR_MBCR2m); /* mailbox set for reception */
+     //printf("\treg. *HCAN0_BCR:0x%x, *HCAN1_BCR:0x%x\n", *HCAN0_BCR, *HCAN1_BCR);
+    /* mailbox RAM initialization - crear all registers MC and MD */
+     for(bank=0;bank<16;bank++) {
+       for(i=0;i<8;i++) {
+         *(HCAN0_MC0+hcanChS*HCAN_MC_o+bank*HCAN_MC_LENGTH+i)=0x00;
+         *(HCAN0_MD0+hcanChS*HCAN_MD_o+bank*HCAN_MD_LENGTH+i)=0x00;
+       };
+     };
+    /* set Message transmission Method */
+     //*HCAN0_MCR &= ~MCR_MCR2m /* by message identifier priority - 0 (initial value) */
+     /* Exit bit configuration mode */
+     //printf("\treg. GSR:0x%04x\n", *(HCAN0_GSR+hcanChS*HCAN_GSR_o));
+
+
+    *(HCAN0_MCR+hcanChS*HCAN_MCR_o)&=~MCR_MCR0m; /* Transition into normal operation mode */
+    while(*(HCAN0_GSR+hcanChS*HCAN_GSR_o)&GSR_GSR3m);
+    //printf("\treg. GSR:0x%04x - bit. conf. exit\n", *(HCAN0_GSR+hcanChS*HCAN_GSR_o));
+    /* setting communication */
+    *(HCAN0_IMR+hcanChS*HCAN_IMR_o)&=~(IMR_IMR1m|IMR_IMR8m); /* (initial=0xffff) */
+    *(HCAN0_MBIMR+hcanChS*HCAN_MBIMR_o)&=~(MBIMR_MBIMR0m|MBIMR_MBIMR1m|MBIMR_MBIMR14m|MBIMR_MBIMR15m); 
+               /* 1 - disable individual interrupt requests (initial 0xffff) */
+    /* MC[x], MD[x] settings */
+
+
+    /* Local acceptance filter masks */
+    *(HCAN0_LAFML+hcanChS*HCAN_LAFML_o)=can_settings_hcan->lafml;
+    *(HCAN0_LAFMH+hcanChS*HCAN_LAFMH_o)=can_settings_hcan->lafmh;
+    //printf("\treg. LAFM:0x%04x%04x - po nastaveni\n", *(HCAN0_LAFMH+hcanChS*HCAN_LAFMH_o),*(HCAN0_LAFML+hcanChS*HCAN_LAFML_o));
+  }
+  printf("can_set_registers finished\n");
+  return(1);
+};
+
+       clock /= c->fix_div;
+
+       /* tseg even = round down, odd = round up */
+       for (tseg=(c->sync+c->tseg1_min+c->tseg2_min)*2; tseg<=(c->sync+c->tseg1_max+c->tseg2_max)*2+1; tseg++) {
+               brp = clock/((1+tseg/2)*baud_rate)+tseg%2;
+               if ((brp < c->brp_min) || (brp > c->brp_max))
+                       continue;
+               error = baud_rate - clock/(brp*(1+tseg/2));
+               if (error < 0)
+                       error = -error;
+               if (error <= best_error) {
+                       best_error = error;
+                       best_tseg = tseg/2;
+                       best_brp = brp-1;
+                       best_rate = clock/(brp*(1+tseg/2));
+               }
+       }
+       if (best_error && (baud_rate/best_error < 10)) {
+               printf("baud rate %ld is not possible with %ld Hz clock\n",
+                                                               baud_rate, 2*clock);
+               printf("%d bps. brp=%d, best_tseg=%d, tseg1=%d, tseg2=%d\n",
+                               best_rate, best_brp, best_tseg, tseg1, tseg2);
+               return -1;
+       }
+       tseg2 = best_tseg-(sampl_pt*(best_tseg+1))/100;
+       if (tseg2 < 0)
+               tseg2 = 0;
+       if (tseg2 > c->tseg2_max)
+               tseg2 = c->tseg2_max;
+       tseg1 = best_tseg-tseg2-2;
+       if (tseg1>c->tseg1_max) {
+               tseg1 = c->tseg1_max;
+               tseg2 = best_tseg-tseg1-2;
+       }
+
+
+#endif
+
+
+
+
diff --git a/app/cantest/can_drive/can_fn.h b/app/cantest/can_drive/can_fn.h
new file mode 100644 (file)
index 0000000..7a32ba2
--- /dev/null
@@ -0,0 +1,193 @@
+/* can_fn.h used for aplications with HCAN H8S2638 */
+#ifndef _can_fn_H
+#define _can_fn_H
+
+#include <types.h>
+
+/* Errors codes */
+#define CANERR_BADCHANEL 100;
+
+/* macros for CAN messages */
+#define CAN_HWID2IDE(hwid) ({ __u32 id=hwid; \
+                            (((id&0x00ff0000)<<5)|((id&0xe0000000)>>(5+6))|((id&0x03000000)>>8)|((id&0x000000ff)<<8)|((id&0x0000ff00)>>8)); })
+#define CAN_IDE2HWID(idin) ({ __u32 id=idin; \
+                            (((id&0x1fe00000)>>5)|((id&0x001c0000)<<(5+6))|((id&0x00030000)<<8)|((id&0x0000ff00)>>8)|((id&0x000000ff)<<8)); })
+#define CAN_HWID2ID_STD(hwid) ( { __u32 id=hwid; \
+                               (((id&0xe0000000)>>(5+8+16))|((id&0x00ff0000)>>(8+5))); } )
+#define CAN_ID_STD2HWID(idin) ( { __u32 id=idin; \
+                               (((id&0x00000007)<<(5+8+16))|((id&0x000007f8)<<(8+5))); })
+#define CAN_ID_FLG2HWID(idin,ext,rtr) ( \
+           ext?(CAN_IDE2HWID(idin)|CAN_HWID_IDE|(rtr?CAN_HWID_RTR:0)): \
+                ((CAN_ID_STD2HWID(idin)|(rtr?CAN_HWID_RTR:0))) \
+         )
+#define CAN_IDM2LAFM(idin)             ({ __u32 id=idin; \
+                                       (((id&0x00000007)<<(16+8+5))|((id&0x000007f8)<<(8+5))); })
+#define CAN_IDEM2LAFM(lafm)            ({ __u32 id=lafm; \
+                                       (((id&0x000000ff)<<(0+8))|((id&0x0000ff00)>>(0+8))|(id&0x00030000) \
+                                       |((id&0x00000007)<<(16+8+5))|((id&0x000007f8)<<(8+5))); })
+
+/* To main header h8s2638h.h */
+#define   LAFM_IDm     0xe0ff0000      /* Mask for standard identifier */
+#define   LAFM_IDEm    0xe3ffffff      /* Mask for extended idenifier */
+
+/* ((CAN_ID_STD2HWID(idin)|(rtr?CAN_HWID_RTR:0))<<16)  */
+#define CAN_STDID_RTR
+#define CAN_HWID_IDE 0x08000000        /* 1 for extended ID format */
+
+#define CAN_HWID_RTR 0x10000000        /* RTR for distinguish between data or remote frames 0 - Data */
+
+#define CAN_BRP2BRPM(brp) ({ __u16 id=brp; \
+                             ((id&0x003f)<<8); })
+#define CAN_TSEG12TSEG1M(tseg1)  ({ __u16 id=tseg1; \
+                                   ((id&0x000f)); })
+#define CAN_TSEG22TSEG2M(tseg2) ({ __u16 id=tseg2; \
+                             ((id&0x0007)<<4); })
+#define CAN_SJW2SJWM(sjw) ({ __u16 id=sjw; \
+                             ((id&0x0003)<<(8+6)); })
+
+/* Define offsets for HCAN chanels */
+#define HCAN_MCR_o (HCAN1_MCR-HCAN0_MCR)
+#define HCAN_GSR_o (HCAN1_GSR-HCAN0_GSR)
+#define HCAN_BCR_o (HCAN1_BCR-HCAN0_BCR)
+#define HCAN_MBCR_o (HCAN1_MBCR-HCAN0_MBCR)
+#define HCAN_TXPR_o (HCAN1_TXPR-HCAN0_TXPR)
+#define HCAN_TXCR_o (HCAN1_TXCR-HCAN0_TXCR)
+#define HCAN_TXACK_o (HCAN1_TXACK-HCAN0_TXACK)
+#define HCAN_ABACK_o (HCAN1_ABACK-HCAN0_ABACK)
+#define HCAN_RXPR_o (HCAN1_RXPR-HCAN0_RXPR)
+#define HCAN_RFPR_o (HCAN1_RFPR-HCAN0_RFPR)
+#define HCAN_IRR_o (HCAN1_IRR-HCAN0_IRR)
+#define HCAN_MBIMR_o (HCAN1_MBIMR-HCAN0_MBIMR)
+#define HCAN_IMR_o (HCAN1_IMR-HCAN0_IMR)
+#define HCAN_REC_o (HCAN1_REC-HCAN0_REC)
+#define HCAN_TEC_o (HCAN1_TEC-HCAN0_TEC)
+#define HCAN_UMSR_o (HCAN1_UMSR-HCAN0_UMSR)
+#define HCAN_LAFML_o (HCAN1_LAFML-HCAN0_LAFML)
+#define HCAN_LAFMH_o (HCAN1_LAFMH-HCAN0_LAFMH)
+#define HCAN_MC_o (HCAN1_MC0-HCAN0_MC0)
+#define HCAN_MD_o (HCAN1_MD0-HCAN0_MD0)
+
+/* H8S 2638 architekture dependencies */
+#define HCAN_MC_LENGTH 8 /* HCAN_MC0+8=HCAN_MC1  */
+#define HCAN_MD_LENGTH 8 /* HCAN_MD0+8=HCAN_MD1  */
+
+#if 0
+/* Number of data bytes in one CAN message */
+#define CAN_MSG_LENGTH 8
+
+typedef int timeval;
+typedef struct timeval canmsg_tstamp_t ;
+
+typedef unsigned long canmsg_id_t;
+
+
+/**
+ * struct canmsg_t - structure representing CAN message
+ * @flags:  message flags
+ *      %MSG_RTR .. message is Remote Transmission Request,
+ *     %MSG_EXT .. message with extended ID, 
+ *      %MSG_OVR .. indication of queue overflow condition,
+ *     %MSG_LOCAL .. message originates from this node.
+ * @cob:    communication object number (not used)
+ * @id:     ID of CAN message
+ * @timestamp: not used
+ * @length: length of used data
+ * @data:   data bytes buffer
+ *
+ * Header: canmsg.h
+ */
+struct canmsg_t {
+       int             flags;
+       int             cob;
+       canmsg_id_t     id;
+       canmsg_t stamp_t timestamp;
+       unsigned short  length;
+       unsigned char   data[CAN_MSG_LENGTH];
+};
+#endif
+
+typedef struct /* structure to access a can msg buffer */
+{
+  __u16 control;
+  //union {
+  struct {
+    struct {
+      __u16 id;
+      __u16 time;
+    } std;
+    struct {
+      __u32 id;
+    } ext;
+    __u32 hwid;
+ // } id;
+  } id;
+  __u8  data[8];
+  __u16 reserved;
+} can_msg_buf;
+
+typedef struct
+{
+  __u8 mcr;
+  __u8 bcr_sjw;
+  __u8 bcr_brp;
+  __u8 bcr_bsp;
+  __u8 bcr_tseg1;
+  __u8 bcr_tseg2;
+  __u16 mbcr;  /* mailbox control register */
+  __u16 mbimr; /* mailbox interrupt mask register */
+  __u16 imr;   /* interrup mask register */
+  __u16 lafml;
+  __u16 lafmh;
+} can_settings_t;
+
+typedef struct {
+  int sync;
+  int tseg1_min;
+  int tseg1_max;
+  int tseg2_min;
+  int tseg2_max;
+  int brp_min;
+  int brp_max;
+  int brp_inc;
+  int fix_div;
+} can_calc_const_t;
+
+#define ZASOBNIK_ZPRAV 10
+typedef struct {
+         can_msg_buf zpravy[ZASOBNIK_ZPRAV];
+         int obs_cnt;
+         int obs_max;
+         } zasobnik_zprav_t;
+
+/* Final functions */
+
+/* Debug variables */
+int prerus_hcan0, prerus_hcan1;
+can_msg_buf zprava_glob;
+uint32_t hard_id,klasika_id, rozsir_id;
+uint8_t hw_0,hw_1,hw_2,hw_3;
+unsigned int adresa, maleHCAN0_MC0,hcanChS,c_offset;
+
+/* ---- interrupt vectors prototypes */
+void gdb_unhandled_isr(void);
+void test_unhandled_isr(void) __attribute__ ((interrupt_handler));
+void hcan0_isr(void) __attribute__ ((interrupt_handler));
+void hcan1_isr(void) __attribute__ ((interrupt_handler));
+
+/* Working on functions */ 
+int ClearMessages(zasobnik_zprav_t *pstack,int count_mes);
+int can_auto_baud(long baud_rate, int *pbrp, int *ptseg1, int *ptseg2, int sampl_pt, can_calc_const_t *c);
+int can_sleep(int can_chanel,int wake_up_mode);
+int can_wake(int can_chanel);
+int test_can_print_m(can_msg_buf *z_print);
+int Can_Enable(int chanel);
+int can_set_registers(int can_chanel, can_settings_t *can_settings_hcan);
+int can_change_registers(int can_chanel,can_settings_t *new_set, can_settings_t *can_settings_hcan);
+int can_test_function(int can_chanel);
+int can_send_msg(int can_chanel, int can_mailbox, can_msg_buf zprava);
+int can_recive_msg(int can_chanel, int can_mailbox, int idx);
+/* Debug functions */
+void ReadRegistersCan(int chanel, int param);
+void SetupRegistersCan(int can_chanel);
+
+#endif /* _can_fn_H */
diff --git a/app/cantest/can_drive/can_odpad.c b/app/cantest/can_drive/can_odpad.c
new file mode 100644 (file)
index 0000000..48807a1
--- /dev/null
@@ -0,0 +1,47 @@
+#if 0 /* old code for use sci */
+       __sti();
+       /*__cli();*/
+
+       /* P3.3 TxD1, P3.4 RxD0 */      
+       #if 1
+       SHADOW_REG_SET(DIO_P3DDR,0x5);  
+       *DIO_P3DR = 0x5f;
+       #else
+       SHADOW_REG_SET(DIO_P3DDR,0x85);
+       #if HW_VER_CODE<VER_CODE(0,2,0)
+       SHADOW_REG_SET(DIO_PFDDR,0x06);
+       #endif /* >=VER_CODE(0,2,0) */
+       #endif
+
+       
+       if(sci_rs232_setmode(0,9600,SCI_RS232_MODEA,1)>=0) {
+        rs232_init_ok=1;
+        *DIO_P3DR &= ~0x01;
+       } else {
+        *DIO_P3DR |= 0xc4;
+         return 0;
+       }
+       #if DEB_LED_ENABLED
+       deb_led_out(0);
+       /* FlWait(2*1000000); */
+       #endif
+       //sci_rs232_sendstr("I am alive, you can ask for \"help\"\r\n");
+       printf("I am alive, you can ask for \"help\"\n ported version for EDK2638\n");
+
+      *DIO_P3DR ^= 0x40;
+      //cmd_rs232_test();
+#endif
+
+#if 0
+   sti(); /* enable iterrupts */
+
+   //init();   // init LEDs
+   //deb_led_out(0);
+   FlWait(5*100000);
+   deb_led_out(1);
+   sci_rs232_setmode(19200, 0, 0, sci_rs232_chan_default); //sci_rs232_chan_default misto 1
+   FlWait(5*100000);
+   deb_led_out(2);
+   //printf("I am alive, you can ask for \"help\"\n ported version for EDK2638\n");
+   deb_led_out(3);
+#endif
\ No newline at end of file
diff --git a/app/cantest/can_drive/can_queue.c b/app/cantest/can_drive/can_queue.c
new file mode 100644 (file)
index 0000000..2d81a90
--- /dev/null
@@ -0,0 +1,750 @@
+/* can_queue.c - CAN message queues
+ * Linux CAN-bus device driver.
+ * New CAN queues by Pavel Pisa - OCERA team member
+ * email:pisa@cmp.felk.cvut.cz
+ * This software is released under the GPL-License.
+ * Version lincan-0.3  17 Jun 2004
+ */
+
+#include "../include/can.h"
+#include "../include/can_sysdep.h"
+#include "../include/can_queue.h"
+
+/* 
+ * Modifies Tx message processing 
+ *  0 .. local message processing disabled
+ *  1 .. local messages disabled by default but can be enabled by canque_set_filt
+ *  2 .. local messages enabled by default, can be disabled by canque_set_filt
+ */
+extern int processlocal;
+
+atomic_t edge_num_cnt;
+
+//#define CAN_DEBUG
+#undef CAN_DEBUG
+
+#ifdef CAN_DEBUG
+       #define DEBUGQUE(fmt,args...) can_printk(KERN_ERR "can_queue (debug): " fmt,\
+       ##args)
+
+#else
+       #define DEBUGQUE(fmt,args...)
+#endif
+
+#define CANQUE_ROUNDROB 1
+
+
+/**
+ * canque_fifo_flush_slots - free all ready slots from the FIFO
+ * @fifo: pointer to the FIFO structure
+ *
+ * The caller should be prepared to handle situations, when some
+ * slots are held by input or output side slots processing.
+ * These slots cannot be flushed or their processing interrupted.
+ *
+ * Return Value: The nonzero value indicates, that queue has not been
+ *     empty before the function call.
+ */
+int canque_fifo_flush_slots(struct canque_fifo_t *fifo)
+{
+       int ret;
+       can_spin_irqflags_t flags;
+       struct canque_slot_t *slot;
+       can_spin_lock_irqsave(&fifo->fifo_lock, flags);
+       slot=fifo->head;
+       if(slot){
+               *fifo->tail=fifo->flist;
+               fifo->flist=slot;
+               fifo->head=NULL;
+               fifo->tail=&fifo->head;
+       }
+       canque_fifo_clear_fl(fifo,FULL);
+       ret=canque_fifo_test_and_set_fl(fifo,EMPTY)?0:1;
+       can_spin_unlock_irqrestore(&fifo->fifo_lock, flags);
+       return ret;
+}
+
+
+/**
+ * canque_fifo_init_slots - initializes slot chain of one CAN FIFO
+ * @fifo: pointer to the FIFO structure
+ *
+ * Return Value: The negative value indicates, that there is no memory
+ *     to allocate space for the requested number of the slots.
+ */
+int canque_fifo_init_slots(struct canque_fifo_t *fifo)
+{
+       struct canque_slot_t *slot;
+       int slotsnr=fifo->slotsnr;
+       if(!fifo->entry || !slotsnr) return -1;
+       slot=fifo->entry;
+       fifo->flist=slot;
+       while(--slotsnr){
+               slot->next=slot+1;
+               slot++;
+       }
+       slot->next=NULL;
+       fifo->head=NULL;
+       fifo->tail=&fifo->head;
+       canque_fifo_set_fl(fifo,EMPTY);
+       return 1;
+}
+
+/* atomic_dec_and_test(&qedge->edge_used);
+ void atomic_inc(&qedge->edge_used);
+ list_add_tail(struct list_head *new, struct list_head *head)
+ list_for_each(edge,qends->inlist);
+ list_entry(ptr, type, member)
+*/
+
+void __canque_edge_decref(struct canque_edge_t *edge)
+{
+       __canque_edge_decref_body(edge);
+}
+
+/**
+ * canque_get_inslot - finds one outgoing edge and allocates slot from it
+ * @qends: ends structure belonging to calling communication object
+ * @qedgep: place to store pointer to found edge
+ * @slotp: place to store pointer to  allocated slot
+ * @cmd: command type for slot
+ *
+ * Function looks for the first non-blocked outgoing edge in @qends structure
+ * and tries to allocate slot from it.
+ * Return Value: If there is no usable edge or there is no free slot in edge
+ *     negative value is returned.
+ */
+int canque_get_inslot(struct canque_ends_t *qends,
+       struct canque_edge_t **qedgep, struct canque_slot_t **slotp, int cmd)
+{
+       int ret=-2;
+       struct canque_edge_t *edge;
+       
+       edge=canque_first_inedge(qends);
+       if(edge){
+               if(!canque_fifo_test_fl(&edge->fifo,BLOCK)){
+                       ret=canque_fifo_get_inslot(&edge->fifo, slotp, cmd);
+                       if(ret>0){
+                               *qedgep=edge;
+                               DEBUGQUE("canque_get_inslot cmd=%d found edge %d\n",cmd,edge->edge_num);
+                               return ret;
+
+                       }
+               }
+               canque_edge_decref(edge);
+       }
+       *qedgep=NULL;
+       DEBUGQUE("canque_get_inslot cmd=%d failed\n",cmd);
+       return ret;
+}
+
+/**
+ * canque_get_inslot4id - finds best outgoing edge and slot for given ID
+ * @qends: ends structure belonging to calling communication object
+ * @qedgep: place to store pointer to found edge
+ * @slotp: place to store pointer to  allocated slot
+ * @cmd: command type for slot
+ * @id: communication ID of message to send into edge
+ * @prio: optional priority of message
+ *
+ * Function looks for the non-blocked outgoing edge accepting messages
+ * with given ID. If edge is found, slot is allocated from that edge.
+ * The edges with non-zero mask are preferred over edges open to all messages.
+ * If more edges with mask accepts given message ID, the edge with
+ * highest priority below or equal to required priority is selected.
+ * Return Value: If there is no usable edge or there is no free slot in edge
+ *     negative value is returned.
+ */
+int canque_get_inslot4id(struct canque_ends_t *qends,
+       struct canque_edge_t **qedgep, struct canque_slot_t **slotp,
+       int cmd, unsigned long id, int prio)
+{
+       int ret=-2;
+       struct canque_edge_t *edge, *bestedge=NULL;
+       
+       canque_for_each_inedge(qends, edge){
+               if(canque_fifo_test_fl(&edge->fifo,BLOCK))
+                       continue;
+               if((id^edge->filtid)&edge->filtmask)
+                       continue;
+               if(bestedge){
+                       if(bestedge->filtmask){
+                               if (!edge->filtmask) continue;
+                       } else {
+                               if(edge->filtmask){
+                                       canque_edge_decref(bestedge);
+                                       bestedge=edge;
+                                       canque_edge_incref(bestedge);
+                                       continue;
+                               }
+                       }
+                       if(bestedge->edge_prio<edge->edge_prio){
+                               if(edge->edge_prio>prio) continue;
+                       } else {
+                               if(bestedge->edge_prio<=prio) continue;
+                       }
+                       canque_edge_decref(bestedge);
+               }
+               bestedge=edge;
+               canque_edge_incref(bestedge);
+       }
+       if((edge=bestedge)!=NULL){
+               ret=canque_fifo_get_inslot(&edge->fifo, slotp, cmd);
+               if(ret>0){
+                       *qedgep=edge;
+                       DEBUGQUE("canque_get_inslot4id cmd=%d id=%ld prio=%d found edge %d\n",cmd,id,prio,edge->edge_num);
+                       return ret;
+               }
+               canque_edge_decref(bestedge);
+       }
+       *qedgep=NULL;
+       DEBUGQUE("canque_get_inslot4id cmd=%d id=%ld prio=%d failed\n",cmd,id,prio);
+       return ret;
+}
+
+
+/**
+ * canque_put_inslot - schedules filled slot for processing
+ * @qends: ends structure belonging to calling communication object
+ * @qedge: edge slot belong to
+ * @slot: pointer to the prepared slot
+ *
+ * Puts slot previously acquired by canque_get_inslot() or canque_get_inslot4id()
+ * function call into FIFO queue and activates edge processing if needed.
+ * Return Value: Positive value informs, that activation of output end
+ *     has been necessary
+ */
+int canque_put_inslot(struct canque_ends_t *qends,
+       struct canque_edge_t *qedge, struct canque_slot_t *slot)
+{
+       int ret;
+       ret=canque_fifo_put_inslot(&qedge->fifo,slot);
+       if(ret) {
+               canque_activate_edge(qends,qedge);
+               canque_notify_outends(qedge,CANQUEUE_NOTIFY_PROC);
+       }
+       canque_edge_decref(qedge);
+       DEBUGQUE("canque_put_inslot for edge %d returned %d\n",qedge->edge_num,ret);
+       return ret;
+}
+
+/**
+ * canque_abort_inslot - aborts preparation of the message in the slot
+ * @qends: ends structure belonging to calling communication object
+ * @qedge: edge slot belong to
+ * @slot: pointer to the previously allocated slot
+ *
+ * Frees slot previously acquired by canque_get_inslot() or canque_get_inslot4id()
+ * function call. Used when message copying into slot fails.
+ * Return Value: Positive value informs, that queue full state has been negated.
+ */
+int canque_abort_inslot(struct canque_ends_t *qends,
+       struct canque_edge_t *qedge, struct canque_slot_t *slot)
+{
+       int ret;
+       ret=canque_fifo_abort_inslot(&qedge->fifo,slot);
+       if(ret) {
+               canque_notify_outends(qedge,CANQUEUE_NOTIFY_SPACE);
+       }
+       canque_edge_decref(qedge);
+       DEBUGQUE("canque_abort_inslot for edge %d returned %d\n",qedge->edge_num,ret);
+       return ret;
+}
+#if 0
+/**
+ * canque_filter_msg2edges - sends message into all edges which accept its ID
+ * @qends: ends structure belonging to calling communication object
+ * @msg: pointer to CAN message
+ *
+ * Sends message to all outgoing edges connected to the given ends, which accepts
+ * message communication ID.
+ * Return Value: Returns number of edges message has been send to
+ */
+int canque_filter_msg2edges(struct canque_ends_t *qends, struct canmsg_t *msg)
+{
+       int destnr=0;
+       int ret;
+       unsigned long msgid;
+       struct canque_edge_t *edge;
+       struct canque_slot_t *slot;
+       
+       DEBUGQUE("canque_filter_msg2edges for msg ID 0x%08lx and flags 0x%02x\n",
+                       msg->id, msg->flags);
+       msgid = canque_filtid2internal(msg->id, msg->flags);
+
+       canque_for_each_inedge(qends, edge) {
+               if(canque_fifo_test_fl(&edge->fifo,BLOCK))
+                       continue;
+               if((msgid^edge->filtid)&edge->filtmask)
+                       continue;
+               ret=canque_fifo_get_inslot(&edge->fifo, &slot, 0);
+               if(ret>0){
+                       slot->msg=*msg;
+                       destnr++;
+                       ret=canque_fifo_put_inslot(&edge->fifo,slot);
+                       if(ret) {
+                               canque_activate_edge(qends,edge);
+                               canque_notify_outends(edge,CANQUEUE_NOTIFY_PROC);
+                       }
+
+               }
+       }
+       DEBUGQUE("canque_filter_msg2edges sent msg ID %ld to %d edges\n",msg->id,destnr);
+       return destnr;
+}
+#endif
+/**
+ * canque_test_outslot - test and retrieve ready slot for given ends
+ * @qends: ends structure belonging to calling communication object
+ * @qedgep: place to store pointer to found edge
+ * @slotp: place to store pointer to received slot
+ *
+ * Function takes highest priority active incoming edge and retrieves
+ * oldest ready slot from it.
+ * Return Value: Negative value informs, that there is no ready output
+ *     slot for given ends. Positive value is equal to the command
+ *     slot has been allocated by the input side.
+ */
+int canque_test_outslot(struct canque_ends_t *qends,
+       struct canque_edge_t **qedgep, struct canque_slot_t **slotp)
+{
+       can_spin_irqflags_t flags;
+       int prio;
+       struct canque_edge_t *edge;
+       int ret;
+       
+       can_spin_lock_irqsave(&qends->ends_lock, flags);
+       for(prio=CANQUEUE_PRIO_NR;--prio>=0;){
+               while(!list_empty(&qends->active[prio])){
+                       edge=list_entry(qends->active[prio].next,struct canque_edge_t,activepeers);
+                       if(!canque_fifo_test_fl(&edge->fifo,DEAD)) {
+                               /* The first test on unlocked FIFO */
+                               if(canque_fifo_test_fl(&edge->fifo,EMPTY)) {
+                                       can_spin_lock(&edge->fifo.fifo_lock);
+                                       /* Test has to be repeated to ensure that EMPTY
+                                          state has not been nagated when locking FIFO */
+                                       if(canque_fifo_test_fl(&edge->fifo,EMPTY)) {
+                                               canque_fifo_set_fl(&edge->fifo,INACTIVE);
+                                               list_del(&edge->activepeers);
+                                               list_add(&edge->activepeers,&qends->idle);
+                                               can_spin_unlock(&edge->fifo.fifo_lock);
+                                               continue;
+                                       }
+                                       can_spin_unlock(&edge->fifo.fifo_lock);
+                               }
+                               canque_edge_incref(edge);
+                               can_spin_unlock_irqrestore(&qends->ends_lock, flags);
+                               *qedgep=edge;
+                               DEBUGQUE("canque_test_outslot found edge %d\n",edge->edge_num);
+                               ret=canque_fifo_test_outslot(&edge->fifo, slotp);
+                               if(ret>=0)
+                                       return ret;
+
+                               canque_edge_decref(edge);
+                               can_spin_lock_irqsave(&qends->ends_lock, flags);
+                       } else {
+                               can_spin_lock(&edge->fifo.fifo_lock);
+                               canque_fifo_set_fl(&edge->fifo,INACTIVE);
+                               list_del(&edge->activepeers);
+                               list_add(&edge->activepeers,&qends->idle);
+                               can_spin_unlock(&edge->fifo.fifo_lock);
+                       }
+               }
+       }
+       can_spin_unlock_irqrestore(&qends->ends_lock, flags);
+       *qedgep=NULL;
+       DEBUGQUE("canque_test_outslot no ready slot\n");
+       return -1;
+}
+
+/**
+ * canque_free_outslot - frees processed output slot
+ * @qends: ends structure belonging to calling communication object
+ * @qedge: edge slot belong to
+ * @slot: pointer to the processed slot
+ *
+ * Function releases processed slot previously acquired by canque_test_outslot()
+ * function call.
+ * Return Value: Return value informs if input side has been notified
+ *     to know about change of edge state
+ */
+int canque_free_outslot(struct canque_ends_t *qends,
+       struct canque_edge_t *qedge, struct canque_slot_t *slot)
+{
+       int ret;
+       can_spin_irqflags_t flags;
+       ret=canque_fifo_free_outslot(&qedge->fifo, slot);
+       if(ret&CAN_FIFOF_EMPTY){
+               canque_notify_inends(qedge,CANQUEUE_NOTIFY_EMPTY);
+       }
+       if(ret&CAN_FIFOF_FULL)
+               canque_notify_inends(qedge,CANQUEUE_NOTIFY_SPACE);
+       can_spin_lock_irqsave(&qends->ends_lock, flags);
+       if((ret&CAN_FIFOF_EMPTY) || CANQUE_ROUNDROB ){
+               can_spin_lock(&qedge->fifo.fifo_lock);
+               if(canque_fifo_test_fl(&qedge->fifo,EMPTY)){
+                       canque_fifo_set_fl(&qedge->fifo,INACTIVE);
+                       list_del(&qedge->activepeers);
+                       list_add(&qedge->activepeers,&qends->idle);
+               } else{
+                       list_del(&qedge->activepeers);
+                       list_add_tail(&qedge->activepeers,&qends->active[qedge->edge_prio]);
+               }
+               can_spin_unlock(&qedge->fifo.fifo_lock);
+       }
+       can_spin_unlock_irqrestore(&qends->ends_lock, flags);
+       canque_edge_decref(qedge);
+       DEBUGQUE("canque_free_outslot for edge %d returned %d\n",qedge->edge_num,ret);
+       return ret;
+}
+
+/**
+ * canque_again_outslot - reschedule output slot to process it again later
+ * @qends: ends structure belonging to calling communication object
+ * @qedge: edge slot belong to
+ * @slot: pointer to the slot for re-processing
+ *
+ * Function reschedules slot previously acquired by canque_test_outslot()
+ * function call for second time processing.
+ * Return Value: Function cannot fail.
+ */
+int canque_again_outslot(struct canque_ends_t *qends,
+       struct canque_edge_t *qedge, struct canque_slot_t *slot)
+{
+       int ret;
+       ret=canque_fifo_again_outslot(&qedge->fifo, slot);
+       canque_edge_decref(qedge);
+       DEBUGQUE("canque_again_outslot for edge %d returned %d\n",qedge->edge_num,ret);
+       return ret;
+}
+
+/**
+ * canque_set_filt - sets filter for specified edge
+ * @qedge: pointer to the edge
+ * @filtid: ID to set for the edge
+ * @filtmask: mask used for ID match check
+ * @filtflags: required filer flags
+ *
+ * Return Value: Negative value is returned if edge is in the process of delete.
+ */
+int canque_set_filt(struct canque_edge_t *qedge,
+       unsigned long filtid, unsigned long filtmask, int filtflags)
+{
+       int ret;
+       can_spin_irqflags_t flags;
+
+       can_spin_lock_irqsave(&qedge->fifo.fifo_lock,flags);
+       
+       if(!(filtflags&MSG_PROCESSLOCAL) && (processlocal<2))
+               filtflags |= MSG_LOCAL_MASK;
+       
+       qedge->filtid=canque_filtid2internal(filtid, filtflags);
+       qedge->filtmask=canque_filtid2internal(filtmask, filtflags>>MSG_FILT_MASK_SHIFT);
+       
+       if(canque_fifo_test_fl(&qedge->fifo,DEAD)) ret=-1;
+       else ret=canque_fifo_test_and_set_fl(&qedge->fifo,BLOCK)?1:0;
+
+       can_spin_unlock_irqrestore(&qedge->fifo.fifo_lock,flags);
+       if(ret>=0){
+               canque_notify_bothends(qedge,CANQUEUE_NOTIFY_FILTCH);
+       }
+       can_spin_lock_irqsave(&qedge->fifo.fifo_lock,flags);
+       if(!ret) canque_fifo_clear_fl(&qedge->fifo,BLOCK);
+       can_spin_unlock_irqrestore(&qedge->fifo.fifo_lock,flags);
+       
+       DEBUGQUE("canque_set_filt for edge %d, ID %ld, mask %ld, flags %d returned %d\n",
+                 qedge->edge_num,filtid,filtmask,filtflags,ret);
+       return ret;
+}
+
+/**
+ * canque_flush - fluesh all ready slots in the edge
+ * @qedge: pointer to the edge
+ *
+ * Tries to flush all allocated slots from the edge, but there could
+ * exist some slots associated to edge which are processed by input
+ * or output side and cannot be flushed at this moment.
+ * Return Value: The nonzero value indicates, that queue has not been
+ *     empty before the function call.
+ */
+int canque_flush(struct canque_edge_t *qedge)
+{
+       int ret;
+       can_spin_irqflags_t flags;
+
+       ret=canque_fifo_flush_slots(&qedge->fifo);
+       if(ret){
+               canque_notify_inends(qedge,CANQUEUE_NOTIFY_EMPTY);
+               canque_notify_inends(qedge,CANQUEUE_NOTIFY_SPACE);
+               can_spin_lock_irqsave(&qedge->outends->ends_lock, flags);
+               can_spin_lock(&qedge->fifo.fifo_lock);
+               if(canque_fifo_test_fl(&qedge->fifo,EMPTY)){
+                       list_del(&qedge->activepeers);
+                       list_add(&qedge->activepeers,&qedge->outends->idle);
+               }
+               can_spin_unlock(&qedge->fifo.fifo_lock);
+               can_spin_unlock_irqrestore(&qedge->outends->ends_lock, flags);
+       }
+       DEBUGQUE("canque_flush for edge %d returned %d\n",qedge->edge_num,ret);
+       return ret;
+}
+
+/**
+ * canqueue_ends_init_gen - subsystem independent routine to initialize ends state
+ * @qends: pointer to the ends structure
+ *
+ * Return Value: Cannot fail.
+ */
+int canqueue_ends_init_gen(struct canque_ends_t *qends)
+{
+       int i;
+       qends->ends_flags=0;
+       for(i=CANQUEUE_PRIO_NR;--i>=0;){
+               INIT_LIST_HEAD(&qends->active[i]);
+       }
+       INIT_LIST_HEAD(&qends->idle);
+       INIT_LIST_HEAD(&qends->inlist);
+       INIT_LIST_HEAD(&qends->outlist);
+       can_spin_lock_init(&qends->ends_lock);
+       return 0;
+}
+
+#if 0 /* move out edges */
+/**
+ * canqueue_connect_edge - connect edge between two communication entities
+ * @qedge: pointer to edge
+ * @inends: pointer to ends the input of the edge should be connected to
+ * @outends: pointer to ends the output of the edge should be connected to
+ *
+ * Return Value: Negative value informs about failed operation.
+ */
+int canqueue_connect_edge(struct canque_edge_t *qedge, struct canque_ends_t *inends, struct canque_ends_t *outends)
+{
+       can_spin_irqflags_t flags;
+       if(qedge == NULL) return -1;
+       DEBUGQUE("canqueue_connect_edge %d\n",qedge->edge_num);
+       canque_edge_incref(qedge);
+       flags=canque_edge_lock_both_ends(inends, outends);
+       can_spin_lock(&qedge->fifo.fifo_lock);
+       qedge->inends=inends;
+       list_add(&qedge->inpeers,&inends->inlist);
+       qedge->outends=outends;
+       list_add(&qedge->outpeers,&outends->outlist);
+       list_add(&qedge->activepeers,&outends->idle);
+       can_spin_unlock(&qedge->fifo.fifo_lock);
+       canque_edge_unlock_both_ends(inends, outends, flags);
+       canque_notify_bothends(qedge, CANQUEUE_NOTIFY_ATTACH);
+
+       if(canque_fifo_test_and_set_fl(&qedge->fifo, READY))
+               canque_edge_decref(qedge);
+       return 0;
+}
+
+/**
+ * canqueue_disconnect_edge - disconnect edge from communicating entities
+ * @qedge: pointer to edge
+ *
+ * Return Value: Negative value means, that edge is used by somebody
+ *     other and cannot be disconnected. Operation has to be delayed.
+ */
+int canqueue_disconnect_edge(struct canque_edge_t *qedge)
+{
+       int ret;
+       can_spin_irqflags_t flags;
+       struct canque_ends_t *inends, *outends;
+
+       inends=qedge->inends;
+       outends=qedge->outends;
+
+       if(inends && outends) {
+               flags=canque_edge_lock_both_ends(inends, outends);
+       } else {
+               DEBUGQUE("canqueue_disconnect_edge called with not fully connected edge");
+               if(inends) can_spin_lock_irqsave(&inends->ends_lock,flags);
+               if(outends) can_spin_lock(&outends->ends_lock);
+               flags=0;
+       }
+       
+       can_spin_lock(&qedge->fifo.fifo_lock);
+       if(atomic_read(&qedge->edge_used)==0) {
+               if(qedge->outends){
+                       list_del(&qedge->activepeers);
+                       mb(); /* memory barrier for list_empty use in canque_dead_func */
+                       list_del(&qedge->outpeers);
+                       qedge->outends=NULL;
+               }
+               if(qedge->inends){
+                       list_del(&qedge->inpeers);
+                       qedge->inends=NULL;
+               }
+               ret=1;
+       } else ret=-1;
+       can_spin_unlock(&qedge->fifo.fifo_lock);
+
+       if(inends && outends) {
+               canque_edge_unlock_both_ends(inends, outends, flags);
+       } else {
+               if(outends) can_spin_unlock(&outends->ends_lock);
+               if(inends) can_spin_unlock_irqrestore(&inends->ends_lock,flags);
+       }
+
+       DEBUGQUE("canqueue_disconnect_edge %d returned %d\n",qedge->edge_num,ret);
+       return ret;
+}
+
+
+/**
+ * canqueue_block_inlist - block slot allocation of all outgoing edges of specified ends  
+ * @qends: pointer to ends structure
+ */
+void canqueue_block_inlist(struct canque_ends_t *qends)
+{
+       struct canque_edge_t *edge;
+
+        canque_for_each_inedge(qends, edge) {
+               canque_fifo_set_fl(&edge->fifo,BLOCK);
+       }
+}
+
+
+/**
+ * canqueue_block_outlist - block slot allocation of all incoming edges of specified ends  
+ * @qends: pointer to ends structure
+ */
+void canqueue_block_outlist(struct canque_ends_t *qends)
+{
+       struct canque_edge_t *edge;
+
+        canque_for_each_outedge(qends, edge) {
+               canque_fifo_set_fl(&edge->fifo,BLOCK);
+       }
+}
+
+
+/**
+ * canqueue_ends_kill_inlist - sends request to die to all outgoing edges
+ * @qends: pointer to ends structure
+ * @send_rest: select, whether already allocated slots should be processed
+ *     by FIFO output side
+ *
+ * Return Value: Non-zero value means, that not all edges could be immediately
+ *     disconnected and that ends structure memory release has to be delayed
+ */
+int canqueue_ends_kill_inlist(struct canque_ends_t *qends, int send_rest)
+{
+       struct canque_edge_t *edge;
+       
+       canque_for_each_inedge(qends, edge){
+               canque_notify_bothends(edge, CANQUEUE_NOTIFY_DEAD_WANTED);
+               if(send_rest){
+                       canque_edge_incref(edge);
+                       if(!canque_fifo_test_and_set_fl(&edge->fifo, FREEONEMPTY)){
+                               if(!canque_fifo_test_fl(&edge->fifo, EMPTY))
+                                       continue;
+                               if(!canque_fifo_test_and_clear_fl(&edge->fifo, FREEONEMPTY))
+                                       continue;
+                       }
+                       canque_edge_decref(edge);
+               }
+       }
+       return list_empty(&qends->inlist)?0:1;
+}
+
+
+/**
+ * canqueue_ends_kill_outlist - sends request to die to all incoming edges
+ * @qends: pointer to ends structure
+ *
+ * Return Value: Non-zero value means, that not all edges could be immediately
+ *     disconnected and that ends structure memory release has to be delayed
+ */
+int canqueue_ends_kill_outlist(struct canque_ends_t *qends)
+{
+       struct canque_edge_t *edge;
+       
+       canque_for_each_outedge(qends, edge){
+               canque_notify_bothends(edge, CANQUEUE_NOTIFY_DEAD_WANTED);
+       }
+       return list_empty(&qends->outlist)?0:1;
+}
+
+
+/**
+ * canqueue_ends_filt_conjuction - computes conjunction of incoming edges filters filters
+ * @qends: pointer to ends structure
+ * @filt: pointer the filter structure filled by computed filters conjunction
+ *
+ * Return Value: Number of incoming edges
+ */
+int canqueue_ends_filt_conjuction(struct canque_ends_t *qends, struct canfilt_t *filt)
+{
+       struct canque_edge_t *edge;
+       int cnt=0;
+       unsigned long filtid=0;
+       unsigned long filtmask=~0;
+       unsigned long local_only=canque_filtid2internal(0,MSG_LOCAL);
+
+       canque_for_each_inedge(qends, edge){
+               /* skip edges processing only local messages */
+               if(edge->filtid & edge->filtmask & local_only)
+                       continue;
+
+               if(!cnt++)
+                       filtid = edge->filtid;
+               else
+                       filtmask &= ~(filtid ^ edge->filtid);
+       
+               filtmask &= edge->filtmask;
+       }
+       
+       filt->id = filtid & MSG_ID_MASK;
+       filt->mask = filtmask & MSG_ID_MASK;
+       filtid >>= 28;
+       filtmask >>= 28;
+       filt->flags = filtid & MSG_EXT;
+       if(filtmask & (MSG_EXT))
+               filt->flags |= MSG_EXT_MASK;
+       if(filtid & (MSG_RTR<<1))
+               filt->flags |= MSG_RTR<<1;
+       if(filtmask & (MSG_RTR<<1))
+               filt->flags |= MSG_RTR_MASK;
+       return cnt;
+}
+
+
+/**
+ * canqueue_ends_flush_inlist - flushes all messages in incoming edges
+ * @qends: pointer to ends structure
+ *
+ * Return Value: Negative value informs about unsuccessful result
+ */
+int canqueue_ends_flush_inlist(struct canque_ends_t *qends)
+{
+       struct canque_edge_t *edge;
+       
+       canque_for_each_inedge(qends, edge){
+               canque_flush(edge);
+       }
+       return 0;
+}
+
+
+/**
+ * canqueue_ends_flush_outlist - flushes all messages in outgoing edges
+ * @qends: pointer to ends structure
+ *
+ * Return Value: Negative value informs about unsuccessful result
+ */
+int canqueue_ends_flush_outlist(struct canque_ends_t *qends)
+{
+       struct canque_edge_t *edge;
+       
+       canque_for_each_outedge(qends, edge){
+               canque_flush(edge);
+       }
+       return 0;
+}
+#endif /* move out edges */
+
+
+
diff --git a/app/cantest/can_drive/can_queue.h b/app/cantest/can_drive/can_queue.h
new file mode 100644 (file)
index 0000000..9c9d606
--- /dev/null
@@ -0,0 +1,815 @@
+/* can_queue.h - CAN queues and message passing infrastructure 
+ * Linux CAN-bus device driver.
+ * Written by Pavel Pisa - OCERA team member
+ * email:pisa@cmp.felk.cvut.cz
+ * This software is released under the GPL-License.
+ * Version lincan-0.3  17 Jun 2004
+ */
+
+#ifndef _CAN_QUEUE_H
+#define _CAN_QUEUE_H
+
+//#include "./canmsg.h"
+#include "canmsg.h"
+//#include "./constants.h"
+#include "constants.h"
+#include "./can_sysdep.h"
+
+/**
+ * struct canque_slot_t - one CAN message slot in the CAN FIFO queue 
+ * @next: pointer to the next/younger slot
+ * @slot_flags: space for flags and optional command describing action
+ *     associated with slot data
+ * @msg: space for one CAN message
+ *
+ * This structure is used to store CAN messages in the CAN FIFO queue.
+ */
+ struct canque_slot_t {
+       struct canque_slot_t *next;
+       unsigned long slot_flags;
+       struct canmsg_t msg;
+};
+
+#define CAN_SLOTF_CMD  0x00ff  /*  */
+
+/**
+ * struct canque_fifo_t - CAN FIFO queue representation
+ * @fifo_flags: this field holds global flags describing state of the FIFO.
+ *     %CAN_FIFOF_ERROR is set when some error condition occurs.
+ *     %CAN_FIFOF_ERR2BLOCK defines, that error should lead to the FIFO block state.
+ *     %CAN_FIFOF_BLOCK state blocks insertion of the next messages. 
+ *     %CAN_FIFOF_OVERRUN attempt to acquire new slot, when FIFO is full. 
+ *     %CAN_FIFOF_FULL indicates FIFO full state. 
+ *     %CAN_FIFOF_EMPTY indicates no allocated slot in the FIFO.
+ *     %CAN_FIFOF_DEAD condition indication. Used when FIFO is beeing destroyed.
+ * @error_code: futher description of error condition
+ * @head: pointer to the FIFO head, oldest slot
+ * @tail: pointer to the location, where pointer to newly inserted slot
+ *     should be added
+ * @flist: pointer to list of the free slots associated with queue
+ * @entry: pointer to the memory allocated for the list slots.
+ * @fifo_lock: the lock to ensure atomicity of slot manipulation operations.
+ * @slotsnr:  number of allocated slots
+ *
+ * This structure represents CAN FIFO queue. It is implemented as 
+ * a single linked list of slots prepared for processing. The empty slots
+ * are stored in single linked list (@flist).
+ */
+struct canque_fifo_t {
+       unsigned long fifo_flags;
+       unsigned long error_code;
+       struct canque_slot_t *head;     /* points to the oldest entry */
+       struct canque_slot_t **tail;    /* points to NULL pointer for chaining */
+       struct canque_slot_t *flist;    /* points the first entry in the free list */
+       struct canque_slot_t *entry;    /* points to first allocated entry */
+       can_spinlock_t fifo_lock;       /* can_spin_lock_irqsave / can_spin_unlock_irqrestore */
+       int    slotsnr;
+};
+
+#define CAN_FIFOF_DESTROY_b    15
+#define CAN_FIFOF_ERROR_b      14
+#define CAN_FIFOF_ERR2BLOCK_b  13
+#define CAN_FIFOF_BLOCK_b      12
+#define CAN_FIFOF_OVERRUN_b    11
+#define CAN_FIFOF_FULL_b       10
+#define CAN_FIFOF_EMPTY_b      9
+#define CAN_FIFOF_DEAD_b       8
+#define CAN_FIFOF_INACTIVE_b   7
+#define CAN_FIFOF_FREEONEMPTY_b        6
+#define CAN_FIFOF_READY_b      5
+#define CAN_FIFOF_NOTIFYPEND_b 4
+#define CAN_FIFOF_RTL_MEM_b    3
+
+#define CAN_FIFOF_DESTROY      (1<<CAN_FIFOF_DESTROY_b)
+#define CAN_FIFOF_ERROR                (1<<CAN_FIFOF_ERROR_b)
+#define CAN_FIFOF_ERR2BLOCK    (1<<CAN_FIFOF_ERR2BLOCK_b)
+#define CAN_FIFOF_BLOCK                (1<<CAN_FIFOF_BLOCK_b)
+#define CAN_FIFOF_OVERRUN      (1<<CAN_FIFOF_OVERRUN_b)
+#define CAN_FIFOF_FULL         (1<<CAN_FIFOF_FULL_b)
+#define CAN_FIFOF_EMPTY                (1<<CAN_FIFOF_EMPTY_b)
+#define CAN_FIFOF_DEAD         (1<<CAN_FIFOF_DEAD_b)
+#define CAN_FIFOF_INACTIVE     (1<<CAN_FIFOF_INACTIVE_b)
+#define CAN_FIFOF_FREEONEMPTY  (1<<CAN_FIFOF_FREEONEMPTY_b)
+#define CAN_FIFOF_READY                (1<<CAN_FIFOF_READY_b)
+#define CAN_FIFOF_NOTIFYPEND    (1<<CAN_FIFOF_NOTIFYPEND_b)
+#define CAN_FIFOF_RTL_MEM       (1<<CAN_FIFOF_RTL_MEM_b)
+
+#define canque_fifo_test_fl(fifo,fifo_fl) \
+  test_bit(CAN_FIFOF_##fifo_fl##_b,&(fifo)->fifo_flags)
+#define canque_fifo_set_fl(fifo,fifo_fl) \
+  set_bit(CAN_FIFOF_##fifo_fl##_b,&(fifo)->fifo_flags)
+#define canque_fifo_clear_fl(fifo,fifo_fl) \
+  clear_bit(CAN_FIFOF_##fifo_fl##_b,&(fifo)->fifo_flags)
+#define canque_fifo_test_and_set_fl(fifo,fifo_fl) \
+  test_and_set_bit(CAN_FIFOF_##fifo_fl##_b,&(fifo)->fifo_flags)
+#define canque_fifo_test_and_clear_fl(fifo,fifo_fl) \
+  test_and_clear_bit(CAN_FIFOF_##fifo_fl##_b,&(fifo)->fifo_flags)
+
+
+/**
+ * canque_fifo_get_inslot - allocate slot for the input of one CAN message 
+ * @fifo: pointer to the FIFO structure
+ * @slotp: pointer to location to store pointer to the allocated slot.
+ * @cmd: optional command associated with allocated slot.
+ *
+ * Return Value: The function returns negative value if there is no
+ *     free slot in the FIFO queue.
+ */
+static inline
+int canque_fifo_get_inslot(struct canque_fifo_t *fifo, struct canque_slot_t **slotp, int cmd)
+{
+       can_spin_irqflags_t flags;
+       struct canque_slot_t *slot;
+       can_spin_lock_irqsave(&fifo->fifo_lock, flags);
+       /* get the first free slot slot from flist */
+       if(!(slot=fifo->flist)) {
+               canque_fifo_set_fl(fifo,OVERRUN);
+               canque_fifo_set_fl(fifo,FULL);
+               can_spin_unlock_irqrestore(&fifo->fifo_lock, flags);
+               *slotp=NULL;
+               return -1;
+       }
+       /* adjust free slot list */
+       if(!(fifo->flist=slot->next))
+               canque_fifo_set_fl(fifo,FULL);
+       can_spin_unlock_irqrestore(&fifo->fifo_lock, flags);
+       *slotp=slot;
+       slot->slot_flags=cmd&CAN_SLOTF_CMD;
+       return 1;
+}
+
+/**
+ * canque_fifo_put_inslot - releases slot to further processing
+ * @fifo: pointer to the FIFO structure
+ * @slot: pointer to the slot previously acquired by canque_fifo_get_inslot().
+ *
+ * Return Value: The nonzero return value indicates, that the queue was empty
+ *     before call to the function. The caller should wake-up output side of the queue.
+ */
+static inline
+int canque_fifo_put_inslot(struct canque_fifo_t *fifo, struct canque_slot_t *slot)
+{
+       int ret;
+       can_spin_irqflags_t flags;
+       slot->next=NULL;
+       can_spin_lock_irqsave(&fifo->fifo_lock, flags);
+       if(*fifo->tail) can_printk(KERN_CRIT "canque_fifo_put_inslot: fifo->tail != NULL\n");
+       *fifo->tail=slot;
+       fifo->tail=&slot->next;
+       ret=0;
+       if(canque_fifo_test_and_clear_fl(fifo,EMPTY))
+         ret=CAN_FIFOF_EMPTY;  /* Fifo has been empty before put */
+       if(canque_fifo_test_and_clear_fl(fifo,INACTIVE))
+         ret=CAN_FIFOF_INACTIVE; /* Fifo has been empty before put */
+       can_spin_unlock_irqrestore(&fifo->fifo_lock, flags);
+       return ret;
+}
+
+/**
+ * canque_fifo_abort_inslot - release and abort slot
+ * @fifo: pointer to the FIFO structure
+ * @slot: pointer to the slot previously acquired by canque_fifo_get_inslot().
+ *
+ * Return Value: The nonzero value indicates, that fifo was full
+ */
+static inline
+int canque_fifo_abort_inslot(struct canque_fifo_t *fifo, struct canque_slot_t *slot)
+{
+       int ret=0;
+       can_spin_irqflags_t flags;
+       can_spin_lock_irqsave(&fifo->fifo_lock, flags);
+       slot->next=fifo->flist;
+       fifo->flist=slot;
+       if(canque_fifo_test_and_clear_fl(fifo,FULL))
+               ret=CAN_FIFOF_FULL;
+       can_spin_unlock_irqrestore(&fifo->fifo_lock, flags);
+       return ret;
+}
+
+/**
+ * canque_fifo_test_outslot - test and get ready slot from the FIFO
+ * @fifo: pointer to the FIFO structure
+ * @slotp: pointer to location to store pointer to the oldest slot from the FIFO.
+ *
+ * Return Value: The negative value indicates, that queue is empty.
+ *     The positive or zero value represents command stored into slot by
+ *     the call to the function canque_fifo_get_inslot().
+ *     The successfully acquired FIFO output slot has to be released by
+ *     the call canque_fifo_free_outslot() or canque_fifo_again_outslot().
+ */
+static inline
+int canque_fifo_test_outslot(struct canque_fifo_t *fifo, struct canque_slot_t **slotp)
+{
+       can_spin_irqflags_t flags;
+       int cmd;
+       struct canque_slot_t *slot;
+       can_spin_lock_irqsave(&fifo->fifo_lock, flags);
+       if(!(slot=fifo->head)){;
+               canque_fifo_set_fl(fifo,EMPTY);
+               can_spin_unlock_irqrestore(&fifo->fifo_lock, flags);
+               *slotp=NULL;
+               return -1;
+       }
+       if(!(fifo->head=slot->next))
+               fifo->tail=&fifo->head;
+       can_spin_unlock_irqrestore(&fifo->fifo_lock, flags);
+
+       *slotp=slot;
+       cmd=slot->slot_flags;
+       return cmd&CAN_SLOTF_CMD;
+}
+
+
+/**
+ * canque_fifo_free_outslot - free processed FIFO slot
+ * @fifo: pointer to the FIFO structure
+ * @slot: pointer to the slot previously acquired by canque_fifo_test_outslot().
+ *
+ * Return Value: The returned value informs about FIFO state change.
+ *     The mask %CAN_FIFOF_FULL indicates, that the FIFO was full before
+ *     the function call. The mask %CAN_FIFOF_EMPTY informs, that last ready slot
+ *     has been processed.
+ */
+static inline
+int canque_fifo_free_outslot(struct canque_fifo_t *fifo, struct canque_slot_t *slot)
+{
+       int ret=0;
+       can_spin_irqflags_t flags;
+       can_spin_lock_irqsave(&fifo->fifo_lock, flags);
+       slot->next=fifo->flist;
+       fifo->flist=slot;
+       if(canque_fifo_test_and_clear_fl(fifo,FULL))
+               ret=CAN_FIFOF_FULL;
+       if(!(fifo->head)){
+               canque_fifo_set_fl(fifo,EMPTY);
+               ret|=CAN_FIFOF_EMPTY;
+       }
+       can_spin_unlock_irqrestore(&fifo->fifo_lock, flags);
+       return ret;
+}
+
+/**
+ * canque_fifo_again_outslot - interrupt and postpone processing of the slot
+ * @fifo: pointer to the FIFO structure
+ * @slot: pointer to the slot previously acquired by canque_fifo_test_outslot().
+ *
+ * Return Value: The function cannot fail..
+ */
+static inline
+int canque_fifo_again_outslot(struct canque_fifo_t *fifo, struct canque_slot_t *slot)
+{
+       can_spin_irqflags_t flags;
+       can_spin_lock_irqsave(&fifo->fifo_lock, flags);
+       if(!(slot->next=fifo->head))
+               fifo->tail=&slot->next;
+       fifo->head=slot;
+       can_spin_unlock_irqrestore(&fifo->fifo_lock, flags);
+       return 1;
+}
+
+int canque_fifo_flush_slots(struct canque_fifo_t *fifo);
+
+int canque_fifo_init_slots(struct canque_fifo_t *fifo);
+
+#define CANQUEUE_PRIO_NR  3
+
+/* Forward declarations for external types */
+struct msgobj_t;
+struct canchip_t;
+
+#if 0 /* move out edges */
+/**
+ * struct canque_edge_t - CAN message delivery subsystem graph edge
+ * @fifo: place where primitive @struct canque_fifo_t FIFO is located.
+ * @filtid: the possible CAN message identifiers filter.
+ * @filtmask: the filter mask, the comparison considers only
+ *     @filtid bits corresponding to set bits in the @filtmask field.
+ * @inpeers: the lists of all peers FIFOs connected by their
+ *     input side (@inends) to the same terminal (@struct canque_ends_t).
+ * @outpeers: the lists of all peers FIFOs connected by their
+ *     output side (@outends) to the same terminal (@struct canque_ends_t).
+ * @activepeers: the lists of peers FIFOs connected by their
+ *     output side (@outends) to the same terminal (@struct canque_ends_t)
+ *     with same priority and active state.
+ * @inends: the pointer to the FIFO input side terminal (@struct canque_ends_t).
+ * @outends: the pointer to the FIFO output side terminal (@struct canque_ends_t).
+ * @edge_used: the atomic usage counter, mainly used for safe destruction of the edge.
+ * @edge_prio: the assigned queue priority from the range 0 to %CANQUEUE_PRIO_NR-1
+ * @edge_num: edge sequential number intended for debugging purposes only
+ * @pending_peers: edges with pending delayed events (RTL->Linux calls)
+ * @pending_inops: bitmask of pending operations
+ * @pending_outops: bitmask of pending operations
+ *
+ * This structure represents one direction connection from messages source 
+ * (@inends) to message consumer (@outends) fifo ends hub. The edge contains
+ * &struct canque_fifo_t for message fifo implementation.
+ */
+struct canque_edge_t {
+       struct canque_fifo_t fifo;
+       unsigned long filtid;
+       unsigned long filtmask;
+       struct list_head inpeers;
+       struct list_head outpeers;
+       struct list_head activepeers;
+       struct canque_ends_t *inends;
+       struct canque_ends_t *outends;
+       atomic_t edge_used;
+       int edge_prio;
+       int edge_num;
+    #ifdef CAN_WITH_RTL
+       struct list_head pending_peers;
+       unsigned long pending_inops;
+       unsigned long pending_outops;
+    #endif /*CAN_WITH_RTL*/
+};
+
+/**
+ * struct canque_ends_t - CAN message delivery subsystem graph vertex (FIFO ends)
+ * @ends_flags: this field holds flags describing state of the ENDS structure.
+ * @active: the array of the lists of active edges directed to the ends structure
+ *     with ready messages. The array is indexed by the edges priorities. 
+ * @idle: the list of the edges directed to the ends structure with empty FIFOs.
+ * @inlist: the list of outgoing edges input sides.
+ * @outlist: the list of all incoming edges output sides. Each of there edges
+ *     is listed on one of @active or @idle lists.
+ * @ends_lock: the lock synchronizing operations between threads accessing
+ *     same ends structure.
+ * @notify: pointer to notify procedure. The next state changes are notified.
+ *     %CANQUEUE_NOTIFY_EMPTY (out->in call) - all slots are processed by FIFO out side. 
+ *     %CANQUEUE_NOTIFY_SPACE (out->in call) - full state negated => there is space for new message.
+ *     %CANQUEUE_NOTIFY_PROC  (in->out call) - empty state negated => out side is requested to process slots.
+ *     %CANQUEUE_NOTIFY_NOUSR (both) - notify, that the last user has released the edge usage
+ *             called with some lock to prevent edge disappear.
+ *     %CANQUEUE_NOTIFY_DEAD  (both) - edge is in progress of deletion.
+ *     %CANQUEUE_NOTIFY_ATACH (both) - new edge has been attached to end.
+ *     %CANQUEUE_NOTIFY_FILTCH (out->in call) - edge filter rules changed
+ *     %CANQUEUE_NOTIFY_ERROR  (out->in call) - error in messages processing.
+ * @context: space to store ends user specific information
+ * @endinfo: space to store some other ends usage specific informations
+ *     mainly for waking-up by the notify calls.
+ * @dead_peers: used to chain ends wanting for postponed destruction
+ *
+ * Structure represents place to connect edges to for CAN communication entity.
+ * The zero, one or more incoming and outgoing edges can be connected to
+ * this structure.
+ */
+struct canque_ends_t {
+       unsigned long ends_flags;
+       struct list_head active[CANQUEUE_PRIO_NR];
+       struct list_head idle;
+       struct list_head inlist;
+       struct list_head outlist;
+       can_spinlock_t ends_lock;       /* can_spin_lock_irqsave / can_spin_unlock_irqrestore */
+       void (*notify)(struct canque_ends_t *qends, struct canque_edge_t *qedge, int what);
+       void *context;
+       union {
+               struct {
+                       wait_queue_head_t readq;
+                       wait_queue_head_t writeq;
+                       wait_queue_head_t emptyq;
+                   #ifdef CAN_ENABLE_KERN_FASYNC
+                       struct fasync_struct *fasync;
+                   #endif /*CAN_ENABLE_KERN_FASYNC*/
+               } fileinfo;
+           #ifdef CAN_WITH_RTL
+               struct {
+                       rtl_spinlock_t rtl_lock;
+                       rtl_wait_t rtl_readq;
+                       atomic_t   rtl_readq_age;
+                       rtl_wait_t rtl_writeq;
+                       atomic_t   rtl_writeq_age;
+                       rtl_wait_t rtl_emptyq;
+                       atomic_t   rtl_emptyq_age;
+                       unsigned long pend_flags;
+               } rtlinfo;
+           #endif /*CAN_WITH_RTL*/
+               struct {
+                       struct msgobj_t *msgobj;
+                       struct canchip_t *chip;
+                   #ifndef CAN_WITH_RTL
+                       wait_queue_head_t daemonq;
+                   #else /*CAN_WITH_RTL*/
+                       pthread_t worker_thread;
+                   #endif /*CAN_WITH_RTL*/
+               } chipinfo;
+       } endinfo;
+       struct list_head dead_peers;
+};
+#endif /* move out edges */
+
+#define CANQUEUE_NOTIFY_EMPTY  1 /* out -> in - all slots are processed by FIFO out side */
+#define CANQUEUE_NOTIFY_SPACE  2 /* out -> in - full state negated => there is space for new message */
+#define CANQUEUE_NOTIFY_PROC   3 /* in -> out - empty state negated => out side is requested to process slots */
+#define CANQUEUE_NOTIFY_NOUSR  4 /* called with some lock to prevent edge disappear */
+#define CANQUEUE_NOTIFY_DEAD   5 /*  */
+#define CANQUEUE_NOTIFY_DEAD_WANTED 6 /*  */
+#define CANQUEUE_NOTIFY_ATTACH 7 /*  */
+#define CANQUEUE_NOTIFY_FILTCH 8 /* filter changed */
+#define CANQUEUE_NOTIFY_ERROR      0x10000 /* error notifiers */
+#define CANQUEUE_NOTIFY_ERRTX_PREP 0x11001 /* tx preparation error */
+#define CANQUEUE_NOTIFY_ERRTX_SEND 0x11002 /* tx send error */
+#define CANQUEUE_NOTIFY_ERRTX_BUS  0x11003 /* tx bus error */
+
+#define CAN_ENDSF_DEAD   (1<<0)
+#define CAN_ENDSF_MEM_RTL (1<<1)
+
+/**
+ * canque_notify_inends - request to send notification to the input ends
+ * @qedge: pointer to the edge structure
+ * @what: notification type
+ */
+static inline
+void canque_notify_inends(struct canque_edge_t *qedge, int what)
+{
+       if(qedge->inends)
+               if(qedge->inends->notify)
+                       qedge->inends->notify(qedge->inends,qedge,what);
+}
+
+/**
+ * canque_notify_outends - request to send notification to the output ends
+ * @qedge: pointer to the edge structure
+ * @what: notification type
+ */
+static inline
+void canque_notify_outends(struct canque_edge_t *qedge, int what)
+{
+       if(qedge->outends)
+               if(qedge->outends->notify)
+                       qedge->outends->notify(qedge->outends,qedge,what);
+}
+
+/**
+ * canque_notify_bothends - request to send notification to the both ends
+ * @qedge: pointer to the edge structure
+ * @what: notification type
+ */
+static inline
+void canque_notify_bothends(struct canque_edge_t *qedge, int what)
+{
+       canque_notify_inends(qedge, what);
+       canque_notify_outends(qedge, what);
+}
+
+#if 0 /* move out edges */
+/**
+ * canque_activate_edge - mark output end of the edge as active
+ * @qedge: pointer to the edge structure
+ * @inends: input side of the edge
+ *
+ * Function call moves output side of the edge from idle onto active edges
+ * list. This function has to be called with edge reference count held.
+ * that is same as for most of other edge functions.
+ */
+static inline
+void canque_activate_edge(struct canque_ends_t *inends, struct canque_edge_t *qedge)
+{
+       can_spin_irqflags_t flags;
+       struct canque_ends_t *outends;
+       if(qedge->edge_prio>=CANQUEUE_PRIO_NR)
+               qedge->edge_prio=CANQUEUE_PRIO_NR-1;
+       if((outends=qedge->outends)){
+               can_spin_lock_irqsave(&outends->ends_lock, flags);
+               can_spin_lock(&qedge->fifo.fifo_lock);
+               if(!canque_fifo_test_fl(&qedge->fifo,EMPTY)){
+                       list_del(&qedge->activepeers);
+                       list_add_tail(&qedge->activepeers,&outends->active[qedge->edge_prio]);
+               }
+               can_spin_unlock(&qedge->fifo.fifo_lock);
+               can_spin_unlock_irqrestore(&outends->ends_lock, flags);
+       }
+}
+#endif /* move out edges */
+
+/**
+ * canque_filtid2internal - converts message ID and filter flags into internal format
+ * @id: CAN message 11 or 29 bit identifier
+ * @filtflags: CAN message flags
+ *
+ * This function maps message ID and %MSG_RTR, %MSG_EXT and %MSG_LOCAL into one 32 bit number
+ */
+static inline
+unsigned int canque_filtid2internal(unsigned long id, int filtflags)
+{
+       filtflags &= MSG_RTR|MSG_EXT|MSG_LOCAL;
+       filtflags += filtflags&MSG_RTR;
+       return (id&MSG_ID_MASK) | (filtflags<<28);
+}
+
+int canque_get_inslot(struct canque_ends_t *qends,
+       struct canque_edge_t **qedgep, struct canque_slot_t **slotp, int cmd);
+       
+int canque_get_inslot4id(struct canque_ends_t *qends,
+       struct canque_edge_t **qedgep, struct canque_slot_t **slotp,
+       int cmd, unsigned long id, int prio);
+       
+int canque_put_inslot(struct canque_ends_t *qends,
+       struct canque_edge_t *qedge, struct canque_slot_t *slot);
+
+int canque_abort_inslot(struct canque_ends_t *qends,
+       struct canque_edge_t *qedge, struct canque_slot_t *slot);
+
+//int canque_filter_msg2edges(struct canque_ends_t *qends, struct canmsg_t *msg);
+
+int canque_test_outslot(struct canque_ends_t *qends,
+       struct canque_edge_t **qedgep, struct canque_slot_t **slotp);
+
+int canque_free_outslot(struct canque_ends_t *qends,
+       struct canque_edge_t *qedge, struct canque_slot_t *slot);
+
+int canque_again_outslot(struct canque_ends_t *qends,
+       struct canque_edge_t *qedge, struct canque_slot_t *slot);
+
+int canque_set_filt(struct canque_edge_t *qedge,
+       unsigned long filtid, unsigned long filtmask, int flags);
+       
+int canque_flush(struct canque_edge_t *qedge);
+
+int canqueue_disconnect_edge(struct canque_edge_t *qedge);
+
+int canqueue_connect_edge(struct canque_edge_t *qedge, struct canque_ends_t *inends, struct canque_ends_t *outends);
+
+int canqueue_ends_init_gen(struct canque_ends_t *qends);
+
+void canqueue_block_inlist(struct canque_ends_t *qends);
+
+void canqueue_block_outlist(struct canque_ends_t *qends);
+
+int canqueue_ends_kill_inlist(struct canque_ends_t *qends, int send_rest);
+
+int canqueue_ends_kill_outlist(struct canque_ends_t *qends);
+
+int canqueue_ends_filt_conjuction(struct canque_ends_t *qends, struct canfilt_t *filt);
+
+int canqueue_ends_flush_inlist(struct canque_ends_t *qends);
+
+int canqueue_ends_flush_outlist(struct canque_ends_t *qends);
+
+/* edge reference and traversal functions */
+
+void canque_edge_do_dead(struct canque_edge_t *edge);
+
+/**
+ * canque_edge_incref - increments edge reference count
+ * @edge: pointer to the edge structure
+ */
+static inline
+void canque_edge_incref(struct canque_edge_t *edge)
+{
+       atomic_inc(&edge->edge_used);
+}
+
+static inline
+can_spin_irqflags_t canque_edge_lock_both_ends(struct canque_ends_t *inends, struct canque_ends_t *outends)
+{
+       can_spin_irqflags_t  flags;
+       if(inends<outends) {
+               can_spin_lock_irqsave(&inends->ends_lock, flags);
+               can_spin_lock(&outends->ends_lock);
+       }else{
+               can_spin_lock_irqsave(&outends->ends_lock, flags);
+               if(outends!=inends) can_spin_lock(&inends->ends_lock);
+       }
+       return flags;   
+}
+
+static inline
+void canque_edge_unlock_both_ends(struct canque_ends_t *inends, struct canque_ends_t *outends, can_spin_irqflags_t flags)
+{
+       if(outends!=inends) can_spin_unlock(&outends->ends_lock);
+       can_spin_unlock_irqrestore(&inends->ends_lock, flags);
+}
+
+/* Non-inlined version of edge reference decrement */
+void __canque_edge_decref(struct canque_edge_t *edge);
+
+static inline
+void __canque_edge_decref_body(struct canque_edge_t *edge)
+{
+       can_spin_irqflags_t flags;
+       int dead_fl=0;
+       struct canque_ends_t *inends=edge->inends;
+       struct canque_ends_t *outends=edge->outends;
+       
+       flags=canque_edge_lock_both_ends(inends, outends);
+       if(atomic_dec_and_test(&edge->edge_used)) {
+               dead_fl=!canque_fifo_test_and_set_fl(&edge->fifo,DEAD);
+               /* Because of former evolution of edge references 
+                  management notify of CANQUEUE_NOTIFY_NOUSR could
+                  be moved to canque_edge_do_dead :-) */
+       }
+       canque_edge_unlock_both_ends(inends, outends, flags);
+       if(dead_fl) canque_edge_do_dead(edge);
+}
+
+#ifndef CAN_HAVE_ARCH_CMPXCHG
+/**
+ * canque_edge_decref - decrements edge reference count
+ * @edge: pointer to the edge structure
+ *
+ * This function has to be called without lock held for both ends of edge.
+ * If reference count drops to 0, function canque_edge_do_dead()
+ * is called.
+ */
+static inline
+void canque_edge_decref(struct canque_edge_t *edge)
+{
+       __canque_edge_decref_body(edge);
+}
+#else
+static inline
+void canque_edge_decref(struct canque_edge_t *edge)
+{
+       int x, y;
+       
+        x = atomic_read(&edge->edge_used);
+        do{
+               if(x<=1)
+                       return __canque_edge_decref(edge);
+               y=x;
+               /* This code strongly depends on the definition of atomic_t !!!! */
+               /* x=cmpxchg(&edge->edge_used, x, x-1); */
+               /* Next alternative could be more portable */
+               x=__cmpxchg(&edge->edge_used, x, x-1, sizeof(atomic_t));
+               /* If even this does not help, comment out CAN_HAVE_ARCH_CMPXCHG in can_sysdep.h */
+       } while(x!=y);
+}
+#endif
+
+static inline
+struct canque_edge_t *canque_first_inedge(struct canque_ends_t *qends)
+{
+       can_spin_irqflags_t flags;
+       struct list_head *entry;
+       struct canque_edge_t *edge;
+       
+       can_spin_lock_irqsave(&qends->ends_lock, flags);
+       entry=qends->inlist.next;
+    skip_dead:
+       if(entry != &qends->inlist) {
+               edge=list_entry(entry,struct canque_edge_t,inpeers);
+               if(canque_fifo_test_fl(&edge->fifo,DEAD)) {
+                       entry=entry->next;
+                       goto skip_dead;
+               }
+               canque_edge_incref(edge);
+       } else {
+               edge=NULL;
+       }
+       can_spin_unlock_irqrestore(&qends->ends_lock, flags);
+       return edge;
+}
+
+
+static inline
+struct canque_edge_t *canque_next_inedge(struct canque_ends_t *qends, struct canque_edge_t *edge)
+{
+       can_spin_irqflags_t flags;
+       struct list_head *entry;
+       struct canque_edge_t *next;
+       
+       can_spin_lock_irqsave(&qends->ends_lock, flags);
+       entry=edge->inpeers.next;
+    skip_dead:
+       if(entry != &qends->inlist) {
+               next=list_entry(entry,struct canque_edge_t,inpeers);
+               if(canque_fifo_test_fl(&edge->fifo,DEAD)) {
+                       entry=entry->next;
+                       goto skip_dead;
+               }
+               canque_edge_incref(next);
+       } else {
+               next=NULL;
+       }
+       can_spin_unlock_irqrestore(&qends->ends_lock, flags);
+       canque_edge_decref(edge);
+       return next;
+}
+
+#define canque_for_each_inedge(qends, edge) \
+           for(edge=canque_first_inedge(qends);edge;edge=canque_next_inedge(qends, edge))
+
+static inline
+struct canque_edge_t *canque_first_outedge(struct canque_ends_t *qends)
+{
+       can_spin_irqflags_t flags;
+       struct list_head *entry;
+       struct canque_edge_t *edge;
+       
+       can_spin_lock_irqsave(&qends->ends_lock, flags);
+       entry=qends->outlist.next;
+    skip_dead:
+       if(entry != &qends->outlist) {
+               edge=list_entry(entry,struct canque_edge_t,outpeers);
+               if(canque_fifo_test_fl(&edge->fifo,DEAD)) {
+                       entry=entry->next;
+                       goto skip_dead;
+               }
+               canque_edge_incref(edge);
+       } else {
+               edge=NULL;
+       }
+       can_spin_unlock_irqrestore(&qends->ends_lock, flags);
+       return edge;
+}
+
+
+static inline
+struct canque_edge_t *canque_next_outedge(struct canque_ends_t *qends, struct canque_edge_t *edge)
+{
+       can_spin_irqflags_t flags;
+       struct list_head *entry;
+       struct canque_edge_t *next;
+       
+       can_spin_lock_irqsave(&qends->ends_lock, flags);
+       entry=edge->outpeers.next;
+    skip_dead:
+       if(entry != &qends->outlist) {
+               next=list_entry(entry,struct canque_edge_t,outpeers);
+               if(canque_fifo_test_fl(&edge->fifo,DEAD)) {
+                       entry=entry->next;
+                       goto skip_dead;
+               }
+               canque_edge_incref(next);
+       } else {
+               next=NULL;
+       }
+       can_spin_unlock_irqrestore(&qends->ends_lock, flags);
+       canque_edge_decref(edge);
+       return next;
+}
+
+#define canque_for_each_outedge(qends, edge) \
+           for(edge=canque_first_outedge(qends);edge;edge=canque_next_outedge(qends, edge))
+
+/* Linux kernel specific functions */
+
+int canque_fifo_init_kern(struct canque_fifo_t *fifo, int slotsnr);
+
+int canque_fifo_done_kern(struct canque_fifo_t *fifo);
+
+struct canque_edge_t *canque_new_edge_kern(int slotsnr);
+
+int canque_get_inslot4id_wait_kern(struct canque_ends_t *qends,
+       struct canque_edge_t **qedgep, struct canque_slot_t **slotp,
+       int cmd, unsigned long id, int prio);
+
+int canque_get_outslot_wait_kern(struct canque_ends_t *qends,
+       struct canque_edge_t **qedgep, struct canque_slot_t **slotp);
+
+int canque_sync_wait_kern(struct canque_ends_t *qends, struct canque_edge_t *qedge);
+
+int canqueue_ends_init_kern(struct canque_ends_t *qends);
+
+int canqueue_ends_dispose_kern(struct canque_ends_t *qends, int sync);
+
+void canqueue_ends_dispose_postpone(struct canque_ends_t *qends);
+
+void canqueue_kern_initialize(void);
+
+#ifdef CAN_WITH_RTL
+
+extern struct tasklet_struct canque_dead_tl;   /*publication required only for RTL*/
+
+/* RT-Linux specific functions and variables */
+
+extern int canqueue_rtl_irq;
+
+extern unsigned long canqueue_rtl2lin_pend;
+
+#define CAN_RTL2LIN_PEND_DEAD_b 0
+
+void canqueue_rtl_initialize(void);
+void canqueue_rtl_done(void);
+
+int canqueue_rtl2lin_check_and_pend(struct canque_ends_t *qends,
+                        struct canque_edge_t *qedge, int what);
+
+struct canque_edge_t *canque_new_edge_rtl(int slotsnr);
+
+void canque_dispose_edge_rtl(struct canque_edge_t *qedge);
+
+int canque_get_inslot4id_wait_rtl(struct canque_ends_t *qends,
+       struct canque_edge_t **qedgep, struct canque_slot_t **slotp,
+       int cmd, unsigned long id, int prio);
+
+int canque_get_outslot_wait_rtl(struct canque_ends_t *qends,
+       struct canque_edge_t **qedgep, struct canque_slot_t **slotp);
+
+int canque_sync_wait_rtl(struct canque_ends_t *qends, struct canque_edge_t *qedge);
+
+void canque_ends_free_rtl(struct canque_ends_t *qends);
+
+int canqueue_ends_init_rtl(struct canque_ends_t *qends);
+
+int canqueue_ends_dispose_rtl(struct canque_ends_t *qends, int sync);
+
+#else /*CAN_WITH_RTL*/
+
+static inline int canqueue_rtl2lin_check_and_pend(struct canque_ends_t *qends,
+                       struct canque_edge_t *qedge, int what) { return 0; }
+
+#endif /*CAN_WITH_RTL*/
+
+
+#endif /*_CAN_QUEUE_H*/
diff --git a/app/cantest/can_drive/can_test.c b/app/cantest/can_drive/can_test.c
new file mode 100644 (file)
index 0000000..54d4fcf
--- /dev/null
@@ -0,0 +1,816 @@
+/* procesor H8S/2638 ver 1.1  */
+#include <stdio.h>
+#include <types.h>
+#include <cpu_def.h>
+#include <h8s2638h.h>
+#include <system_def.h>
+#include <string.h>
+#include "can_fn.h"
+#include <periph/sci_rs232.h>
+#include <utils.h>
+#include <boot_fn.h>
+#include <cmd_proc.h>
+
+#define DEBUG_LOW 1
+#define CAN_START_ON_RUN 0
+
+ #ifndef DEB_LED_OUT
+  #define DEB_LED_OUT
+  static void deb_led_out(char val)
+  {
+    if (val&1)
+      DEB_LED_ON(0);
+    else
+      DEB_LED_OFF(0);
+    if (val&2)
+      DEB_LED_ON(1);
+    else
+      DEB_LED_OFF(1);
+    if (val&4)
+      DEB_LED_ON(2);
+    else
+      DEB_LED_OFF(2);
+    if (val&8)
+      DEB_LED_ON(3);
+    else
+      DEB_LED_OFF(3);
+   }
+ #endif
+
+/* ---- global variables */
+zasobnik_zprav_t zpravy_zas_hcan0, zpravy_zas_hcan1;
+
+  /* default settings */
+#if 1
+can_settings_t can_settings_hcan0 =
+{
+  .mcr=0x00,
+  .bcr_sjw=0x02,
+  .bcr_brp=0x1,
+  .bcr_bsp=0x00,
+  .bcr_tseg1=0x0f,
+  .bcr_tseg2=0x05,
+  .mbcr=0x00,  /* not used */
+  .mbimr=0x00, /* not used */
+  .imr=0x00,   /* not used */
+  .lafml=0x0000,
+  .lafmh=0x6000
+};
+can_settings_t can_settings_hcan1 =
+{
+  .mcr=0x00,
+  .bcr_sjw=0x02,
+  .bcr_brp=0x01,
+  .bcr_bsp=0x00,
+  .bcr_tseg1=0x0f,
+  .bcr_tseg2=0x05,
+  .mbcr=0x00,  /* not used */
+  .mbimr=0x00, /* not used */
+  .imr=0x00,   /* not used */
+  .lafml=0x0003,
+  .lafmh=0x6000
+};
+
+can_calc_const_t can_calc_const_2638 = {
+  .sync=1,
+  .tseg1_min=4,
+  .tseg1_max=16,
+  .tseg2_min=2,
+  .tseg2_max=8,
+  .brp_min=2,
+  .brp_max=128,
+  .brp_inc=2,
+  .fix_div=2 /* not used */
+};
+
+
+#endif
+
+/* ---- function on end of file declaration */
+int cmd_rs232_test(void);
+int rs232_init_ok=0;
+int cmd_rs232_standa(void);
+
+// ports initialization
+void init()
+{
+    DEB_LED_INIT();
+}
+
+
+
+/* ---- main function --- */
+cmd_io_t cmd_io_rs232_line;
+cmd_des_t const *cmd_rs232_default[];
+
+int main()
+{
+  /* variables init */
+  zpravy_zas_hcan0.obs_max=ZASOBNIK_ZPRAV;
+  zpravy_zas_hcan1.obs_max=ZASOBNIK_ZPRAV;
+//  int i;
+
+  excptvec_initfill(test_unhandled_isr,1);
+  sti();
+  init();
+  /* set serial chanel */
+  if(sci_rs232_setmode(19200, 0, 0, sci_rs232_chan_default)>=0)  {
+    rs232_init_ok=1;
+    //FlWait(2*1000000);
+    deb_led_out(1);
+    printf("I am alive, you can ask for \"help\"\n ported version for EDK2638\n");
+  };
+   #if CAN_START_ON_RUN
+     printf("HCAN0 enabled:%d\n",Can_Enable(0));
+     printf("HCAN1 enabled:%d\n",Can_Enable(1));
+     can_set_registers(0,can_settings_hcan0);
+     can_set_registers(1,can_settings_hcan1);
+   #endif /* CAN_START_ON_RUN */
+   while(1){
+         cmd_processor_run(&cmd_io_rs232_line, cmd_rs232_default);
+  #if 0
+         #if 0
+         info=cmd_rs232_test();
+         printf("I am stil alive. - %d \n",info);
+         FlWait(3*100000);
+        cmd_rs232_standa();
+         #endif
+        // printf("HCAN1 enabled:%d\n",Can_Enable(1));
+        // FlWait(1*100000)
+         printf("jdu zapnout oba \n");
+         printf("HCAN0 enabled:%d\n",Can_Enable(0));
+         printf("HCAN1 enabled:%d\n",Can_Enable(1));
+         FlWait(1*100000);
+         can_set_registers(0);
+         can_set_registers(1);
+         can_test_function(1);
+         FlWait(3*100000);
+         printf("zpravy_zasob - obs_cnt:0x%x\n", zpravy_zasob.obs_cnt);
+         for(i=0;i<zpravy_zasob.obs_cnt;i++) {
+           printf("zprava %d\n", i);
+           zprava=zpravy_zasob.zpravy[i];
+           test_can_print_m(&zprava);
+         };
+         printf(" zprava globalni:\n");
+         test_can_print_m(&zprava_glob);
+         printf("adresa:0x%x, HCAN0_MC0:0x%x, hcanChS:0x%x, c_offset:0x%x\n", adresa, maleHCAN0_MC0, hcanChS, c_offset);
+  #if DEBUG_LOW
+    printf("*** HCAN1\n");
+    printf("reg. MC15:0-3:0x%02x:%02x:%02x:%02x\n", *(HCAN1_MC1+0), *(HCAN1_MC1+1), *(HCAN1_MC1+2), *(HCAN1_MC1+3));
+    printf("reg. MC15:4-7:0x%x:%x:%x:%x\n",         *(HCAN1_MC1+4), *(HCAN1_MC1+5), *(HCAN1_MC1+6), *(HCAN1_MC1+7));
+    printf("reg. MD15:0-3:0x%02x:%02x:%02x:%02x\n", *(HCAN1_MD1+0), *(HCAN1_MD1+1), *(HCAN1_MD1+2), *(HCAN1_MD1+3));
+    printf("reg. MD15:4-7:0x%x:%x:%x:%x\n",         *(HCAN1_MD1+4), *(HCAN1_MD1+5), *(HCAN1_MD1+6), *(HCAN1_MD1+7));
+    printf("\n");
+  #endif
+         break;
+#endif
+   }
+
+
+  /* blink LEDs */
+   while(1)
+   {
+      deb_led_out(0);
+      FlWait(1*100000);
+      printf("I am alive. \n ported version for EDK2638\n");
+      deb_led_out(3);
+      FlWait(1*100000);
+   };
+};
+
+/* ------------------------------------------------------------------------------------------------------------ */
+/* new command add -> add new function cmd_do_name, cmd_des_name update variable cmd_rs232_default */
+/* ---- prikaz: POKUS pridan pokus pro vyzkouseni command systemu */
+int cmd_do_pokus(cmd_io_t *cmd_io, const struct cmd_des *des, char *param[])
+{ 
+  printf("Test command POKUS \"help\"\n pokus uspesny\n");
+  return 0; 
+}
+
+cmd_des_t const cmd_des_pokus={0, CDESM_OPCHR,
+                       "POKUS","test command",
+                       cmd_do_pokus,{}};
+/* ---- prikaz CANINFO ----------------------------------------------------------------------- */
+int cmd_do_caninfo(cmd_io_t *cmd_io, const struct cmd_des *des, char *param[])
+{
+  long val;
+  int chanel;
+  int part;
+  char *p;
+
+  if(*param[2]!=':') return -CMDERR_OPCHAR;
+  p=param[3];
+  si_skspace(&p);
+  if(si_long(&p,&val,0)<0) return -CMDERR_BADPAR;
+  switch(val){
+    case 0: chanel=0; break;
+    case 1: chanel=1; break;
+    default: return -CMDERR_BADPAR;
+  }
+  //printf("chanel:%d, part:%d, val:%ld, p:%s\n", chanel, part, val, p);
+  si_skspace(&p);
+  if(si_long(&p,&val,0)<0) part=-1;
+  else
+    if((val>=0)&&(val<16))
+      part=val;
+    else return -CMDERR_BADPAR;
+  //printf("chanel:%d, part:%d, val:%ld, p:%s\n", chanel, part, val, p);
+  ReadRegistersCan(chanel, part);
+  return 0;
+}
+
+cmd_des_t const cmd_des_caninfo={0, CDESM_OPCHR,
+                       "CANINFO","[n] [b] n - chanel, b num of bank MC(MD), n only - registers HCANn",
+                       cmd_do_caninfo,{}};
+
+/* ---- prikaz CANREC ----------------------------------------------------------------------- */
+int cmd_do_canrec(cmd_io_t *cmd_io, const struct cmd_des *des, char *param[])
+{
+  long val;
+  int chanel;
+  int part;
+  char *p;
+  __u32 id_zp,cislo;
+  int ext,rtr;
+  int i;
+  zasobnik_zprav_t *zpravy_zas=NULL;
+  can_msg_buf zprava;
+  int can_mailbox_c_offset;
+
+  deb_led_out(0);
+  if(*param[2]!=':') return -CMDERR_OPCHAR;
+  p=param[3];
+  si_skspace(&p);
+  if(si_long(&p,&val,0)<0) return -CMDERR_BADPAR;
+  switch(val){
+    case 0: chanel=0; break;
+    case 1: chanel=1; break;
+    default: return -CMDERR_BADPAR;
+  }
+  //printf("chanel:%d, part:%d, val:%ld, p:%s\n", chanel, part, val, p);
+  si_skspace(&p); /* mailbox set recemption id */
+  if(si_long(&p,&val,0)<0) part=-1;
+  else
+    if((val>=0)&&(val<16))
+      part=val;
+    else return -CMDERR_BADPAR;
+  if(part>=0)
+  {
+    si_skspace(&p); /* id */
+    if(si_long(&p,&val,16)<0) return -CMDERR_BADPAR;
+      id_zp=val;
+    //printf("chanel:%d, part:%d, val:%ld, p:%s\n", chanel, part, val, p);
+    si_skspace(&p); /* ext */
+    if(si_long(&p,&val,16)<0) ext=0;
+      ext=val;
+    si_skspace(&p); /* rtr */
+    if(si_long(&p,&val,16)<0) rtr=0;
+      rtr=val;
+
+    can_mailbox_c_offset=part*HCAN_MC_LENGTH;
+    cislo=CAN_ID_FLG2HWID(id_zp,ext,rtr);
+    for(i=0;i<4;i++) {
+      *(HCAN0_MC0+chanel*HCAN_MC_o+can_mailbox_c_offset+4+(3-i))=cislo&0xff; //zprava_k_prijeti;
+       cislo=(cislo>>8);
+    };
+  }
+  else {
+    if(chanel==0)
+      zpravy_zas=&zpravy_zas_hcan0;
+    if(chanel==1)
+      zpravy_zas=&zpravy_zas_hcan1;
+    if(zpravy_zas==NULL) return -CANERR_BADCHANEL;
+    //printf("id:0x%04x, hard_id_h:0x%04x, hard_id_l:0x%04x, rozsir_id_l:0x%04x, rozsir_id_l:0x%04x\n",
+    //       klasika_id&0xffff, (hard_id>>16)&0xffff, hard_id&0xffff, (rozsir_id>>16)&0xffff, rozsir_id&0xffff);
+    //printf("0x:%x:%x:%x:%x\n",hw_0,hw_1,hw_2,hw_3);
+    if(!(zpravy_zas->obs_cnt))
+      printf("No messages on chanel %d\n", chanel);
+    for(i=0;i<zpravy_zas->obs_cnt;i++) {
+      printf("zprava %d\n", i);
+      zprava=zpravy_zas->zpravy[i];
+      test_can_print_m(&zprava);
+    };
+  };
+  //ReadRegistersCan(chanel, part);
+  return 0;
+}
+
+cmd_des_t const cmd_des_canrec={0, CDESM_OPCHR,
+                       "CANREC","[n] [b] [id] [ext] [rtr], n only - print received HCANn \n",
+                       cmd_do_canrec,{}};
+
+
+/* ---- prikaz CANSEND ----------------------------------------------------------------------- */
+int cmd_do_cansend(cmd_io_t *cmd_io, const struct cmd_des *des, char *param[])
+{
+  long val;
+  int chanel;
+  int part=0;
+  char *p;
+  int i;
+  can_msg_buf zprava;
+  __u32 id_zp;
+  __u16 data_16[4];
+  int ext,rtr;
+
+  if(*param[2]!=':') return -CMDERR_OPCHAR;
+  p=param[3];
+  si_skspace(&p); /* chanel */
+  if(si_long(&p,&val,0)<0) return -CMDERR_BADPAR;
+  switch(val){
+    case 0: chanel=0; break;
+    case 1: chanel=1; break;
+    default: return -CMDERR_BADPAR;
+  }
+  //printf("chanel:%d, part:%d, val:%ld, p:%s\n", chanel, part, val, p);
+  si_skspace(&p); /* bank */
+  if(si_long(&p,&val,0)<0) return -CMDERR_BADPAR;
+  else {
+    if((val>=0)&&(val<16))
+      part=val;
+    else return -CMDERR_BADPAR;
+  };
+  //printf("chanel:%d, part:%d, val:%ld, p:%s\n", chanel, part, val, p);
+  si_skspace(&p); /* id */
+  if(si_long(&p,&val,16)<0) return -CMDERR_BADPAR;
+    id_zp=val;
+  //printf("chanel:%d, part:%d, val:%ld, p:%s\n", chanel, part, val, p);
+  si_skspace(&p); /* ext */
+  if(si_long(&p,&val,16)<0) ext=0;
+    ext=val;
+  si_skspace(&p); /* rtr */
+  if(si_long(&p,&val,16)<0) rtr=0;
+    rtr=val;
+  si_skspace(&p); /* data 0 */
+  if(si_long(&p,&val,16)<0) data_16[0]=0;
+    data_16[0]=val;
+  si_skspace(&p); /* data 1 */
+  if(si_long(&p,&val,16)<0) data_16[1]=0;
+    data_16[1]=val;
+  si_skspace(&p); /* data 2 */
+  if(si_long(&p,&val,16)<0) data_16[2]=0;
+    data_16[2]=val;
+  si_skspace(&p); /* data 3 */
+  if(si_long(&p,&val,16)<0) data_16[3]=0;
+    data_16[3]=val;
+  if(!ext)
+    zprava.id.std.id=id_zp;
+  else
+    zprava.id.ext.id=id_zp;
+  zprava.id.hwid=CAN_ID_FLG2HWID(id_zp,ext,rtr);
+
+  for(i=0;i<4;i++) {
+    zprava.data[2*i]=(data_16[i]&0xff00)>>8;
+    zprava.data[2*i+1]=data_16[i]&0xff;
+  };
+  #if 0
+  printf("ch:%d, bank:%d, id:0x%x, ext:%d, rtr:%d, datah:0x%x, datal:0x%x\n",
+          chanel, part, id_zp, ext, rtr, datah, datal);
+  printf("id:0x%x, eid:0x%x, datah:0x%x, datal:0x%x\n",
+           zprava.id.std.id, zprava.id.ext.id, zprava.data[0], zprava.data[7]);
+  printf("zprava:0x%x, &zprava:0x%x \n", zprava, &zprava);
+  #endif
+  can_send_msg(chanel, part, zprava);
+  return 0;
+}
+
+cmd_des_t const cmd_des_cansend={0, CDESM_OPCHR,
+                       "CANSEND","[n] [b] [id] [ext] [rtr] [d0] - [d3] \n\t n - chanel, b bank ,Use bank for send!",
+                       cmd_do_cansend,{}};
+
+/* ---- prikaz CANLAFM ----------------------------------------------------------------------- */
+int cmd_do_lafm(cmd_io_t *cmd_io, const struct cmd_des *des, char *param[])
+{
+  long val;
+  int chanel;
+  char *p;
+  __u32 lafm;
+  __u16 lafml, lafmh;
+  int ext;
+
+  deb_led_out(0);
+  if(*param[2]!=':') return -CMDERR_OPCHAR;
+  p=param[3];
+  si_skspace(&p);
+  if(si_long(&p,&val,0)<0) return -CMDERR_BADPAR;
+  switch(val){
+    case 0: chanel=0; break;
+    case 1: chanel=1; break;
+    default: return -CMDERR_BADPAR;
+  }
+  //printf("chanel:%d, val:%ld, p:%s\n", chanel, val, p);
+  si_skspace(&p); /* mailbox set ext flag */
+  if(si_long(&p,&val,0)<0) return -CMDERR_BADPAR;
+  else
+    if((val>=0)&&(val<2))
+      ext=val;
+    else return -CMDERR_BADPAR;
+  si_skspace(&p); /* read lafmh  */
+  if(si_long(&p,&val,0)<0) return -CMDERR_BADPAR;
+    lafmh=val;
+  //printf("chanel:%d, val:%ld, p:%s\n", chanel, val, p);
+  si_skspace(&p); /* read lafml  */
+  if(si_long(&p,&val,0)<0) return -CMDERR_BADPAR;
+    lafml=val;
+  //printf("chanel:%d, val:%ld, p:%s\n", chanel, val, p);
+  if(ext==0)
+  { /* no ext */
+    lafm=(lafmh<<16)|lafml;
+    lafm=CAN_IDM2LAFM(lafm);
+    printf("ext:%ld lafm:0x%04x%04x ", ext, (int) ((0xffff0000&(lafm))>>16), (int) (0xffff&(lafm)));
+    //*(HCAN0_LAFML+chanel*HCAN_LAFML_o)|=(__u16) 0xffff&(lafm&LAFM_IDm);
+    *(HCAN0_LAFMH+chanel*HCAN_LAFMH_o)|=(int) ((0xffff0000&(lafm&LAFM_IDm))>>16);
+  };
+  if(ext==1)
+  { /* ext */
+    lafm=(lafmh<<16)|lafml;
+    lafm=CAN_IDEM2LAFM(lafm);
+    printf("ext:%ld lafm:0x%04x%04x ", ext, (int) ((0xffff0000&(lafm))>>16), (int) (0xffff&(lafm)));
+    *(HCAN0_LAFML+chanel*HCAN_LAFML_o)|=(__u16) (0xffff&(lafm&LAFM_IDEm));
+    *(HCAN0_LAFMH+chanel*HCAN_LAFMH_o)|=(__u16) ((0xffff0000&(lafm&LAFM_IDEm))>>16);
+  };
+  printf(" lafml:0x%04x, lafmh:0x%04x\n", lafml, lafmh);
+  //ReadRegistersCan(chanel, part);
+  return 0;
+}
+
+cmd_des_t const cmd_des_lafm={0, CDESM_OPCHR,
+                       "CANLAFM","[n] [ext] [FMh] [FMd], [n] - chanel, [ext] , [FMh/l] - filter h/l \n",
+                       cmd_do_lafm,{}};
+
+/* ---- prikaz CANNEWSET ----------------------------------------------------------------------- */
+int cmd_do_cannewset(cmd_io_t *cmd_io, const struct cmd_des *des, char *param[])
+{
+  long val;
+  int can_chanel;
+  char *p;
+  can_settings_t new_set;
+
+  deb_led_out(0);
+  if(*param[2]!=':') return -CMDERR_OPCHAR;
+  p=param[3];
+  si_skspace(&p);
+  if(si_long(&p,&val,0)<0) return -CMDERR_BADPAR;
+  switch(val){
+    case 0: 
+      can_chanel=0; break;
+    case 1: 
+      can_chanel=1; break;
+    default: return -CMDERR_BADPAR;
+  }
+  //printf("chanel:%d, val:%ld, p:%s\n", chanel, val, p);
+  si_skspace(&p); /* brp */
+  if(si_long(&p,&val,0)<0) return -CMDERR_BADPAR;
+      new_set.bcr_brp=val;
+  si_skspace(&p); /* tseg1  */
+  if(si_long(&p,&val,0)<0) return -CMDERR_BADPAR;
+    new_set.bcr_tseg1=val;
+  //printf("chanel:%d, val:%ld, p:%s\n", chanel, val, p);
+  si_skspace(&p); /* tseg2 */
+  if(si_long(&p,&val,0)<0) return -CMDERR_BADPAR;
+    new_set.bcr_tseg2=val;
+  //printf("chanel:%d, val:%ld, p:%s\n", chanel, val, p);
+  si_skspace(&p); /* sjw */
+  if(si_long(&p,&val,0)<0) return -CMDERR_BADPAR;
+    new_set.bcr_sjw=val;
+  //printf("chanel:%d, val:%ld, p:%s\n", chanel, val, p);
+  switch(can_chanel){
+    case 0: can_chanel=0;
+      can_change_registers(0,&new_set,&can_settings_hcan0);
+      break;
+    case 1: can_chanel=1;
+      can_change_registers(1,&new_set,&can_settings_hcan1);
+      break;
+    default: return -CMDERR_BADPAR;
+  }
+  return 0;
+}
+
+cmd_des_t const cmd_des_cannewset={0, CDESM_OPCHR,
+                       "CANNEWSET","[n] [brp] [tseg1] [tseg2] [sjw], [n] - chanel \n",
+                       cmd_do_cannewset,{}};
+
+/* ---- prikaz: CANSTART ----------------------------------------------------------------------- */
+int cmd_do_canstart(cmd_io_t *cmd_io, const struct cmd_des *des, char *param[])
+{ 
+  long val;
+  int can_chanel;
+  char *p;
+
+  if(*param[2]!=':') return -CMDERR_OPCHAR;
+  p=param[3];
+  si_skspace(&p);
+  if(si_long(&p,&val,0)<0) return -CMDERR_BADPAR;
+  //printf("Zadane parametry %s\n", param[3]);
+  switch(val){
+    case 0: can_chanel=0; 
+      printf("HCAN0 enabled:%d\n",Can_Enable(0));
+      can_set_registers(0,&can_settings_hcan0);
+      break;
+    case 1: can_chanel=1;
+      printf("HCAN1 enabled:%d\n",Can_Enable(1));
+      can_set_registers(1,&can_settings_hcan1);
+      break;
+    default: return -CMDERR_BADPAR;
+  }
+  printf("\tchanel:%d \n", can_chanel);
+  return 0;
+}
+
+cmd_des_t const cmd_des_canstart={0, CDESM_OPCHR,
+                       "CANSTART","CANSTART [n] - chanel, enable and set selected chanel",
+                       cmd_do_canstart,{}};
+
+/* ---- prikaz: CANSTOP ----------------------------------------------------------------------- */
+int cmd_do_canstop(cmd_io_t *cmd_io, const struct cmd_des *des, char *param[])
+{ 
+  long val;
+  int can_chanel;
+  char *p;
+
+  if(*param[2]!=':') return -CMDERR_OPCHAR;
+  p=param[3];
+  si_skspace(&p);
+  if(si_long(&p,&val,0)<0) return -CMDERR_BADPAR;
+  printf("Zadane parametry %s\n", param[3]);
+  switch(val){
+    case 0: can_chanel=0; 
+      *SYS_MSTPCRC|=MSTPCRC_MSTPC3m;
+      break;
+    case 1: can_chanel=1;
+      *SYS_MSTPCRC|=MSTPCRC_MSTPC2m;
+      break;
+    default: return -CMDERR_BADPAR;
+  }
+  printf("\tHCAN chanel stoped:%d \n", can_chanel);
+  return 0;
+}
+
+cmd_des_t const cmd_des_canstop={0, CDESM_OPCHR,
+                       "CANSTOP","CANSTOP [n] - chanel, stop selected HCAN chanel",
+                       cmd_do_canstop,{}};
+
+/* ---- prikaz: CANSETREG ----------------------------------------------------------------------- */
+int cmd_do_cansetreg(cmd_io_t *cmd_io, const struct cmd_des *des, char *param[])
+{ 
+  long val;
+  int can_chanel;
+  char *p;
+
+  if(*param[2]!=':') return -CMDERR_OPCHAR;
+  p=param[3];
+  si_skspace(&p);
+  if(si_long(&p,&val,0)<0) return -CMDERR_BADPAR;
+  printf("Zadane parametry %s\n", param[3]);
+  switch(val){
+    case 0: 
+      can_chanel=0;
+      can_set_registers(0,&can_settings_hcan0);
+      break;
+    case 1: 
+      can_chanel=1;
+      can_set_registers(0,&can_settings_hcan1);
+      break;
+    default: return -CMDERR_BADPAR;
+  }
+  printf("\tHCAN chanel set:%d \n", can_chanel);
+  return 0;
+}
+
+cmd_des_t const cmd_des_cansetreg={0, CDESM_OPCHR,
+                       "CANSETREG","CANSETREG [n] - chanel, set registers of selected HCAN chanel",
+                       cmd_do_cansetreg,{}};
+
+/* ---- prikaz: CANBAUD ----------------------------------------------------------------------- */
+int cmd_do_canbaud(cmd_io_t *cmd_io, const struct cmd_des *des, char *param[])
+{ 
+  long val;
+  int can_chanel;
+  long baud_rate, best_rate;
+  char *p;
+  int brp,tseg1,tseg2,best_tseg;
+  can_settings_t *pcan_settings_hcan, new_set;
+
+  if(*param[2]!=':') return -CMDERR_OPCHAR;
+  p=param[3];
+  si_skspace(&p);
+  if(si_long(&p,&val,0)<0) return -CMDERR_BADPAR;
+  //printf("Zadane parametry %s\n", param[3]);
+  switch(val){
+    case 0: 
+      can_chanel=0;
+      pcan_settings_hcan=&can_settings_hcan0;
+      break;
+    case 1: 
+      can_chanel=1;
+      pcan_settings_hcan=&can_settings_hcan1;
+      break;
+    default: return -CMDERR_BADPAR;
+  }
+  si_skspace(&p);
+  if(si_long(&p,&val,0)<0) return -CMDERR_BADPAR;
+    baud_rate=val;
+  if(can_auto_baud(baud_rate, &brp, &tseg1, &tseg2, 75, &can_calc_const_2638)) {
+    printf("Settings for baud rate %ld bps is not possible.", baud_rate);
+    return(0);
+  }
+  else {
+    new_set=*pcan_settings_hcan;
+    new_set.bcr_brp=brp;
+    new_set.bcr_tseg1=tseg1;
+    new_set.bcr_tseg2=tseg2;
+    if(can_change_registers(can_chanel,&new_set,pcan_settings_hcan)) {
+      printf("Error in CANBAUD\n");
+      return 0;
+    };
+    best_tseg=tseg1+tseg2+2;
+    best_rate=CPU_REF_HZ/(2*((brp+1)*(3+tseg1+tseg2)));
+    printf("New settings for baud rate %ld bps\n", best_rate);
+    printf("\tbrp=%d, best_tseg=%d, tseg1=%d, tseg2=%d, sampl_pt=%d\n",
+               brp, best_tseg, tseg1, tseg2, (100*(best_tseg-tseg2)/(best_tseg+1)));
+  };
+  return 0;
+}
+
+cmd_des_t const cmd_des_canbaud={0, CDESM_OPCHR,
+                       "CANBAUD","CANBAUD [n] - chanel, [baud] - speed b/s",
+                       cmd_do_canbaud,{}};
+
+/* ---- prikaz: CANSLEEP ----------------------------------------------------------------------- */
+int cmd_do_cansleep(cmd_io_t *cmd_io, const struct cmd_des *des, char *param[])
+{ 
+  long val;
+  int can_chanel;
+  int wake_up_mode;
+  char *p;
+
+  if(*param[2]!=':') return -CMDERR_OPCHAR;
+  p=param[3];
+  si_skspace(&p);
+  if(si_long(&p,&val,0)<0) return -CMDERR_BADPAR;
+  //printf("Zadane parametry %s\n", param[3]);
+  switch(val){
+    case 0: 
+      can_chanel=0;
+      break;
+    case 1: 
+      can_chanel=1;
+      break;
+    default: return -CMDERR_BADPAR;
+  }
+  si_skspace(&p);
+  if(si_long(&p,&val,0)<0) return -CMDERR_BADPAR;
+    wake_up_mode=val;
+  if(can_sleep(can_chanel,wake_up_mode))
+     printf("Error in CAN sleep, chanel:%d \n", can_chanel);
+  printf("\tHCAN chanel:%d in sleep mode.\n", can_chanel);
+  return 0;
+}
+
+cmd_des_t const cmd_des_cansleep={0, CDESM_OPCHR,
+                       "CANSLEEP","CANSLEEP [n] - chanel, [a] - CAN wake by activity - 1",
+                       cmd_do_cansleep,{}};
+
+/* ---- prikaz: CANWAKE ----------------------------------------------------------------------- */
+int cmd_do_canwake(cmd_io_t *cmd_io, const struct cmd_des *des, char *param[])
+{ 
+  long val;
+  int can_chanel;
+  char *p;
+
+  if(*param[2]!=':') return -CMDERR_OPCHAR;
+  p=param[3];
+  si_skspace(&p);
+  if(si_long(&p,&val,0)<0) return -CMDERR_BADPAR;
+  //printf("Zadane parametry %s\n", param[3]);
+  switch(val){
+    case 0: 
+      can_chanel=0;
+      break;
+    case 1: 
+      can_chanel=1;
+      break;
+    default: return -CMDERR_BADPAR;
+  }
+  if(can_wake(can_chanel))
+     printf("Error in CAN wake up, chanel:%d \n", can_chanel);
+  printf("\tHCAN chanel:%d in wake up mode.\n", can_chanel);
+  return 0;
+}
+
+cmd_des_t const cmd_des_canwake={0, CDESM_OPCHR,
+                       "CANWAKE","CANWAKE [n] - chanel",
+                       cmd_do_canwake,{}};
+
+/* ---- prikaz: CANCLSTACK ----------------------------------------------------------------------- */
+int cmd_do_canclstack(cmd_io_t *cmd_io, const struct cmd_des *des, char *param[])
+{ 
+  long val;
+  int can_chanel,count_mes;
+  int cleared_mes;
+  char *p;
+  zasobnik_zprav_t *pstack;
+
+  if(*param[2]!=':') return -CMDERR_OPCHAR;
+  p=param[3];
+  si_skspace(&p);
+  if(si_long(&p,&val,0)<0) return -CMDERR_BADPAR;
+  //printf("Zadane parametry %s\n", param[3]);
+  switch(val){
+    case 0: 
+      can_chanel=0;
+      pstack=&zpravy_zas_hcan0;
+      break;
+    case 1: 
+      can_chanel=1;
+      pstack=&zpravy_zas_hcan1;
+      break;
+    default: return -CMDERR_BADPAR;
+  }
+  si_skspace(&p);
+  if(si_long(&p,&val,0)<0) count_mes=-1;
+    count_mes=val;
+  cleared_mes=ClearMessages(pstack,count_mes);
+  printf("\tHCAN chanel:%d cleared messages:%d(%d)\n", can_chanel, cleared_mes, count_mes);
+  return 0;
+}
+
+cmd_des_t const cmd_des_canclstack={0, CDESM_OPCHR,
+                       "CANCLSTACK","CANCLSTACK [n] - chanel, [c] - count messages to delete, missing clear all",
+                       cmd_do_canclstack,{}};
+
+/* ---- prikaz: CANSETUP ----------------------------------------------------------------------- */
+int cmd_do_cansetup(cmd_io_t *cmd_io, const struct cmd_des *des, char *param[])
+{
+  return 0;
+}
+
+cmd_des_t const cmd_des_cansetup={0, CDESM_OPCHR,
+                       "CANSETUP","cansetup",
+                       cmd_do_cansetup,{}};
+/* ---- prikaz: CAN ----------------------------------------------------------------------- */
+int cmd_do_can(cmd_io_t *cmd_io, const struct cmd_des *des, char *param[])
+{ 
+  long val;
+  int stc;
+  char *p;
+
+  if(*param[2]!=':') return -CMDERR_OPCHAR;
+  p=param[3];
+  si_skspace(&p);
+  if(si_long(&p,&val,0)<0) return -CMDERR_BADPAR;
+  printf("Zadane parametry %s\n", param[3]);
+  switch(val){
+    case 1: stc=0; break;
+    case 2: stc=1; break;
+    case 4: stc=2; break;
+    default: return -CMDERR_BADPAR;
+  }
+  printf("\tstc:%d \n", stc);
+  return 0;
+}
+
+cmd_des_t const cmd_des_can={0, CDESM_OPCHR,
+                       "CAN","CAN - in testing",
+                       cmd_do_can,{}};
+
+/* ---- prikaz help, vytiskne detaily vsech prikazu z cmd_des_ */
+cmd_des_t const **cmd_rs232;
+cmd_des_t const cmd_des_help={0, 0,"help","prints help for commands",
+                       cmd_do_help,{(char*)&cmd_rs232}};
+
+/* ---- Seznam prikazu. */
+extern cmd_des_t *cmd_iic_test[1];
+
+cmd_des_t const *cmd_rs232_default[]={
+  &cmd_des_help,
+  &cmd_des_pokus,      /* pridano na zkousku */
+  &cmd_des_can,                /* nastavovani can komunikace */
+  &cmd_des_caninfo,    /* read register HCAN registers */
+  &cmd_des_cansetup,   /* setup can registers */
+  &cmd_des_cansend,    /* send CAN message */
+  &cmd_des_canrec,     /* print or set CAN for recieve messages */
+  &cmd_des_lafm,       /* set LAFM registers */
+  &cmd_des_canstart,   /* enable HCAN 1,2 and set HCANs registers */
+  &cmd_des_canstop,    /* module stop */
+  &cmd_des_canclstack, /* clear stack of received messages */
+  &cmd_des_cansetreg,  /* sets HCAN registers */
+  &cmd_des_cannewset,  /* store new settings in structure */
+  &cmd_des_cansleep,   /* CAN sleep mode */
+  &cmd_des_canwake,    /* CAN wake from sleep mode */
+  &cmd_des_canbaud,    /* CAN auto baud rate */
+  NULL
+};
+
+cmd_des_t const **cmd_rs232=cmd_rs232_default;
+
+
+    #if 0 /* trasovac */
+    __u32 temp32;
+    for(i=0,temp32=0;i<4;i++) { /* co to dela? */
+      temp32|=(*(HCAN0_MC0+4+i));//zprava->id.hwid;
+      printf("| temp_h:0x%04x, temp_l:0x%04x\n", (temp32>>16), temp32&0xffff);
+      temp32<<=8;
+      printf(" >> temp_h:0x%04x, temp_l:0x%04x\n", (temp32>>16), temp32&0xffff);
+    };
+    #endif
diff --git a/app/cantest/can_drive/canmsg.h b/app/cantest/can_drive/canmsg.h
new file mode 100644 (file)
index 0000000..779f68c
--- /dev/null
@@ -0,0 +1,136 @@
+/* canmsg.h - common kernel-space and user-space CAN message structure
+ * Linux CAN-bus device driver.
+ * Written by Pavel Pisa - OCERA team member
+ * email:pisa@cmp.felk.cvut.cz
+ * This software is released under the GPL-License.
+ * Version lincan-0.3  17 Jun 2004
+ */
+
+#ifndef _CANMSG_T_H
+#define _CANMSG_T_H
+
+#ifdef __KERNEL__
+
+#include <linux/time.h>
+#include <linux/types.h>
+
+#else /* __KERNEL__ */
+
+#include <sys/time.h>
+#include <sys/types.h>
+
+#endif /* __KERNEL__ */
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* 
+ * CAN_MSG_VERSION_2 enables new canmsg_t layout compatible with
+ * can4linux project from http://www.port.de/
+ * 
+ */
+#define CAN_MSG_VERSION_2
+
+/* Number of data bytes in one CAN message */
+#define CAN_MSG_LENGTH 8
+
+#ifdef CAN_MSG_VERSION_2
+
+typedef struct timeval canmsg_tstamp_t ;
+
+typedef unsigned long canmsg_id_t;
+
+/**
+ * struct canmsg_t - structure representing CAN message
+ * @flags:  message flags
+ *      %MSG_RTR .. message is Remote Transmission Request,
+ *     %MSG_EXT .. message with extended ID, 
+ *      %MSG_OVR .. indication of queue overflow condition,
+ *     %MSG_LOCAL .. message originates from this node.
+ * @cob:    communication object number (not used)
+ * @id:     ID of CAN message
+ * @timestamp: not used
+ * @length: length of used data
+ * @data:   data bytes buffer
+ *
+ * Header: canmsg.h
+ */
+struct canmsg_t {
+       int             flags;
+       int             cob;
+       canmsg_id_t     id;
+       canmsg_tstamp_t timestamp;
+       unsigned short  length;
+       unsigned char   data[CAN_MSG_LENGTH];
+};
+
+#else /*CAN_MSG_VERSION_2*/
+#ifndef PACKED
+#define PACKED __attribute__((packed))
+#endif
+/* Old, deprecated version of canmsg_t structure */
+struct canmsg_t {
+       short           flags;
+       int             cob;
+       canmsg_id_t     id;
+       unsigned long   timestamp;
+       unsigned int    length;
+       unsigned char   data[CAN_MSG_LENGTH];
+} PACKED;
+#endif /*CAN_MSG_VERSION_2*/
+
+typedef struct canmsg_t canmsg_t;
+
+/**
+ * struct canfilt_t - structure for acceptance filter setup
+ * @flags:  message flags
+ *      %MSG_RTR .. message is Remote Transmission Request,
+ *     %MSG_EXT .. message with extended ID, 
+ *      %MSG_OVR .. indication of queue overflow condition,
+ *     %MSG_LOCAL .. message originates from this node.
+ *     there are corresponding mask bits
+ *     %MSG_RTR_MASK, %MSG_EXT_MASK, %MSG_LOCAL_MASK.
+ *     %MSG_PROCESSLOCAL enables local messages processing in the
+ *     combination with global setting
+ * @queid:  CAN queue identification in the case of the multiple
+ *         queues per one user (open instance)
+ * @cob:    communication object number (not used)
+ * @id:     selected required value of cared ID id bits
+ * @mask:   select bits significand for the comparation;
+ *          1 .. take care about corresponding ID bit, 0 .. don't care
+ *
+ * Header: canmsg.h
+ */
+struct canfilt_t {
+       int             flags;
+       int             queid;
+       int             cob;
+       canmsg_id_t     id;
+       canmsg_id_t     mask;
+};
+
+typedef struct canfilt_t canfilt_t;
+
+/* Definitions to use for canmsg_t and canfilt_t flags */
+#define MSG_RTR   (1<<0)
+#define MSG_OVR   (1<<1)
+#define MSG_EXT   (1<<2)
+#define MSG_LOCAL (1<<3)
+/* If you change above lines, check canque_filtid2internal function */
+
+/* Additional definitions used for canfilt_t only */
+#define MSG_FILT_MASK_SHIFT   8
+#define MSG_RTR_MASK   (MSG_RTR<<MSG_FILT_MASK_SHIFT)
+#define MSG_EXT_MASK   (MSG_EXT<<MSG_FILT_MASK_SHIFT)
+#define MSG_LOCAL_MASK (MSG_LOCAL<<MSG_FILT_MASK_SHIFT)
+#define MSG_PROCESSLOCAL (MSG_OVR<<MSG_FILT_MASK_SHIFT)
+
+/* Can message ID mask */
+#define MSG_ID_MASK ((1l<<29)-1)
+
+#ifdef __cplusplus
+} /* extern "C"*/
+#endif
+
+#endif /*_CANMSG_T_H*/
diff --git a/app/cantest/can_drive/constants.h b/app/cantest/can_drive/constants.h
new file mode 100644 (file)
index 0000000..b777cad
--- /dev/null
@@ -0,0 +1,113 @@
+/* constants.h
+ * Header file for the Linux CAN-bus driver.
+ * Written by Arnaud Westenberg email:arnaud@wanadoo.nl
+ * Rewritten for new CAN queues by Pavel Pisa - OCERA team member
+ * email:pisa@cmp.felk.cvut.cz
+ * This software is released under the GPL-License.
+ * Version lincan-0.3  17 Jun 2004
+ */
+
+#ifndef __CONSTANTS_H__
+#define __CONSTANTS_H__
+
+/* Device name as it will appear in /proc/devices */
+#define DEVICE_NAME "can"
+
+/* Branch of the driver */
+#define CAN_DRV_BRANCH (('L'<<24)|('I'<<16)|('N'<<8)|'C')
+
+/* Version of the driver */
+#define CAN_DRV_VER_MAJOR 0
+#define CAN_DRV_VER_MINOR 3
+#define CAN_DRV_VER_PATCH 1
+#define CAN_DRV_VER ((CAN_DRV_VER_MAJOR<<16) | (CAN_DRV_VER_MINOR<<8) | CAN_DRV_VER_PATCH)
+
+/* Default driver major number, see /usr/src/linux/Documentation/devices.txt */
+#define CAN_MAJOR 91
+
+/* Definition of the maximum number of concurrent supported hardware boards,
+ * chips per board, total number of chips, interrupts and message objects.
+ * Obviously there are no 32 different interrupts, but each chip can have its
+ * own interrupt so we have to check for it MAX_IRQ == MAX_TOT_CHIPS times.
+ */
+#define MAX_HW_CARDS 8
+#define MAX_HW_CHIPS 4
+#define MAX_TOT_CHIPS (MAX_HW_CHIPS*MAX_HW_CARDS)
+#define MAX_TOT_CHIPS_STR 32   /* must be explicit for MODULE_PARM */
+#define MAX_IRQ 32
+#define MAX_MSGOBJS 32
+#define MAX_TOT_MSGOBJS (MAX_TOT_CHIPS*MAX_MSGOBJS)
+#define MAX_BUF_LENGTH 64
+//#define MAX_BUF_LENGTH 4
+
+
+/* These flags can be used for the msgobj_t structure flags data entry */
+#define MSGOBJ_OPENED_b                   0
+#define MSGOBJ_TX_REQUEST_b       1
+#define MSGOBJ_TX_LOCK_b           2
+#define MSGOBJ_IRQ_REQUEST_b       3
+#define MSGOBJ_WORKER_WAKE_b       4
+#define MSGOBJ_FILTCH_REQUEST_b    5
+#define MSGOBJ_RX_MODE_b           6
+#define MSGOBJ_RX_MODE_EXT_b       7
+#define MSGOBJ_TX_PENDING_b        8
+
+#define MSGOBJ_OPENED              (1<<MSGOBJ_OPENED_b)
+#define MSGOBJ_TX_REQUEST          (1<<MSGOBJ_TX_REQUEST_b)
+#define MSGOBJ_TX_LOCK             (1<<MSGOBJ_TX_LOCK_b)
+#define MSGOBJ_IRQ_REQUEST         (1<<MSGOBJ_IRQ_REQUEST_b)
+#define MSGOBJ_WORKER_WAKE         (1<<MSGOBJ_WORKER_WAKE_b)
+#define MSGOBJ_FILTCH_REQUEST      (1<<MSGOBJ_FILTCH_REQUEST_b)
+#define MSGOBJ_RX_MODE             (1<<MSGOBJ_RX_MODE_b)
+#define MSGOBJ_RX_MODE_EXT         (1<<MSGOBJ_RX_MODE_EXT_b)
+#define MSGOBJ_TX_PENDING          (1<<MSGOBJ_TX_PENDING_b)
+
+#define can_msgobj_test_fl(obj,obj_fl) \
+  test_bit(MSGOBJ_##obj_fl##_b,&(obj)->obj_flags)
+#define can_msgobj_set_fl(obj,obj_fl) \
+  set_bit(MSGOBJ_##obj_fl##_b,&(obj)->obj_flags)
+#define can_msgobj_clear_fl(obj,obj_fl) \
+  clear_bit(MSGOBJ_##obj_fl##_b,&(obj)->obj_flags)
+#define can_msgobj_test_and_set_fl(obj,obj_fl) \
+  test_and_set_bit(MSGOBJ_##obj_fl##_b,&(obj)->obj_flags)
+#define can_msgobj_test_and_clear_fl(obj,obj_fl) \
+  test_and_clear_bit(MSGOBJ_##obj_fl##_b,&(obj)->obj_flags)
+
+
+/* These flags can be used for the canchip_t structure flags data entry */
+#define CHIP_ATTACHED    (1<<0)  /* chip is attached to HW, release_chip() has to be called */
+#define CHIP_CONFIGURED  (1<<1)  /* chip is configured and prepared for communication */
+#define CHIP_SEGMENTED   (1<<2)  /* segmented access, ex: i82527 with 16 byte window*/
+#define CHIP_IRQ_SETUP   (1<<3)  /* IRQ handler has been set */
+#define CHIP_IRQ_PCI     (1<<4)  /* chip is on PCI board and uses PCI interrupt  */
+#define CHIP_IRQ_VME     (1<<5)  /* interrupt is VME bus and requires VME bridge */
+#define CHIP_IRQ_CUSTOM  (1<<6)  /* custom interrupt provided by board or chip code */
+#define CHIP_IRQ_FAST    (1<<7)  /* interrupt handler only schedules postponed processing */
+
+#define CHIP_MAX_IRQLOOP 1000
+
+/* System independent defines of IRQ handled state */
+#define CANCHIP_IRQ_NONE     0
+#define CANCHIP_IRQ_HANDLED  1
+#define CANCHIP_IRQ_ACCEPTED 2
+#define CANCHIP_IRQ_STUCK    3
+
+/* These flags can be used for the candevices_t structure flags data entry */
+#define CANDEV_PROGRAMMABLE_IRQ (1<<0)
+#define CANDEV_IO_RESERVED     (1<<1)
+
+/* Next flags are specific for struct canuser_t applications connection */
+#define CANUSER_RTL_CLIENT      (1<<0)
+#define CANUSER_RTL_MEM         (1<<1)
+#define CANUSER_DIRECT          (1<<2)
+
+
+enum timing_BTR1 {
+       MAX_TSEG1 = 15,
+       MAX_TSEG2 = 7
+};
+
+/* Flags for baud_rate function */
+#define BTR1_SAM (1<<1)
+
+#endif
diff --git a/app/cantest/can_drive/rs_test.c b/app/cantest/can_drive/rs_test.c
new file mode 100644 (file)
index 0000000..16d6dd2
--- /dev/null
@@ -0,0 +1,70 @@
+/* procesor H8S/2638 ver 1.1  */
+#include <stdio.h>
+#include <types.h>
+#include <cpu_def.h>
+#include <h8s2638h.h>
+#include <system_def.h>
+#include <string.h>
+#include <boot_fn.h>
+#include <periph/sci_rs232.h>
+
+//Interrupt routine
+void  LightOn(void) __attribute__ ((interrupt_handler));
+void LightOn(void)
+{
+    while (1) {
+        DEB_LED_ON(0);
+        DEB_LED_ON(1);
+        DEB_LED_ON(2);
+        FlWait(1*20000);
+        DEB_LED_OFF(1);
+        FlWait(1*200000);
+    }
+}
+
+/* If you want to spare memory and only have support for SCI channels
+ * 0 and 1 uncomment the following block. */
+#if 1
+sci_info_t *sci_rs232_chan_array[] = {
+    &sci_rs232_chan0,
+    &sci_rs232_chan1
+};
+#endif
+
+int main()
+{
+    /* Initialize and enable interrupts */
+    excptvec_initfill(LightOn,0);
+    sti();
+    /* Initialize SCI channels 0 and 1 */
+    sci_rs232_setmode(19200, 0, 0, 0); 
+    sci_rs232_setmode(19200, 0, 0, 1); 
+    /* If you and want channel 1 to be default uncomment the following
+     * two lines. */
+    //sci_rs232_chan_default = 1;
+
+    int i = 0;
+    while (1){
+        /* This will go to channel 0. */
+        sci_rs232_sendch('H', 0);
+        sci_rs232_sendch('e', 0);
+        sci_rs232_sendch('l', 0);
+        sci_rs232_sendch('l', 0);
+        sci_rs232_sendch('o', 0);
+
+        /* This will go to default channel. */
+        printf(" world!\n");    
+
+        if (i++%2) DEB_LED_ON(2); 
+        else DEB_LED_OFF(2);
+
+        FlWait(100000);
+    };
+};
+
+/* Local variables: */
+/* compile-command:"make -C ~/h8300/h8300-boot/app/rs_test all load run" */
+/* End: */
diff --git a/app/cantest/can_drive/rs_test2.c b/app/cantest/can_drive/rs_test2.c
new file mode 100644 (file)
index 0000000..169719a
--- /dev/null
@@ -0,0 +1,92 @@
+/* tests of sci_rs232_sendch, printf, sci_rs232_recch, scanf ...*/
+
+/* procesor H8S/2638 ver 1.1  */
+#include <stdio.h>
+#include <types.h>
+#include <cpu_def.h>
+#include <h8s2638h.h>
+#include <system_def.h>
+#include <string.h>
+#include <boot_fn.h>
+#include <periph/sci_rs232.h>
+
+static void deb_led_out(char val)
+{
+    if (val&1)
+        *DIO_PJDR |=PJDR_PJ1DRm; 
+    else
+        *DIO_PJDR &=~PJDR_PJ1DRm; 
+
+    if (val&2)
+        *DIO_PJDR |=PJDR_PJ2DRm; 
+    else
+        *DIO_PJDR &=~PJDR_PJ2DRm; 
+
+    if (val&4)
+        *DIO_PJDR |=PJDR_PJ3DRm; 
+    else
+        *DIO_PJDR &=~PJDR_PJ3DRm; 
+}
+
+//Interrupt routine
+void  LightOn(void) __attribute__ ((interrupt_handler));
+void LightOn(void)
+{
+    deb_led_out(4);
+    FlWait(1*20000);
+    deb_led_out(1);
+    FlWait(1*200000);
+}    
+
+
+int main()
+{
+    char s[20];
+    int i;
+
+    excptvec_initfill(LightOn,0);
+    sti();
+    sci_rs232_setmode(19200, 0, 0, sci_rs232_chan_default);
+    while (1){
+        FlWait(1*200000);
+        deb_led_out(6);
+        FlWait(1*200000);
+
+        int val1;
+       FlWait(1*700000);
+        printf(" Please enter an integer:\n");
+        //FlWait(1*700000);
+        val1 = sci_rs232_recch(sci_rs232_chan_default);
+        FlWait(1*700000);
+        deb_led_out(5);
+        printf("-> %d\n", val1);  //when nothing entered: prints -1 : queue is empty 
+  
+        char val2 ='a';
+        printf(" Please enter a character:\n");  
+        //FlWait(1*500000);
+        val2 = sci_rs232_recch(sci_rs232_chan_default);
+        FlWait(1*500000);
+        deb_led_out(5);
+        printf("-> %c \n", val2); //when nothing entered: prints an y with .. on (???) (=255 in ASCII)
+  
+        char val3[20];
+        deb_led_out(5); 
+        printf(" Please enter a word: \n");
+        FlWait(1*200000); 
+        scanf("%s", val3);    
+        printf("-> %s\n", val3);
+        deb_led_out(2); 
+  
+        printf(" Please enter another word: \n");
+        i=read(0,s,sizeof(s)-1);
+        s[i]=0;
+        printf("String is \"%s\" and len is %d\n",s,i);
+        i=-1;
+
+        printf(" Please enter a decimal number: \n");
+        scanf("%d\n",&i);
+        printf("Value is %d\n",i);
+   
+    };
+};
diff --git a/app/cantest/canfestival/Makefile b/app/cantest/canfestival/Makefile
new file mode 100644 (file)
index 0000000..f595272
--- /dev/null
@@ -0,0 +1,14 @@
+# Generic directory or leaf node makefile for OCERA make framework
+
+ifndef MAKERULES_DIR
+MAKERULES_DIR := $(shell ( old_pwd="" ;  while [ ! -e Makefile.rules ] ; do if [ "$$old_pwd" == `pwd`  ] ; then exit 1 ; else old_pwd=`pwd` ; cd -L .. 2>/dev/null ; fi ; done ; pwd ) )
+endif
+
+ifeq ($(MAKERULES_DIR),)
+all : default
+.DEFAULT::
+       @echo -e "\nThe Makefile.rules has not been found in this or partent directory\n"
+else   
+include $(MAKERULES_DIR)/Makefile.rules
+endif
+
diff --git a/app/cantest/canfestival/Makefile.omk b/app/cantest/canfestival/Makefile.omk
new file mode 100644 (file)
index 0000000..721c161
--- /dev/null
@@ -0,0 +1,3 @@
+# -*- makefile -*-
+
+SUBDIRS = include src applislave driver
diff --git a/app/cantest/canfestival/applislave/Makefile b/app/cantest/canfestival/applislave/Makefile
new file mode 100644 (file)
index 0000000..f595272
--- /dev/null
@@ -0,0 +1,14 @@
+# Generic directory or leaf node makefile for OCERA make framework
+
+ifndef MAKERULES_DIR
+MAKERULES_DIR := $(shell ( old_pwd="" ;  while [ ! -e Makefile.rules ] ; do if [ "$$old_pwd" == `pwd`  ] ; then exit 1 ; else old_pwd=`pwd` ; cd -L .. 2>/dev/null ; fi ; done ; pwd ) )
+endif
+
+ifeq ($(MAKERULES_DIR),)
+all : default
+.DEFAULT::
+       @echo -e "\nThe Makefile.rules has not been found in this or partent directory\n"
+else   
+include $(MAKERULES_DIR)/Makefile.rules
+endif
+
diff --git a/app/cantest/canfestival/applislave/Makefile.omk b/app/cantest/canfestival/applislave/Makefile.omk
new file mode 100644 (file)
index 0000000..56d82ea
--- /dev/null
@@ -0,0 +1,10 @@
+# -*- makefile -*-
+
+bin_PROGRAMS  = applislave
+
+applislave_SOURCES = appli.c objdict.c
+
+applislave_LIBS = canfestival candriver  boot_fn arch_drivers sci_channels excptvec misc
+applislave_MOREOBJS = $(USER_LIB_DIR)/system_stub.o
+
+link_VARIANTS = ram flash
diff --git a/app/cantest/canfestival/applislave/appli.c b/app/cantest/canfestival/applislave/appli.c
new file mode 100644 (file)
index 0000000..7d33980
--- /dev/null
@@ -0,0 +1,560 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+#include <stddef.h> /* for NULL */
+
+//#include <asm-m68hc12/portsaccess.h>
+//#include <asm-m68hc12/ports_def.h>
+//#include <asm-m68hc12/ports.h>
+#include  <interrupt.h>
+
+#include <applicfg.h>
+#include <candriver.h>
+#include <timerhw.h>
+
+#include "../include/def.h"
+#include "../include/can.h"
+#include "../include/objdictdef.h"
+#include "../include/objacces.h"
+#include "../include/canOpenDriver.h"
+#include "../include/sdo.h"
+#include "../include/pdo.h"
+#include "../include/timer.h"
+#include "../include/lifegrd.h"
+#include "../include/sync.h"
+
+#include "../include/nmtSlave.h"
+
+/* Added for H8S/2638 */
+#include <periph/sci_rs232.h>
+#include <h8s2638h.h>
+#include <system_def.h>
+#include <cpu_def.h>
+
+#include "objdict.h"
+
+/* !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!! */
+//#define PORT_DIS_FUNC /* projekt nebude fungovat, ale lze kompilovat */
+
+#define DEBUG 0
+
+/* Debug variables */
+#if DEBUG
+  extern int prerus_hcan0, prerus_hcan0_rec;
+  extern int prerus_hcan0_old, prerus_hcan0_rec_old;
+/* Pointer for write or read a message in/from the reception stack */
+volatile t_pointerStack ptrMsgRcv[NB_LINE_CAN];
+#endif
+
+/* end Debug variables */
+
+// HCS12 configuration
+// -----------------------------------------------------
+/*
+enum E_CanBaudrate 
+{
+   CAN_BAUDRATE_250K,
+   CAN_BAUDRATE_500K,
+   CAN_BAUDRATE_1M,
+   CAN_BAUDRATE_OLD_VALUE
+};
+*/
+
+ #ifndef DEB_LED_OUT
+  #define DEB_LED_OUT
+  static void deb_led_out(char val)
+  {
+    if (val&1)
+      DEB_LED_ON(0);
+    else
+      DEB_LED_OFF(0);
+    if (val&2)
+      DEB_LED_ON(1);
+    else
+      DEB_LED_OFF(1);
+    if (val&4)
+      DEB_LED_ON(2);
+    else
+      DEB_LED_OFF(2);
+    if (val&8)
+      DEB_LED_ON(3);
+    else
+      DEB_LED_OFF(3);
+   }
+ #endif
+
+// The variables sent or updated by PDO
+// -----------------------------------------------------
+extern UNS8 seconds;           // Mapped at index 0x2000, subindex 0x1
+extern UNS8 minutes;           // Mapped at index 0x2000, subindex 0x2
+extern UNS8 hours;             // Mapped at index 0x2000, subindex 0x3
+extern UNS8 day;               // Mapped at index 0x2000, subindex 0x4
+extern UNS32 canopenErrNB;     // Mapped at index 0x6000, subindex 0x0
+extern UNS32 canopenErrVAL;    // Mapped at index 0x6001, subindex 0x0
+extern UNS16 casovac_h;                // Mapped at index 0x2001, subindex 0x01
+extern UNS16 casovac_l;                // Mapped at index 0x2001, subindex 0x02
+extern UNS32 casovac;
+extern UNS8 interval;  // Mapped at index 0x2000, subindex 0x05
+extern UNS8 ledky;             // Mapped at index 0x2000, subindex 0x06
+UNS32 casovac_zal;
+
+// Required definition variables
+// -----------------------------
+// The variables that you should define for debugging.
+// They are used by the macro MSG_ERR and MSG_WAR in applicfg.h
+// if the node is a slave, they can be mapped in the object dictionnary.
+// if not null, allow the printing of message to the console
+// Could be managed by PDO
+UNS8 printMsgErrToConsole = 1;
+UNS8 printMsgWarToConsole = 1;
+
+
+
+/*************************User's variables declaration**************************/
+UNS8 softCount = 0;
+UNS8 lastMinute = 0;
+UNS8 lastSecond = 0;
+UNS8 seconds_left = 0;
+UNS8 sendingError = 0;
+//--------------------------------FONCTIONS-------------------------------------
+/* You *must* have these 2 functions in your code*/
+void heartbeatError(UNS8 heartbeatID);
+void SD0timeoutError(UNS8 bus_id, UNS8 line);
+
+// Interruption timer 2. (The timer 4 is used by CanOpen)
+void timer4Hdl (void) __attribute__ ((interrupt_handler));
+
+void incDate(void);
+void initLeds(void);
+void initTimerClk(void);
+void initCAN (void);
+void initialisation(void);
+void preOperational(void);
+void operational(void);
+void stopped(void);
+//------------------------------------------------------------------------------
+
+//------------------------------------------------------------------------------
+// Interruption timer 4
+void timer4Hdl (void) __attribute__ ((interrupt_handler));
+void timer4Hdl (void)
+{
+  //unsigned short saveif;     /* interrupt every 1s */
+
+  //save_and_cli(saveif);      /* interrupts save and disable */
+  *TPU_TSR4 &= ~TSR4_TGFAm;    /* clear compare match */
+  incDate();
+  //restore_flags(saveif);     /* interruptions restore end enable */
+}
+
+//------------------------------------------------------------------------------
+// Init the timer for the clock demo
+void initTimerClk(void)
+{
+  //unsigned short saveif;
+
+  //save_and_cli(saveif);      /* interrupts save and disable */
+  excptvec_set(56,timer4Hdl);  /* register interrup routine for this timer */
+  if(*SYS_MSTPCRA&MSTPCRA_TPUm)        /* when module is stoped do */
+    *SYS_MSTPCRA &= ~MSTPCRA_TPUm; // power TPU unit
+  *TPU_TSTR &=~TSTR_CST4m;     // stop timer in all case
+  *TPU_TCR4 =(TCR_TPSC2m|TCR_TPSC1m)|(TCR1_CCLR0m); //rising edge, f divided by 1024, cleared by compare TGRA
+  *TPU_TMDR4 =0x00;    // normal mode
+  *TPU_TIOR4=0x00;     /* output compare is disabled */
+  *TPU_TSR4 &= ~TSR_TGFAm ;    //clear flag for TGRA compare
+  *TPU_TIER4 = TIER_TGIEAm;    //enable interrupt on compare with TGFA 
+  *TPU_TCNT4 = 0x00;
+  *TPU_TGR4A = 0x4650;         /* cout for 1 s, compare TGRA */
+  //TPU_TGR2B
+  *TPU_TSTR |=TSTR_CST4m;      //start timer
+  //restore_flags(saveif);     /* interruptions restore end enable */
+}
+
+//------------------------------------------------------------------------------
+void heartbeatError(UNS8 heartbeatID)
+{
+  MSG_ERR(0x1F00, "!!! No heart beat received from node : ", heartbeatID);
+}
+
+//------------------------------------------------------------------------------
+void SD0timeoutError (UNS8 bus_id, UNS8 line)
+{
+  // Informations on what occurs are in transfers[bus_id][line]....
+  // See scanSDOtimeout() in sdo.c
+}
+
+//------------------------------------------------------------------------------
+// Incrementation of the date, every second
+void incDate(void)
+{
+  if (seconds == 59) {
+    seconds = 0;
+    if (minutes == 59) {
+      minutes = 0;
+      if (hours == 23) {
+       hours = 0;
+       day++;
+      } 
+      else
+       hours++;
+    }
+    else 
+      minutes++;
+  }
+  else
+    seconds++;
+
+  // Toggle the led 4 every seconds
+  //IO_PORTS_8(PORTB) ^= 0x10;
+
+}
+
+//Initialisation of the port B for the leds.
+void initLeds(void)
+{
+#ifdef PORT_DIS_FUNC /* vyrazeno port */
+  // Port B is output
+  IO_PORTS_8(DDRB)= 0XFF;
+  // RAZ
+  IO_PORTS_8(PORTB) = 0xFF;
+#endif /* PORT_DIS_FUNC */
+}
+
+//------------------------------------------------------------------------------
+
+// A placer avant initTimer de la biblioth�ue CanOpen
+/* void initTimerbis(void) */
+/* {   */
+
+/*   lock();                      // Inhibe les interruptions */
+/*   // Configuration des IT Channels (0..3) */
+/*   IO_PORTS_8(TIOS)  &= 0xF0;  // Canals 0->3 en entr�s.    */
+/*   IO_PORTS_8(TCTL4) &= 0XFD;  // Canal 0 d�ection sur front montant. */
+/*   IO_PORTS_8(TCTL4) |= 0X01;    */
+/*   IO_PORTS_8(TCTL4) &= 0XF7;  // Canal 1 d�ection sur front montant. */
+/*   IO_PORTS_8(TCTL4) |= 0X04; */
+/*   IO_PORTS_8(TCTL4) &= 0XDF;  // Canal 2 d�ection sur front montant. */
+/*   IO_PORTS_8(TCTL4) |= 0X10;   */
+/*   IO_PORTS_8(TCTL4) &= 0X7F;  // Canal 3 d�ection sur front montant. */
+/*   IO_PORTS_8(TCTL4) |= 0X40;        */
+/*   IO_PORTS_8(TSCR2) |= 0X05;  // Pre-scaler = 32.  */
+   
+/*   IO_PORTS_8(ICOVW) |= 0x0F;  // La sauvgrade des valeures de TC0 et TC0H  */
+/*                               // correspondant aux canals (0..3) jusqu'a la */
+/*                               // prochaine lecture dans ces registres.  */
+/*   MASK  = IO_PORTS_8(ICSYS); */
+/*   MASK &= 0xFE;               // Canals (0..3) en IC QUEUE MODE. */
+/*   MASK |= 0x08;               // Canals (0..3) : g��e une interruption apr�  */
+/*                               // la capture de deux valeures du timer sur detection */
+/*                               // d'un front montant ï¿½l'entr� des canals (0..3). */
+/*   MASK |= 0x02;               */
+/*   IO_PORTS_8(ICSYS) = MASK; */
+/*   IO_PORTS_16(TC0HH);         // Vider le registre holding correspondant au canal0. */
+/*   IO_PORTS_8(TSCR1) |= 0x10;  // RAZ automatique des flags d'interruption apr� lecture */
+/*                               // dans les registres correspondant.   */
+                              
+/*   IO_PORTS_8(TIE)   |= 0x0F;  // Autorise interruption Canals (0..3). */
+/*   IO_PORTS_8(TSCR2) |= 0X80;  // Autorise interruption sur l'Overflow.  */
+/*   unlock();                   // Autorise les interruptions  */
+  
+/* } */
+
+//------------------------------------------------------------------------------
+
+
+
+void initCAN(void)
+{
+  //Init the H8S/2638 microcontroler for CanOpen 
+
+  // Init the H8S/2638 CAN driver
+  #if 0
+  const canBusInit bi0 = {
+    0,    /* no low power                 */   /* Low power/normal in wait mode   (1/0)      */
+    0,    /* no time stamp                */   /* Timer for time-stamp enable/disable (1/0)  */
+    1,    /* enable HCAN                 */    /* Enable MSCAN (yes=1) Do it !               */
+    0,    /* clock source : oscillator (In fact, it is not used)   */
+    0,    /* no loop back                 */   /* loop back mode for test (yes=1/no=0)       */
+    0,    /* no listen only               */   /* MSCAN is listen only (yes=1/no=0 ie normal)*/
+    0,    /* no low pass filter for wk up */   /* low pas filter for wake up (yes=1/no=0)    */
+       CAN_Baudrates[CAN_BAUDRATE_250K],
+    {
+      0x00,    /* Filter on 16 bits. See Motorola Block Guide V02.14 fig 4-3 */
+      0x00, 0xFF, /* filter 0 hight accept all msg      */
+      0x00, 0xFF, /* filter 0 low accept all msg        */
+      0x00, 0xFF, /* filter 1 hight filter all of  msg  */
+      0x00, 0xFF, /* filter 1 low filter all of  msg    */
+      0x00, 0xFF, /* filter 2 hight filter most of  msg */
+      0x00, 0xFF, /* filter 2 low filter most of  msg   */
+      0x00, 0xFF, /* filter 3 hight filter most of  msg */
+      0x00, 0xFF, /* filter 3 low filter most of  msg   */
+    }
+  };
+  #endif /* 0 */
+  canInit(CANOPEN_LINE_NUMBER_USED, 200000);
+}
+
+//$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$
+// FUNCTIONS WHICH ARE PART OF CANFESTIVAL and *must* be implemented here.
+
+//------------------------------------------------------------------------------
+void gene_SYNC_heartbeatError( UNS8 heartbeatID )
+{ /* ??? Caled in interrup routine ??? */
+  //MSG_ERR(0x1F00, "HeartBeat not received from node : ", heartbeatID);
+}
+
+//------------------------------------------------------------------------------
+void gene_SYNC_SDOtimeoutError (UNS8 line)
+{  /* !!! Caled in interrup routine !!! */
+  //MSG_ERR(0x1F01, "SDO timeout for line : ", line);
+}
+
+//------------------------------------------------------------------------------
+UNS8 gene_SYNC_canSend(Message *m)
+{
+  // HCS12 driver function to send the CAN msg
+  canMsgTransmit(0, *m);
+  return 0;
+}
+
+//------------------------------------------------------------------------------
+void gene_SYNC_initialisation()
+{  
+  MSG_WAR (0x3F00, "Entering in INIT ", 0); 
+ // initSensor();
+ // IO_PORTS_8(PORTB) &= ~ 0x01; // led  0         : ON
+ // IO_PORTS_8(PORTB) |=   0x0E; // leds 1, 2, 3   : OFF
+ //initialisation();
+}
+
+
+//------------------------------------------------------------------------------
+void gene_SYNC_preOperational()
+{
+  MSG_WAR (0x3F01, "Entering in PRE-OPERATIONAL ", 0); 
+ // IO_PORTS_8(PORTB) &= ~ 0x03; // leds 0, 1      : ON
+ // IO_PORTS_8(PORTB) |=   0x0C; // leds 2, 3      : OFF
+}
+
+
+//------------------------------------------------------------------------------
+void gene_SYNC_operational()
+{ 
+   MSG_WAR (0x3F02, "Entering in OPERATIONAL ", 0); 
+   //IO_PORTS_8(PORTB) &= ~ 0x07; // leds 0, 1, 2   : ON
+   //IO_PORTS_8(PORTB) |=   0x08; // leds 3         : OFF
+}
+
+//------------------------------------------------------------------------------
+void gene_SYNC_stopped()
+{
+  MSG_WAR (0x3F02, "Entering in STOPPED ", 0); 
+}
+
+//------------------------------------------------------------------------------
+void gene_SYNC_post_sync()
+{
+}
+
+//------------------------------------------------------------------------------
+void gene_SYNC_post_TPDO()
+{
+}
+
+// End functions which are part of Canfestival
+//$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$
+
+
+/*********************************************************************/
+void initialisation( void )
+{ 
+  //initcapteur();      //initialisation du capteur, timer, compteurs logiciels
+  initCAN();   //initialisation du bus Can /* not for H8S */
+  MSG_WAR(0X3F05, "I am in INITIALISATION mode ", 0);
+  /* Defining the node Id */
+  //setNodeId(0x05);
+  MSG_WAR(0x3F06, "My node ID is : ", getNodeId(&gene_SYNC_Data)); 
+  {
+    UNS8 *data;
+    UNS8 size;
+    UNS8 dataType;
+    // Manufacturer Device name (default = empty string)
+    getODentry(&gene_SYNC_Data,0x1008, 0x0, (void **)&data, &size, &dataType, 0);
+    MSG_WAR(0x3F09, data, 0);
+    // Manufacturer Hardware version. (default = compilation. date)
+    getODentry(&gene_SYNC_Data,0x1009, 0x0, (void **)&data, &size, &dataType, 0);
+    MSG_WAR(0x3F09, data, 0);
+    // Manufacturer Software version. (default = compilation. time)
+    getODentry(&gene_SYNC_Data,0x100A, 0x0, (void **)&data, &size, &dataType, 0);
+    MSG_WAR(0x3F09, data, 0);
+  }
+  //initCANopenMain();    //initialisation du canopen 
+  //heartbeatInit();      //initialisation du lifeguarding
+  //initResetMode();
+  initTimer();          //initialisation of the timer used by Canopen
+  initTimerClk();
+}
+
+#if 0
+/*********************************************************************/
+void preOperational(void)
+{
+#if DEBUG
+  if(prerus_hcan0!=prerus_hcan0_old) {
+    printf("prerus:%d ", prerus_hcan0);
+    prerus_hcan0_old=prerus_hcan0;
+  };
+  if(prerus_hcan0_rec!=prerus_hcan0_rec_old) {
+    printf("prerus rec:%d ", prerus_hcan0_rec);
+    prerus_hcan0_rec_old=prerus_hcan0_rec;
+    printf("MsgRcv r=%d, MsgRcv w=%d\n", ptrMsgRcv[0].r, ptrMsgRcv[0].w);
+  };
+#endif
+
+  // Test if the heartBeat have been received. Send headbeat
+  heartbeatMGR();
+  // Read message
+  receiveMsgHandler(0);
+}
+#endif
+
+TIMEVAL getTime(void);
+/********************************************************************/
+void operational( void )
+{ 
+
+  // Init the errors
+  canopenErrNB = 0;
+  canopenErrVAL = 0;
+  UNS8 navrat;
+
+  // Test if the heartBeat have been received. Send headbeat
+  //heartbeatMGR();
+  // Read message
+  //receiveMsgHandler(0);
+
+  //casovac = getTime();
+  //printf("cas:0x%04x%04x\n", (casovac_zal>>16), casovac_zal&0xffff);
+  //FlWait(5*100000);
+  if (lastMinute != minutes) {
+    MSG_WAR(0x3F00, "event : minutes change -> node decides to send it. Value : ", minutes);
+    navrat=sendPDOevent( &gene_SYNC_Data, &minutes );
+    MSG_WAR(0x3F00, "navrat: ", navrat);
+    lastMinute = minutes;
+  }
+
+  if (canopenErrNB == 0)
+    sendingError = 0;
+
+  if (lastSecond != seconds) {
+    seconds_left++;
+      deb_led_out(ledky);
+    //MSG_WAR (0x3F50, "Seconds = ", seconds);
+    //if ((seconds == 20)|(seconds == 50) /*&& (sendingError == 0)*/)
+    if (seconds_left >= interval)
+      {
+       //MSG_ERR(0x1F55, "DEMO of ERROR. Sent by PDO. Value : ", 0xABCD);
+       //sendingError = 1;
+        MSG_WAR (0x3F52, "Seconds = ", seconds);
+        navrat=sendPDOevent( &gene_SYNC_Data, &seconds );
+        seconds_left = 0;
+      }
+    /*
+    if (canopenErrNB) {
+      MSG_WAR(0x3F56, "ERROR nb : ",  canopenErrNB);
+    }
+    */
+    lastSecond = seconds;
+  }
+
+}
+
+#if 0 /* vyrazeni pro nove */
+/*****************************************************************************/
+void stopped( void )
+{
+  heartbeatMGR();
+  // Read message
+  receiveMsgHandler(0);
+}
+
+#endif /* vyrazeni pro nove */
+
+/*****************************************************************************/
+void test_unhandled_isr(void) __attribute__ ((interrupt_handler));
+void test_unhandled_isr(void)
+{
+  while(1);
+}
+
+/********************************* MAIN ***************************************/
+int main ()
+{
+  int rs232_init_ok;
+  Message m;
+  UNS8 ret;
+  e_nodeState StateOP=Operational;
+
+  excptvec_initfill(test_unhandled_isr,1);
+  sti();       /* enable interrupts */
+
+
+  /* set serial chanel */
+  if(sci_rs232_setmode(19200, 0, 0, sci_rs232_chan_default)>=0)  {
+    rs232_init_ok=1;
+  };
+  FlWait(2*1000000);
+
+  MSG_WAR(0x3F34, "Entering in the main", 0);
+  //----------------------------- INITIALISATION --------------------------------
+  /* Defining the node Id */
+  setNodeId(&gene_SYNC_Data, 0x03);
+  initialisation();
+
+  /* Put the node in Initialisation mode */
+  MSG_WAR(0x3F35, "va passer en init", 0);
+  setState(&gene_SYNC_Data, Initialisation);
+
+  //----------------------------- START -----------------------------------------
+  /* Put the node in pre-operational mode */
+  //MSG_WAR(0x3F36, "va passer en pre-op", 0);
+  //setState(&gene_SYNC_Data, Pre_operational);
+
+
+
+  /* CanOpen slave state machine         */
+  /* ------------------------------------*/
+
+  while(1) { /* slave's state machine */
+
+       if (f_can_receive(0, &m)) {
+          //MSG_WAR(0x3F36, "f_can", ret);
+         MSG_WAR(0x3F36, "Msg received", m.cob_id.w);
+         canDispatch(&gene_SYNC_Data, &m);
+       }
+       if (gene_SYNC_Data.nodeState == StateOP)
+          operational();
+
+  }
+  return (0); 
+}
diff --git a/app/cantest/canfestival/applislave/example_objdict.c b/app/cantest/canfestival/applislave/example_objdict.c
new file mode 100644 (file)
index 0000000..0fafeaf
--- /dev/null
@@ -0,0 +1,579 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+
+#include <stddef.h>
+
+#include <canfestival/applicfg.h>
+#include "canfestival/def.h"
+#include "canfestival/can.h"
+#include "canfestival/objdictdef.h"
+#include "canfestival/pdo.h"
+#include "canfestival/sdo.h"
+#include "canfestival/sync.h"
+#include "canfestival/lifegrd.h"
+#include "canfestival/nmtSlave.h"
+
+/**************************************************************************/
+/* Declaration of the mapped variables                                    */
+/**************************************************************************/
+UNS8 seconds = 0;              // Mapped at index 0x2000, subindex 0x01
+UNS8 minutes = 0;              // Mapped at index 0x2000, subindex 0x02
+UNS8 hours = 0;                // Mapped at index 0x2000, subindex 0x03
+UNS8 day = 0;          // Mapped at index 0x2000, subindex 0x04
+UNS32 canopenErrNB = 0;                // Mapped at index 0x6000, subindex 0x00
+UNS32 canopenErrVAL = 0;               // Mapped at index 0x6001, subindex 0x00
+UNS8 strTest[10] = 0;          // Mapped at index 0x6002, subindex 0x00
+
+/**************************************************************************/
+/* Declaration of the value range types                                   */
+/**************************************************************************/
+
+
+
+UNS32 gene_SYNC_valueRangeTest (UNS8 typeValue, UNS32 unsValue, REAL32 realValue)
+{
+  switch (typeValue) {
+  }
+  return 0;
+}
+
+
+/**************************************************************************/
+/* The node id                                                            */
+/**************************************************************************/
+/* node_id default value. 
+   This default value is deprecated.
+   You should always overwrite this by using the function setNodeId(UNS8 nodeId) in your C code.
+*/
+#define NODE_ID 0x01
+UNS8 gene_SYNC_bDeviceNodeId = NODE_ID;
+
+
+//*****************************************************************************/
+/* Array of message processing information */
+/* Should not be modified */
+
+const UNS8 gene_SYNC_iam_a_slave = 1
+
+  // Macros definition
+
+/* Beware : 
+index                 *must* be writen 4 numbers in hexa
+sub_index             *must* be writen 2 numbers in hexa
+size_variable_in_UNS8 *must* be writen 2 numbers in hexa
+*/
+#define PDO_MAP(index, sub_index, size_variable_in_bits)\
+0x ## index ## sub_index ## size_variable_in_bits
+
+/** This macro helps creating the object dictionary entries.
+ *  by calling this macro
+ *  it creates an entry in form of: 7 of entries, pointer to the entry. 
+ */
+#define DeclareIndexTableEntry(entryname, index)    { (subindex*)entryname,sizeof(entryname)/sizeof(entryname[0]), index}
+
+//$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$
+//
+//                       OBJECT DICTIONARY
+//                   
+//$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$
+// Make your change, depending of your application
+
+/* index 0x1000 :   Device type. 
+                    You have to change the value below, so
+                    it fits your canopen-slave-module */
+                    /* Not used, so, should not be modified */
+                    
+                    UNS32 gene_SYNC_obj1000 = 0;
+                    subindex gene_SYNC_Index1000[] =
+                    {
+                      { RO, uint32, sizeof(UNS32), (void*)&gene_SYNC_obj1000 }
+                    };
+
+/* index 0x1001 :   Error register. 
+                    Change the entries to fit your application 
+                    Not used, so, should not be modified */
+                    /*const*/ UNS8 gene_SYNC_obj1001 = 0x0;
+                    /*const*/ subindex gene_SYNC_Index1001[] =
+                    {
+                      { RO, uint8, sizeof(UNS8), (void*)&gene_SYNC_obj1001 }
+                    };
+
+/* index 0x1005 :   COB_ID SYNC */
+                    /* Should not be modified */
+                    UNS32 gene_SYNC_obj1005 = 0x00000080; // bit 30 = 1 : device can generate a SYNC message
+                                                // Beware, it is over written when the node 
+                                                // enters in reset mode
+                                                // See initResetMode() in init.c
+                    /*const*/ subindex gene_SYNC_Index1005[] =
+                    {
+                      { RW, uint32, sizeof(UNS32), (void*)&gene_SYNC_obj1005 }
+                    };
+
+/* index 0x1006 :   SYNC period */
+                    // For producing the SYNC signal every n micro-seconds.
+                    // Put 0 to not producing SYNC
+                    /*const*/ UNS32 gene_SYNC_obj1006 = 0x0; 
+                                         // Default 0 to not produce SYNC //
+                                         // Beware, it is over written when the 
+                                         // node enters in reset mode.
+                                         // See initResetMode() in init.c
+                    /*const*/ subindex gene_SYNC_Index1006[] =
+                    {
+                      { RW, uint32, sizeof(UNS32), (void*)&gene_SYNC_obj1006 }
+                    };
+
+/* index 0x1007 :   Synchronous Window Length
+                    Seems to be needed by DS401 to generate the SYNC signal ! */
+                    /*const*/ UNS32 gene_SYNC_obj1007 = 0x0; /* Default 0 */
+                    /*const*/ subindex gene_SYNC_Index1007[] =
+                    {
+                      { RW, uint32, sizeof(UNS32), (void*)&gene_SYNC_obj1007 }
+                    };
+
+/* index 0x1008 :   Manufacturer device name */
+                    UNS8 gene_SYNC_obj1008[] = "Appli_Slave_HC12"; /* Default 0 */
+                    subindex gene_SYNC_Index1008[] =
+                    {
+                      { RO, uint32, sizeof(gene_SYNC_obj1008), (void*)&gene_SYNC_obj1008 }
+                    };
+
+/* index 0x1009 :   Manufacturer hardware version */
+                    UNS8 gene_SYNC_obj1009[] = "__DATE__"; /* Default 0 */
+                    subindex gene_SYNC_Index1009[] =
+                    {
+                      { RO, uint32, sizeof(gene_SYNC_obj1009), (void*)&gene_SYNC_obj1009 }
+                    };
+
+/* index 0x100A :   Manufacturer software version */
+                    UNS8 gene_SYNC_obj100A[] = __TIME__; /* Default 0 */
+                    subindex gene_SYNC_Index100A[] =
+                    {
+                      { RO, uint32, gene_SYNC_sizeof(obj100A), (void*)&gene_SYNC_obj100A}
+                    };
+
+
+                    TIMER_HANDLE gene_SYNC_heartBeatTimers[1] = {TIMER_NONE,};
+/* index 0x1016 :   HeartBeat consumers 
+                    The nodes which can send a heartbeat */ 
+                    UNS32 gene_SYNC_obj1016[] = {// Consumer time for each node 
+                    0x00000000}; // Format 0x00NNTTTT (N=Node T=time in ms)
+
+                    UNS8 gene_SYNC_obj1016_cnt = 1; // 1 nodes could send me
+                                                  // their heartbeat.
+                    subindex gene_SYNC_Index1016[] = 
+                    {
+                      { RO, uint8, sizeof(UNS8), (void*)&gene_SYNC_obj1016_cnt },
+                      { RW, uint32, sizeof(UNS32), (void*)&gene_SYNC_obj1016[0] }
+                    }; 
+
+/* index 0x1017 :   Heartbeat producer                    
+                    Every HBProducerTime, the node sends its heartbeat */
+                    UNS16 gene_SYNC_obj1017 = 0; //HBProducerTime in ms. If 0 : not activated 
+                                                     // Beware, it is over written when the 
+                                                     // node enters in reset mode.
+                                                     // See initResetMode() in init.c
+                    subindex gene_SYNC_Index1017[] =
+                    {
+                     { RW, uint16, sizeof(UNS16), &gene_SYNC_obj1017 }
+                    };
+
+/* index 0x1018 :   Identity object */
+                    /** index 1018: identify object. Adjust the entries for your node/company
+                    */
+                    /* Values can be modified */
+
+                    s_identity gene_SYNC_obj1018 =
+                    {
+                      4,       // number of supported entries
+                      0,  // Vendor-ID (given by the can-cia)
+                      0,  // Product Code
+                      0,  // Revision number
+                      0  // serial number
+                    };
+
+                    subindex gene_SYNC_Index1018[] =
+                    {
+                      { RO, uint8,  sizeof(UNS8),  (void*)&gene_SYNC_obj1018.count },
+                      { RO, uint32, sizeof(UNS32), (void*)&gene_SYNC_obj1018.vendor_id},
+                      { RO, uint32, sizeof(UNS32), (void*)&gene_SYNC_obj1018.product_code},
+                      { RO, uint32, sizeof(UNS32), (void*)&gene_SYNC_obj1018.revision_number},
+                      { RO, uint32, sizeof(UNS32), (void*)&gene_SYNC_obj1018.serial_number}
+                    };
+
+/* index 0x1200 :   The SDO Server parameters */
+                    /* BEWARE You cannot define more than one SDO server */
+                    /* The values should not be modified here, 
+                    but can be changed at runtime */
+                    // Beware that the default values that you could put here
+                    // will be over written at the initialisation of the node. 
+                    // See setNodeId() in init.c
+                    s_sdo_parameter gene_SYNC_obj1200  = 
+                      { 3,                   // Number of entries. Always 3 for the SDO               
+                        0x601,     // The cob_id transmited in CAN msg to the server     
+                        0x581,     // The cob_id received in CAN msg from the server  
+                        0x01      // The node id of the client. Should not be modified
+                      };
+                    subindex gene_SYNC_Index1200[] =
+                    {
+                      { RO, uint8,  sizeof( UNS8 ), (void*)&gene_SYNC_obj1200.count },
+                      { RO, uint32, sizeof( UNS32), (void*)&gene_SYNC_obj1200.cob_id_client },
+                      { RO, uint32, sizeof( UNS32), (void*)&gene_SYNC_obj1200.cob_id_server },
+                      { RW, uint8,  sizeof( UNS8),  (void*)&gene_SYNC_obj1200.node_id }
+                    };
+
+/* index 0x1280 :   SDO client parameter */
+                    s_sdo_parameter gene_SYNC_obj1280 = 
+                      { 3,     // Nb of entries 
+                        0x600, // cobid transmited to the server. The good value should be 0x600 + server nodeId
+                        0x580, // cobid received from the server. The good value should be 0x580 + server nodeId
+                        0x01  // server NodeId
+                      };
+                    subindex gene_SYNC_Index1280[] = 
+                      { 
+                        { RO, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1280.count },
+                        { RW, uint8, sizeof( UNS32 ), (void*)&gene_SYNC_obj1280.cob_id_client },
+                        { RW, uint8, sizeof( UNS32 ), (void*)&gene_SYNC_obj1280.cob_id_server },
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1280.node_id }
+                      }; 
+
+/* index 0x1400 :   PDO receive communication parameter */
+                    s_pdo_communication_parameter gene_SYNC_obj1400 = 
+                      { 2, // Largest subindex supported 
+                        0x0, // Default COBID (overwritten at init for index 0x1400 to 0x1403)
+                        253 // Transmission type. See objdictdef.h 
+                      };
+                    subindex gene_SYNC_Index1400[] = 
+                      { 
+                        { RO, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1400.count },
+                        { RW, uint8, sizeof( UNS32 ), (void*)&gene_SYNC_obj1400.cob_id },
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1400.type },
+                      }; 
+
+/* index 0x1401 :   PDO receive communication parameter */
+                    s_pdo_communication_parameter gene_SYNC_obj1401 = 
+                      { 2, // Largest subindex supported 
+                        0x0, // Default COBID (overwritten at init for index 0x1400 to 0x1403)
+                        253 // Transmission type. See objdictdef.h 
+                      };
+                    subindex gene_SYNC_Index1401[] = 
+                      { 
+                        { RO, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1401.count },
+                        { RW, uint8, sizeof( UNS32 ), (void*)&gene_SYNC_obj1401.cob_id },
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1401.type },
+                      }; 
+
+/* index 0x1402 :   PDO receive communication parameter */
+                    s_pdo_communication_parameter gene_SYNC_obj1402 = 
+                      { 2, // Largest subindex supported 
+                        0x0, // Default COBID (overwritten at init for index 0x1400 to 0x1403)
+                        253 // Transmission type. See objdictdef.h 
+                      };
+                    subindex gene_SYNC_Index1402[] = 
+                      { 
+                        { RO, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1402.count },
+                        { RW, uint8, sizeof( UNS32 ), (void*)&gene_SYNC_obj1402.cob_id },
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1402.type },
+                      }; 
+
+/* index 0x1600 :   PDO receive mapping parameter of PDO communication index 0x1400 */
+                    UNS8 gene_SYNC_obj1600_cnt = 0; // Number of mapped variables
+                    UNS32 gene_SYNC_obj1600_mappedVar[] = { 
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000
+                      };
+                    subindex gene_SYNC_Index1600[] = 
+                      { 
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1600_cnt },
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1600_mappedVar[0]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1600_mappedVar[1]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1600_mappedVar[2]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1600_mappedVar[3]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1600_mappedVar[4]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1600_mappedVar[5]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1600_mappedVar[6]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1600_mappedVar[7]}
+                      }; 
+
+/* index 0x1601 :   PDO receive mapping parameter of PDO communication index 0x1401 */
+                    UNS8 gene_SYNC_obj1601_cnt = 0; // Number of mapped variables
+                    UNS32 gene_SYNC_obj1601_mappedVar[] = { 
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000
+                      };
+                    subindex gene_SYNC_Index1601[] = 
+                      { 
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1601_cnt },
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1601_mappedVar[0]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1601_mappedVar[1]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1601_mappedVar[2]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1601_mappedVar[3]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1601_mappedVar[4]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1601_mappedVar[5]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1601_mappedVar[6]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1601_mappedVar[7]}
+                      }; 
+
+/* index 0x1602 :   PDO receive mapping parameter of PDO communication index 0x1402 */
+                    UNS8 gene_SYNC_obj1602_cnt = 0; // Number of mapped variables
+                    UNS32 gene_SYNC_obj1602_mappedVar[] = { 
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000
+                      };
+                    subindex gene_SYNC_Index1602[] = 
+                      { 
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1602_cnt },
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1602_mappedVar[0]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1602_mappedVar[1]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1602_mappedVar[2]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1602_mappedVar[3]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1602_mappedVar[4]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1602_mappedVar[5]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1602_mappedVar[6]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1602_mappedVar[7]}
+                      }; 
+
+/* index 0x1800 :   PDO transmit communication parameter */
+                    s_pdo_communication_parameter gene_SYNC_obj1800 = 
+                      { 2, // Largest subindex supported 
+                        0x0, // Default COBID (overwritten at init for index 0x1400 to 0x1403)
+                        253 // Transmission type. See objdictdef.h 
+                      };
+                    subindex gene_SYNC_Index1800[] = 
+                      { 
+                        { RO, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1800.count },
+                        { RW, uint8, sizeof( UNS32 ), (void*)&gene_SYNC_obj1800.cob_id },
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1800.type },
+                      }; 
+
+/* index 0x1801 :   PDO transmit communication parameter */
+                    s_pdo_communication_parameter gene_SYNC_obj1801 = 
+                      { 2, // Largest subindex supported 
+                        0x0, // Default COBID (overwritten at init for index 0x1400 to 0x1403)
+                        253 // Transmission type. See objdictdef.h 
+                      };
+                    subindex gene_SYNC_Index1801[] = 
+                      { 
+                        { RO, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1801.count },
+                        { RW, uint8, sizeof( UNS32 ), (void*)&gene_SYNC_obj1801.cob_id },
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1801.type },
+                      }; 
+
+/* index 0x1802 :   PDO transmit communication parameter */
+                    s_pdo_communication_parameter gene_SYNC_obj1802 = 
+                      { 2, // Largest subindex supported 
+                        0x0, // Default COBID (overwritten at init for index 0x1400 to 0x1403)
+                        253 // Transmission type. See objdictdef.h 
+                      };
+                    subindex gene_SYNC_Index1802[] = 
+                      { 
+                        { RO, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1802.count },
+                        { RW, uint8, sizeof( UNS32 ), (void*)&gene_SYNC_obj1802.cob_id },
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1802.type },
+                      }; 
+
+/* index 0x1A00 :   PDO transmit mapping parameter of PDO communication index 0x1800 */
+                    UNS8 gene_SYNC_obj1A00_cnt = 0; // Number of mapped variables
+                    UNS32 gene_SYNC_obj1A00_mappedVar[] = { 
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000
+                      };
+                    subindex gene_SYNC_Index1A00[] = 
+                      { 
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1A00_cnt },
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A00_mappedVar[0]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A00_mappedVar[1]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A00_mappedVar[2]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A00_mappedVar[3]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A00_mappedVar[4]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A00_mappedVar[5]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A00_mappedVar[6]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A00_mappedVar[7]}
+                      }; 
+
+/* index 0x1A01 :   PDO transmit mapping parameter of PDO communication index 0x1801 */
+                    UNS8 gene_SYNC_obj1A01_cnt = 0; // Number of mapped variables
+                    UNS32 gene_SYNC_obj1A01_mappedVar[] = { 
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000
+                      };
+                    subindex gene_SYNC_Index1A01[] = 
+                      { 
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1A01_cnt },
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A01_mappedVar[0]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A01_mappedVar[1]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A01_mappedVar[2]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A01_mappedVar[3]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A01_mappedVar[4]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A01_mappedVar[5]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A01_mappedVar[6]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A01_mappedVar[7]}
+                      }; 
+
+/* index 0x1A02 :   PDO transmit mapping parameter of PDO communication index 0x1802 */
+                    UNS8 gene_SYNC_obj1A02_cnt = 0; // Number of mapped variables
+                    UNS32 gene_SYNC_obj1A02_mappedVar[] = { 
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000
+                      };
+                    subindex gene_SYNC_Index1A02[] = 
+                      { 
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1A02_cnt },
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A02_mappedVar[0]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A02_mappedVar[1]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A02_mappedVar[2]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A02_mappedVar[3]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A02_mappedVar[4]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A02_mappedVar[5]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A02_mappedVar[6]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A02_mappedVar[7]}
+                      }; 
+
+
+/* index 0x2000 :   Mapped variable */
+                    UNS8 gene_SYNC_highestSubIndex_2000 = 4; // number of subindex - 1
+                    subindex gene_SYNC_Index2000[] = 
+                     {
+                       { RO, uint8, sizeof (UNS8), (void*)&gene_SYNC_highestSubIndex_2000 },
+                       { RW, uint8, sizeof (UNS8), (void*)&seconds },
+                       { RW, uint8, sizeof (UNS8), (void*)&minutes },
+                       { RW, uint8, sizeof (UNS8), (void*)&hours },
+                       { RW, uint8, sizeof (UNS8), (void*)&day }
+                     };
+
+/* index 0x6000 :   Mapped variable */
+                    UNS8 gene_SYNC_highestSubIndex_6000 = 0; // number of subindex - 1
+                    subindex gene_SYNC_Index6000[] = 
+                     {
+                       { RW, uint32, sizeof (UNS32), (void*)&canopenErrNB }
+                     };
+
+/* index 0x6001 :   Mapped variable */
+                    UNS8 gene_SYNC_highestSubIndex_6001 = 0; // number of subindex - 1
+                    subindex gene_SYNC_Index6001[] = 
+                     {
+                       { RW, uint32, sizeof (UNS32), (void*)&canopenErrVAL }
+                     };
+
+/* index 0x6002 :   Mapped variable */
+                    UNS8 gene_SYNC_highestSubIndex_6002 = 0; // number of subindex - 1
+                    subindex gene_SYNC_Index6002[] = 
+                     {
+                       { RW, visible_string, sizeof (strTest), (void*)&strTest }
+                     };
+
+const indextable gene_SYNC_objdict[] = 
+{
+  DeclareIndexTableEntry(gene_SYNC_Index1000, 0x1000),
+  DeclareIndexTableEntry(gene_SYNC_Index1001, 0x1001),
+  DeclareIndexTableEntry(gene_SYNC_Index1005, 0x1005),
+  DeclareIndexTableEntry(gene_SYNC_Index1006, 0x1006),
+  DeclareIndexTableEntry(gene_SYNC_Index1007, 0x1007),
+  DeclareIndexTableEntry(gene_SYNC_Index1008, 0x1008),
+  DeclareIndexTableEntry(gene_SYNC_Index1009, 0x1009),
+  DeclareIndexTableEntry(gene_SYNC_Index100A, 0x100A),
+  DeclareIndexTableEntry(gene_SYNC_Index1016, 0x1016),
+  DeclareIndexTableEntry(gene_SYNC_Index1017, 0x1017),
+  DeclareIndexTableEntry(gene_SYNC_Index1018, 0x1018),
+  DeclareIndexTableEntry(gene_SYNC_Index1200, 0x1200),
+  DeclareIndexTableEntry(gene_SYNC_Index1280, 0x1280),
+  DeclareIndexTableEntry(gene_SYNC_Index1400, 0x1400),
+  DeclareIndexTableEntry(gene_SYNC_Index1401, 0x1401),
+  DeclareIndexTableEntry(gene_SYNC_Index1402, 0x1402),
+  DeclareIndexTableEntry(gene_SYNC_Index1600, 0x1600),
+  DeclareIndexTableEntry(gene_SYNC_Index1601, 0x1601),
+  DeclareIndexTableEntry(gene_SYNC_Index1602, 0x1602),
+  DeclareIndexTableEntry(gene_SYNC_Index1800, 0x1800),
+  DeclareIndexTableEntry(gene_SYNC_Index1801, 0x1801),
+  DeclareIndexTableEntry(gene_SYNC_Index1802, 0x1802),
+  DeclareIndexTableEntry(gene_SYNC_Index1A00, 0x1A00),
+  DeclareIndexTableEntry(gene_SYNC_Index1A01, 0x1A01),
+  DeclareIndexTableEntry(gene_SYNC_Index1A02, 0x1A02),
+  DeclareIndexTableEntry(gene_SYNC_Index2000, 0x2000),
+  DeclareIndexTableEntry(gene_SYNC_Index6000, 0x6000),
+  DeclareIndexTableEntry(gene_SYNC_Index6001, 0x6001),
+  DeclareIndexTableEntry(gene_SYNC_Index6002, 0x6002),
+};
+
+// To count at which received SYNC a PDO must be sent.
+// Even if no pdoTransmit are defined, at least one entry is computed
+// for compilations issues.
+UNS8 gene_SYNC_count_sync[1] = {0, };
+
+quick_index gene_SYNC_firstIndex = {
+    SDO_SVR : 11,
+    SDO_CLT : 12,
+    PDO_RCV : 13,
+    PDO_RCV_MAP : 16,
+    PDO_TRS : 19,
+    PDO_TRS_MAP : 22
+}
+
+quick_index gene_SYNC_lastIndex{
+    SDO_SVR : 11,
+    SDO_CLT : 12,
+    PDO_RCV : 15,
+    PDO_RCV_MAP : 18,
+    PDO_TRS : 21,
+    PDO_TRS_MAP : 24
+}
+
+UNS16 gene_SYNC_ObjdictSize = sizeof(gene_SYNC_objdict)/sizeof(gene_SYNC_objdict[0]); 
+
diff --git a/app/cantest/canfestival/applislave/muj_objdict.c b/app/cantest/canfestival/applislave/muj_objdict.c
new file mode 100644 (file)
index 0000000..7380110
--- /dev/null
@@ -0,0 +1,574 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+#include "objdict.h"
+
+/**************************************************************************/
+/* Declaration of the mapped variables                                    */
+/**************************************************************************/
+UNS8 seconds = 0;              // Mapped at index 0x2000, subindex 0x01
+UNS8 minutes = 0;              // Mapped at index 0x2000, subindex 0x02
+UNS8 hours = 0;                // Mapped at index 0x2000, subindex 0x03
+UNS8 day = 0;          // Mapped at index 0x2000, subindex 0x04
+UNS32 canopenErrNB = 0;                // Mapped at index 0x6000, subindex 0x00
+UNS32 canopenErrVAL = 0;               // Mapped at index 0x6001, subindex 0x00
+UNS8 strTest[10] = 0;          // Mapped at index 0x6002, subindex 0x00
+
+/**************************************************************************/
+/* Declaration of the value range types                                   */
+/**************************************************************************/
+
+
+
+UNS32 gene_SYNC_valueRangeTest (UNS8 typeValue, UNS32 unsValue, REAL32 realValue)
+{
+  switch (typeValue) {
+  }
+  return 0;
+}
+
+
+/**************************************************************************/
+/* The node id                                                            */
+/**************************************************************************/
+/* node_id default value. 
+   This default value is deprecated.
+   You should always overwrite this by using the function setNodeId(UNS8 nodeId) in your C code.
+*/
+#define NODE_ID 0x03
+UNS8 gene_SYNC_bDeviceNodeId = NODE_ID;
+
+
+//*****************************************************************************/
+/* Array of message processing information */
+/* Should not be modified */
+
+const UNS8 gene_SYNC_iam_a_slave = 1;
+
+  // Macros definition
+
+/* Beware : 
+index                 *must* be writen 4 numbers in hexa
+sub_index             *must* be writen 2 numbers in hexa
+size_variable_in_UNS8 *must* be writen 2 numbers in hexa
+*/
+#define PDO_MAP(index, sub_index, size_variable_in_bits)\
+0x ## index ## sub_index ## size_variable_in_bits
+
+/** This macro helps creating the object dictionary entries.
+ *  by calling this macro
+ *  it creates an entry in form of: 7 of entries, pointer to the entry. 
+ */
+#define DeclareIndexTableEntry(entryname, index)    { (subindex*)entryname,sizeof(entryname)/sizeof(entryname[0]), index}
+
+//$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$
+//
+//                       OBJECT DICTIONARY
+//                   
+//$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$
+// Make your change, depending of your application
+
+/* index 0x1000 :   Device type. 
+                    You have to change the value below, so
+                    it fits your canopen-slave-module */
+                    /* Not used, so, should not be modified */
+                    
+                    UNS32 gene_SYNC_obj1000 = 0;
+                    subindex gene_SYNC_Index1000[] =
+                    {
+                      { RO, uint32, sizeof(UNS32), (void*)&gene_SYNC_obj1000 }
+                    };
+
+/* index 0x1001 :   Error register. 
+                    Change the entries to fit your application 
+                    Not used, so, should not be modified */
+                    UNS8 gene_SYNC_obj1001 = 0x00000000;
+                    subindex gene_SYNC_Index1001[] =
+                    {
+                      { RO, uint8, sizeof(UNS8), (void*)&gene_SYNC_obj1001 }
+                    };
+
+/* index 0x1005 :   COB_ID SYNC */
+                    /* Should not be modified */
+                    UNS32 gene_SYNC_obj1005 = 0x00000080; // bit 30 = 1 : device can generate a SYNC message
+                                                // Beware, it is over written when the node 
+                                                // enters in reset mode
+                                                // See initResetMode() in init.c
+                    /*const*/ subindex gene_SYNC_Index1005[] =
+                    {
+                      { RW, uint32, sizeof(UNS32), (void*)&gene_SYNC_obj1005 }
+                    };
+
+/* index 0x1006 :   SYNC period */
+                    // For producing the SYNC signal every n micro-seconds.
+                    // Put 0 to not producing SYNC
+                    /*const*/ UNS32 gene_SYNC_obj1006 = 0x0; 
+                                         // Default 0 to not produce SYNC //
+                                         // Beware, it is over written when the 
+                                         // node enters in reset mode.
+                                         // See initResetMode() in init.c
+                    /*const*/ subindex gene_SYNC_Index1006[] =
+                    {
+                      { RW, uint32, sizeof(UNS32), (void*)&gene_SYNC_obj1006 }
+                    };
+
+/* index 0x1007 :   Synchronous Window Length
+                    Seems to be needed by DS401 to generate the SYNC signal ! */
+                    /*const*/ UNS32 gene_SYNC_obj1007 = 0x0; /* Default 0 */
+                    /*const*/ subindex gene_SYNC_Index1007[] =
+                    {
+                      { RW, uint32, sizeof(UNS32), (void*)&gene_SYNC_obj1007 }
+                    };
+
+                    TIMER_HANDLE gene_SYNC_heartBeatTimers[1];
+                    UNS32 gene_SYNC_obj1016[1]; 
+                    UNS8 gene_SYNC_obj1016_cnt = 0;
+                    subindex gene_SYNC_Index1016[0];
+/* index 0x1008 :   Manufacturer device name */
+                    UNS8 gene_SYNC_obj1008[] = "Appli_Slave_HC12"; /* Default 0 */
+                    subindex gene_SYNC_Index1008[] =
+                    {
+                      { RO, uint32, sizeof(gene_SYNC_obj1008), (void*)&gene_SYNC_obj1008 }
+                    };
+
+/* index 0x1009 :   Manufacturer hardware version */
+                    UNS8 gene_SYNC_obj1009[] = "__DATE__"; /* Default 0 */
+                    subindex gene_SYNC_Index1009[] =
+                    {
+                      { RO, uint32, sizeof(gene_SYNC_obj1009), (void*)&gene_SYNC_obj1009 }
+                    };
+
+/* index 0x100A :   Manufacturer software version */
+                    UNS8 gene_SYNC_obj100A[] = __TIME__; /* Default 0 */
+                    subindex gene_SYNC_Index100A[] =
+                    {
+                      { RO, uint32, gene_SYNC_sizeof(obj100A), (void*)&gene_SYNC_obj100A}
+                    };
+
+
+                    TIMER_HANDLE gene_SYNC_heartBeatTimers[1] = {TIMER_NONE,};
+/* index 0x1016 :   HeartBeat consumers 
+                    The nodes which can send a heartbeat */ 
+                    UNS32 gene_SYNC_obj1016[] = {// Consumer time for each node 
+                    0x00000000}; // Format 0x00NNTTTT (N=Node T=time in ms)
+
+                    UNS8 gene_SYNC_obj1016_cnt = 1; // 1 nodes could send me
+                                                  // their heartbeat.
+                    subindex gene_SYNC_Index1016[] = 
+                    {
+                      { RO, uint8, sizeof(UNS8), (void*)&gene_SYNC_obj1016_cnt },
+                      { RW, uint32, sizeof(UNS32), (void*)&gene_SYNC_obj1016[0] }
+                    }; 
+
+/* index 0x1017 :   Heartbeat producer                    
+                    Every HBProducerTime, the node sends its heartbeat */
+                    UNS16 gene_SYNC_obj1017 = 0; //HBProducerTime in ms. If 0 : not activated 
+                                                     // Beware, it is over written when the 
+                                                     // node enters in reset mode.
+                                                     // See initResetMode() in init.c
+                    subindex gene_SYNC_Index1017[] =
+                    {
+                     { RW, uint16, sizeof(UNS16), &gene_SYNC_obj1017 }
+                    };
+
+/* index 0x1018 :   Identity object */
+                    /** index 1018: identify object. Adjust the entries for your node/company
+                    */
+                    /* Values can be modified */
+
+                    s_identity gene_SYNC_obj1018 =
+                    {
+                      4,       // number of supported entries
+                      0,  // Vendor-ID (given by the can-cia)
+                      0,  // Product Code
+                      0,  // Revision number
+                      0  // serial number
+                    };
+
+                    subindex gene_SYNC_Index1018[] =
+                    {
+                      { RO, uint8,  sizeof(UNS8),  (void*)&gene_SYNC_obj1018.count },
+                      { RO, uint32, sizeof(UNS32), (void*)&gene_SYNC_obj1018.vendor_id},
+                      { RO, uint32, sizeof(UNS32), (void*)&gene_SYNC_obj1018.product_code},
+                      { RO, uint32, sizeof(UNS32), (void*)&gene_SYNC_obj1018.revision_number},
+                      { RO, uint32, sizeof(UNS32), (void*)&gene_SYNC_obj1018.serial_number}
+                    };
+
+/* index 0x1200 :   The SDO Server parameters */
+                    /* BEWARE You cannot define more than one SDO server */
+                    /* The values should not be modified here, 
+                    but can be changed at runtime */
+                    // Beware that the default values that you could put here
+                    // will be over written at the initialisation of the node. 
+                    // See setNodeId() in init.c
+                    s_sdo_parameter gene_SYNC_obj1200  = 
+                      { 3,                   // Number of entries. Always 3 for the SDO               
+                        0x601,     // The cob_id transmited in CAN msg to the server     
+                        0x581,     // The cob_id received in CAN msg from the server  
+                        0x01      // The node id of the client. Should not be modified
+                      };
+                    subindex gene_SYNC_Index1200[] =
+                    {
+                      { RO, uint8,  sizeof( UNS8 ), (void*)&gene_SYNC_obj1200.count },
+                      { RO, uint32, sizeof( UNS32), (void*)&gene_SYNC_obj1200.cob_id_client },
+                      { RO, uint32, sizeof( UNS32), (void*)&gene_SYNC_obj1200.cob_id_server },
+                      { RW, uint8,  sizeof( UNS8),  (void*)&gene_SYNC_obj1200.node_id }
+                    };
+
+/* index 0x1280 :   SDO client parameter */
+                    s_sdo_parameter gene_SYNC_obj1280 = 
+                      { 3,     // Nb of entries 
+                        0x600, // cobid transmited to the server. The good value should be 0x600 + server nodeId
+                        0x580, // cobid received from the server. The good value should be 0x580 + server nodeId
+                        0x01  // server NodeId
+                      };
+                    subindex gene_SYNC_Index1280[] = 
+                      { 
+                        { RO, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1280.count },
+                        { RW, uint8, sizeof( UNS32 ), (void*)&gene_SYNC_obj1280.cob_id_client },
+                        { RW, uint8, sizeof( UNS32 ), (void*)&gene_SYNC_obj1280.cob_id_server },
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1280.node_id }
+                      }; 
+
+/* index 0x1400 :   PDO receive communication parameter */
+                    s_pdo_communication_parameter gene_SYNC_obj1400 = 
+                      { 2, // Largest subindex supported 
+                        0x0, // Default COBID (overwritten at init for index 0x1400 to 0x1403)
+                        253 // Transmission type. See objdictdef.h 
+                      };
+                    subindex gene_SYNC_Index1400[] = 
+                      { 
+                        { RO, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1400.count },
+                        { RW, uint8, sizeof( UNS32 ), (void*)&gene_SYNC_obj1400.cob_id },
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1400.type },
+                      }; 
+
+/* index 0x1401 :   PDO receive communication parameter */
+                    s_pdo_communication_parameter gene_SYNC_obj1401 = 
+                      { 2, // Largest subindex supported 
+                        0x0, // Default COBID (overwritten at init for index 0x1400 to 0x1403)
+                        253 // Transmission type. See objdictdef.h 
+                      };
+                    subindex gene_SYNC_Index1401[] = 
+                      { 
+                        { RO, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1401.count },
+                        { RW, uint8, sizeof( UNS32 ), (void*)&gene_SYNC_obj1401.cob_id },
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1401.type },
+                      }; 
+
+/* index 0x1402 :   PDO receive communication parameter */
+                    s_pdo_communication_parameter gene_SYNC_obj1402 = 
+                      { 2, // Largest subindex supported 
+                        0x0, // Default COBID (overwritten at init for index 0x1400 to 0x1403)
+                        253 // Transmission type. See objdictdef.h 
+                      };
+                    subindex gene_SYNC_Index1402[] = 
+                      { 
+                        { RO, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1402.count },
+                        { RW, uint8, sizeof( UNS32 ), (void*)&gene_SYNC_obj1402.cob_id },
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1402.type },
+                      }; 
+
+/* index 0x1600 :   PDO receive mapping parameter of PDO communication index 0x1400 */
+                    UNS8 gene_SYNC_obj1600_cnt = 0; // Number of mapped variables
+                    UNS32 gene_SYNC_obj1600_mappedVar[] = { 
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000
+                      };
+                    subindex gene_SYNC_Index1600[] = 
+                      { 
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1600_cnt },
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1600_mappedVar[0]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1600_mappedVar[1]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1600_mappedVar[2]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1600_mappedVar[3]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1600_mappedVar[4]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1600_mappedVar[5]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1600_mappedVar[6]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1600_mappedVar[7]}
+                      }; 
+
+/* index 0x1601 :   PDO receive mapping parameter of PDO communication index 0x1401 */
+                    UNS8 gene_SYNC_obj1601_cnt = 0; // Number of mapped variables
+                    UNS32 gene_SYNC_obj1601_mappedVar[] = { 
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000
+                      };
+                    subindex gene_SYNC_Index1601[] = 
+                      { 
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1601_cnt },
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1601_mappedVar[0]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1601_mappedVar[1]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1601_mappedVar[2]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1601_mappedVar[3]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1601_mappedVar[4]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1601_mappedVar[5]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1601_mappedVar[6]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1601_mappedVar[7]}
+                      }; 
+
+/* index 0x1602 :   PDO receive mapping parameter of PDO communication index 0x1402 */
+                    UNS8 gene_SYNC_obj1602_cnt = 0; // Number of mapped variables
+                    UNS32 gene_SYNC_obj1602_mappedVar[] = { 
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000
+                      };
+                    subindex gene_SYNC_Index1602[] = 
+                      { 
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1602_cnt },
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1602_mappedVar[0]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1602_mappedVar[1]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1602_mappedVar[2]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1602_mappedVar[3]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1602_mappedVar[4]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1602_mappedVar[5]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1602_mappedVar[6]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1602_mappedVar[7]}
+                      }; 
+
+/* index 0x1800 :   PDO transmit communication parameter */
+                    s_pdo_communication_parameter gene_SYNC_obj1800 = 
+                      { 2, // Largest subindex supported 
+                        0x0, // Default COBID (overwritten at init for index 0x1400 to 0x1403)
+                        253 // Transmission type. See objdictdef.h 
+                      };
+                    subindex gene_SYNC_Index1800[] = 
+                      { 
+                        { RO, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1800.count },
+                        { RW, uint8, sizeof( UNS32 ), (void*)&gene_SYNC_obj1800.cob_id },
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1800.type },
+                      }; 
+
+/* index 0x1801 :   PDO transmit communication parameter */
+                    s_pdo_communication_parameter gene_SYNC_obj1801 = 
+                      { 2, // Largest subindex supported 
+                        0x0, // Default COBID (overwritten at init for index 0x1400 to 0x1403)
+                        253 // Transmission type. See objdictdef.h 
+                      };
+                    subindex gene_SYNC_Index1801[] = 
+                      { 
+                        { RO, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1801.count },
+                        { RW, uint8, sizeof( UNS32 ), (void*)&gene_SYNC_obj1801.cob_id },
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1801.type },
+                      }; 
+
+/* index 0x1802 :   PDO transmit communication parameter */
+                    s_pdo_communication_parameter gene_SYNC_obj1802 = 
+                      { 2, // Largest subindex supported 
+                        0x0, // Default COBID (overwritten at init for index 0x1400 to 0x1403)
+                        253 // Transmission type. See objdictdef.h 
+                      };
+                    subindex gene_SYNC_Index1802[] = 
+                      { 
+                        { RO, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1802.count },
+                        { RW, uint8, sizeof( UNS32 ), (void*)&gene_SYNC_obj1802.cob_id },
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1802.type },
+                      }; 
+
+/* index 0x1A00 :   PDO transmit mapping parameter of PDO communication index 0x1800 */
+                    UNS8 gene_SYNC_obj1A00_cnt = 0; // Number of mapped variables
+                    UNS32 gene_SYNC_obj1A00_mappedVar[] = { 
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000
+                      };
+                    subindex gene_SYNC_Index1A00[] = 
+                      { 
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1A00_cnt },
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A00_mappedVar[0]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A00_mappedVar[1]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A00_mappedVar[2]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A00_mappedVar[3]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A00_mappedVar[4]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A00_mappedVar[5]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A00_mappedVar[6]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A00_mappedVar[7]}
+                      }; 
+
+/* index 0x1A01 :   PDO transmit mapping parameter of PDO communication index 0x1801 */
+                    UNS8 gene_SYNC_obj1A01_cnt = 0; // Number of mapped variables
+                    UNS32 gene_SYNC_obj1A01_mappedVar[] = { 
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000
+                      };
+                    subindex gene_SYNC_Index1A01[] = 
+                      { 
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1A01_cnt },
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A01_mappedVar[0]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A01_mappedVar[1]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A01_mappedVar[2]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A01_mappedVar[3]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A01_mappedVar[4]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A01_mappedVar[5]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A01_mappedVar[6]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A01_mappedVar[7]}
+                      }; 
+
+/* index 0x1A02 :   PDO transmit mapping parameter of PDO communication index 0x1802 */
+                    UNS8 gene_SYNC_obj1A02_cnt = 0; // Number of mapped variables
+                    UNS32 gene_SYNC_obj1A02_mappedVar[] = { 
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000
+                      };
+                    subindex gene_SYNC_Index1A02[] = 
+                      { 
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1A02_cnt },
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A02_mappedVar[0]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A02_mappedVar[1]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A02_mappedVar[2]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A02_mappedVar[3]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A02_mappedVar[4]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A02_mappedVar[5]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A02_mappedVar[6]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A02_mappedVar[7]}
+                      }; 
+
+
+/* index 0x2000 :   Mapped variable */
+                    UNS8 gene_SYNC_highestSubIndex_2000 = 4; // number of subindex - 1
+                    subindex gene_SYNC_Index2000[] = 
+                     {
+                       { RO, uint8, sizeof (UNS8), (void*)&gene_SYNC_highestSubIndex_2000 },
+                       { RW, uint8, sizeof (UNS8), (void*)&seconds },
+                       { RW, uint8, sizeof (UNS8), (void*)&minutes },
+                       { RW, uint8, sizeof (UNS8), (void*)&hours },
+                       { RW, uint8, sizeof (UNS8), (void*)&day }
+                     };
+
+/* index 0x6000 :   Mapped variable */
+                    UNS8 gene_SYNC_highestSubIndex_6000 = 0; // number of subindex - 1
+                    subindex gene_SYNC_Index6000[] = 
+                     {
+                       { RW, uint32, sizeof (UNS32), (void*)&canopenErrNB }
+                     };
+
+/* index 0x6001 :   Mapped variable */
+                    UNS8 gene_SYNC_highestSubIndex_6001 = 0; // number of subindex - 1
+                    subindex gene_SYNC_Index6001[] = 
+                     {
+                       { RW, uint32, sizeof (UNS32), (void*)&canopenErrVAL }
+                     };
+
+/* index 0x6002 :   Mapped variable */
+                    UNS8 gene_SYNC_highestSubIndex_6002 = 0; // number of subindex - 1
+                    subindex gene_SYNC_Index6002[] = 
+                     {
+                       { RW, visible_string, sizeof (strTest), (void*)&strTest }
+                     };
+
+const indextable gene_SYNC_objdict[] = 
+{
+  DeclareIndexTableEntry(gene_SYNC_Index1000, 0x1000),
+  DeclareIndexTableEntry(gene_SYNC_Index1001, 0x1001),
+  DeclareIndexTableEntry(gene_SYNC_Index1005, 0x1005),
+  DeclareIndexTableEntry(gene_SYNC_Index1006, 0x1006),
+  DeclareIndexTableEntry(gene_SYNC_Index1007, 0x1007),
+  DeclareIndexTableEntry(gene_SYNC_Index1008, 0x1008),
+  DeclareIndexTableEntry(gene_SYNC_Index1009, 0x1009),
+  DeclareIndexTableEntry(gene_SYNC_Index100A, 0x100A),
+  DeclareIndexTableEntry(gene_SYNC_Index1016, 0x1016),
+  DeclareIndexTableEntry(gene_SYNC_Index1017, 0x1017),
+  DeclareIndexTableEntry(gene_SYNC_Index1018, 0x1018),
+  DeclareIndexTableEntry(gene_SYNC_Index1200, 0x1200),
+  DeclareIndexTableEntry(gene_SYNC_Index1280, 0x1280),
+  DeclareIndexTableEntry(gene_SYNC_Index1400, 0x1400),
+  DeclareIndexTableEntry(gene_SYNC_Index1401, 0x1401),
+  DeclareIndexTableEntry(gene_SYNC_Index1402, 0x1402),
+  DeclareIndexTableEntry(gene_SYNC_Index1600, 0x1600),
+  DeclareIndexTableEntry(gene_SYNC_Index1601, 0x1601),
+  DeclareIndexTableEntry(gene_SYNC_Index1602, 0x1602),
+  DeclareIndexTableEntry(gene_SYNC_Index1800, 0x1800),
+  DeclareIndexTableEntry(gene_SYNC_Index1801, 0x1801),
+  DeclareIndexTableEntry(gene_SYNC_Index1802, 0x1802),
+  DeclareIndexTableEntry(gene_SYNC_Index1A00, 0x1A00),
+  DeclareIndexTableEntry(gene_SYNC_Index1A01, 0x1A01),
+  DeclareIndexTableEntry(gene_SYNC_Index1A02, 0x1A02),
+  DeclareIndexTableEntry(gene_SYNC_Index2000, 0x2000),
+  DeclareIndexTableEntry(gene_SYNC_Index6000, 0x6000),
+  DeclareIndexTableEntry(gene_SYNC_Index6001, 0x6001),
+  DeclareIndexTableEntry(gene_SYNC_Index6002, 0x6002),
+};
+
+// To count at which received SYNC a PDO must be sent.
+// Even if no pdoTransmit are defined, at least one entry is computed
+// for compilations issues.
+UNS8 gene_SYNC_count_sync[1] = {0, };
+
+quick_index gene_SYNC_firstIndex = {
+    SDO_SVR : 11,
+    SDO_CLT : 12,
+    PDO_RCV : 13,
+    PDO_RCV_MAP : 16,
+    PDO_TRS : 19,
+    PDO_TRS_MAP : 22
+}
+
+quick_index gene_SYNC_lastIndex{
+    SDO_SVR : 11,
+    SDO_CLT : 12,
+    PDO_RCV : 15,
+    PDO_RCV_MAP : 18,
+    PDO_TRS : 21,
+    PDO_TRS_MAP : 24
+}
+
+UNS16 gene_SYNC_ObjdictSize = sizeof(gene_SYNC_objdict)/sizeof(gene_SYNC_objdict[0]); 
+
+CO_Data gene_SYNC_Data = CANOPEN_NODE_DATA_INITIALIZER(gene_SYNC);
+
diff --git a/app/cantest/canfestival/applislave/objdict-sync.c b/app/cantest/canfestival/applislave/objdict-sync.c
new file mode 100644 (file)
index 0000000..c4e249e
--- /dev/null
@@ -0,0 +1,233 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+#include "objdict.h"
+
+/**************************************************************************/
+/* Declaration of the mapped variables                                    */
+/**************************************************************************/
+
+/**************************************************************************/
+/* Declaration of the value range types                                   */
+/**************************************************************************/
+
+
+
+UNS32 gene_SYNC_valueRangeTest (UNS8 typeValue, UNS32 unsValue, REAL32 realValue)
+{
+  switch (typeValue) {
+  }
+  return 0;
+}
+
+
+/**************************************************************************/
+/* The node id                                                            */
+/**************************************************************************/
+/* node_id default value. 
+   This default value is deprecated.
+   You should always overwrite this by using the function setNodeId(UNS8 nodeId) in your C code.
+*/
+#define NODE_ID 0x03
+UNS8 gene_SYNC_bDeviceNodeId = NODE_ID;
+
+
+//*****************************************************************************/
+/* Array of message processing information */
+/* Should not be modified */
+
+const UNS8 gene_SYNC_iam_a_slave = 1;
+
+  // Macros definition
+
+/* Beware : 
+index                 *must* be writen 4 numbers in hexa
+sub_index             *must* be writen 2 numbers in hexa
+size_variable_in_UNS8 *must* be writen 2 numbers in hexa
+*/
+#define PDO_MAP(index, sub_index, size_variable_in_bits)\
+0x ## index ## sub_index ## size_variable_in_bits
+
+/** This macro helps creating the object dictionary entries.
+ *  by calling this macro
+ *  it creates an entry in form of: 7 of entries, pointer to the entry. 
+ */
+#define DeclareIndexTableEntry(entryname, index)    { (subindex*)entryname,sizeof(entryname)/sizeof(entryname[0]), index}
+
+//$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$
+//
+//                       OBJECT DICTIONARY
+//                   
+//$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$
+// Make your change, depending of your application
+
+/* index 0x1000 :   Device type. 
+                    You have to change the value below, so
+                    it fits your canopen-slave-module */
+                    /* Not used, so, should not be modified */
+                    
+                    UNS32 gene_SYNC_obj1000 = 0;
+                    subindex gene_SYNC_Index1000[] =
+                    {
+                      { RO, uint32, sizeof(UNS32), (void*)&gene_SYNC_obj1000 }
+                    };
+
+/* index 0x1001 :   Error register. 
+                    Change the entries to fit your application 
+                    Not used, so, should not be modified */
+                    UNS8 gene_SYNC_obj1001 = 0x00000000;
+                    subindex gene_SYNC_Index1001[] =
+                    {
+                      { RO, uint8, sizeof(UNS8), (void*)&gene_SYNC_obj1001 }
+                    };
+
+/* index 0x1005 :   COB_ID SYNC */
+                    /* Should not be modified */
+                    UNS32 gene_SYNC_obj1005 = 0x40000080; // bit 30 = 1 : device can generate a SYNC message
+                                                // Beware, it is over written when the node 
+                                                // enters in reset mode
+                                                // See initResetMode() in init.c
+                    subindex gene_SYNC_Index1005[] =
+                    {
+                      { RW, uint32, sizeof(UNS32), (void*)&gene_SYNC_obj1005 }
+                    };
+
+/* index 0x1006 :   SYNC period */
+                    // For producing the SYNC signal every n micro-seconds.
+                    // Put 0 to not producing SYNC
+                    UNS32 gene_SYNC_obj1006 = 0x000186A0; 
+                                         // Default 0 to not produce SYNC //
+                                         // Beware, it is over written when the 
+                                         // node enters in reset mode.
+                                         // See initResetMode() in init.c
+                    subindex gene_SYNC_Index1006[] =
+                    {
+                      { RW, uint32, sizeof(UNS32), (void*)&gene_SYNC_obj1006 }
+                    };
+
+
+                    TIMER_HANDLE gene_SYNC_heartBeatTimers[1];
+                    UNS32 gene_SYNC_obj1016[1]; 
+                    UNS8 gene_SYNC_obj1016_cnt = 0;
+                    subindex gene_SYNC_Index1016[0];
+
+                    UNS16 gene_SYNC_obj1017 = 0x0000;
+/* index 0x1018 :   Identity object */
+                    /** index 1018: identify object. Adjust the entries for your node/company
+                    */
+                    /* Values can be modified */
+
+                    s_identity gene_SYNC_obj1018 =
+                    {
+                      4,       // number of supported entries
+                      0,  // Vendor-ID (given by the can-cia)
+                      0,  // Product Code
+                      0,  // Revision number
+                      0  // serial number
+                    };
+
+                    subindex gene_SYNC_Index1018[] =
+                    {
+                      { RO, uint8,  sizeof(UNS8),  (void*)&gene_SYNC_obj1018.count },
+                      { RO, uint32, sizeof(UNS32), (void*)&gene_SYNC_obj1018.vendor_id},
+                      { RO, uint32, sizeof(UNS32), (void*)&gene_SYNC_obj1018.product_code},
+                      { RO, uint32, sizeof(UNS32), (void*)&gene_SYNC_obj1018.revision_number},
+                      { RO, uint32, sizeof(UNS32), (void*)&gene_SYNC_obj1018.serial_number}
+                    };
+
+/* index 0x1200 :   The SDO Server parameters */
+                    /* BEWARE You cannot define more than one SDO server */
+                    /* The values should not be modified here, 
+                    but can be changed at runtime */
+                    // Beware that the default values that you could put here
+                    // will be over written at the initialisation of the node. 
+                    // See setNodeId() in init.c
+                    s_sdo_parameter gene_SYNC_obj1200  = 
+                      { 3,                   // Number of entries. Always 3 for the SDO           
+                        0x000,     // The cob_id transmited in CAN msg to the server     
+                        0x000,     // The cob_id received in CAN msg from the server  
+                        0x03      // The node id of the client. Should not be modified
+                      };
+                    subindex gene_SYNC_Index1200[] =
+                    {
+                      { RO, uint8,  sizeof( UNS8 ), (void*)&gene_SYNC_obj1200.count },
+                      { RO, uint32, sizeof( UNS32), (void*)&gene_SYNC_obj1200.cob_id_client },
+                      { RO, uint32, sizeof( UNS32), (void*)&gene_SYNC_obj1200.cob_id_server },
+                      { RW, uint8,  sizeof( UNS8),  (void*)&gene_SYNC_obj1200.node_id }
+                    };
+
+/* index 0x1280 :   SDO client parameter */
+                    s_sdo_parameter gene_SYNC_obj1280 = 
+                      { 3,     // Nb of entries 
+                        0x000, // cobid transmited to the server. The good value should be 0x600 + server nodeId
+                        0x000, // cobid received from the server. The good value should be 0x580 + server nodeId
+                        0x00  // server NodeId
+                      };
+                    subindex gene_SYNC_Index1280[] = 
+                      { 
+                        { RO, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1280.count },
+                        { RW, uint8, sizeof( UNS32 ), (void*)&gene_SYNC_obj1280.cob_id_client },
+                        { RW, uint8, sizeof( UNS32 ), (void*)&gene_SYNC_obj1280.cob_id_server },
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1280.node_id }
+                      }; 
+
+
+const indextable gene_SYNC_objdict[] = 
+{
+  DeclareIndexTableEntry(gene_SYNC_Index1000, 0x1000),
+  DeclareIndexTableEntry(gene_SYNC_Index1001, 0x1001),
+  DeclareIndexTableEntry(gene_SYNC_Index1005, 0x1005),
+  DeclareIndexTableEntry(gene_SYNC_Index1006, 0x1006),
+  DeclareIndexTableEntry(gene_SYNC_Index1018, 0x1018),
+  DeclareIndexTableEntry(gene_SYNC_Index1200, 0x1200),
+  DeclareIndexTableEntry(gene_SYNC_Index1280, 0x1280),
+};
+
+// To count at which received SYNC a PDO must be sent.
+// Even if no pdoTransmit are defined, at least one entry is computed
+// for compilations issues.
+UNS8 gene_SYNC_count_sync[1] = {0, };
+
+quick_index gene_SYNC_firstIndex = {
+    SDO_SVR : 5,
+    SDO_CLT : 6,
+    PDO_RCV : 0,
+    PDO_RCV_MAP : 0,
+    PDO_TRS : 0,
+    PDO_TRS_MAP : 0
+};
+
+quick_index gene_SYNC_lastIndex = {
+    SDO_SVR : 5,
+    SDO_CLT : 6,
+    PDO_RCV : 0,
+    PDO_RCV_MAP : 0,
+    PDO_TRS : 0,
+    PDO_TRS_MAP : 0
+};
+
+UNS16 gene_SYNC_ObjdictSize = sizeof(gene_SYNC_objdict)/sizeof(gene_SYNC_objdict[0]); 
+
+CO_Data gene_SYNC_Data = CANOPEN_NODE_DATA_INITIALIZER(gene_SYNC);
+
diff --git a/app/cantest/canfestival/applislave/objdict.c b/app/cantest/canfestival/applislave/objdict.c
new file mode 100644 (file)
index 0000000..e25b4f0
--- /dev/null
@@ -0,0 +1,588 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+#include "objdict.h"
+
+/**************************************************************************/
+/* Declaration of the mapped variables                                    */
+/**************************************************************************/
+UNS8 seconds = 0;              // Mapped at index 0x2000, subindex 0x01
+UNS8 minutes = 0;              // Mapped at index 0x2000, subindex 0x02
+UNS8 hours = 0;                // Mapped at index 0x2000, subindex 0x03
+UNS8 day = 0;          // Mapped at index 0x2000, subindex 0x04
+UNS32 canopenErrNB = 0;                // Mapped at index 0x6000, subindex 0x00
+UNS32 canopenErrVAL = 0;               // Mapped at index 0x6001, subindex 0x00
+UNS8 strTest[10] = "";         // Mapped at index 0x6002, subindex 0x00
+
+UNS16 casovac_h;       // Mapped at index 0x2001, subindex 0x01
+UNS16 casovac_l;       // Mapped at index 0x2001, subindex 0x02
+UNS32 casovac = 0;
+UNS8  interval = 15;
+UNS8  ledky = 0;
+/**************************************************************************/
+/* Declaration of the value range types                                   */
+/**************************************************************************/
+
+
+
+UNS32 gene_SYNC_valueRangeTest (UNS8 typeValue, UNS32 unsValue, REAL32 realValue)
+{
+  switch (typeValue) {
+  }
+  return 0;
+}
+
+
+/**************************************************************************/
+/* The node id                                                            */
+/**************************************************************************/
+/* node_id default value. 
+   This default value is deprecated.
+   You should always overwrite this by using the function setNodeId(UNS8 nodeId) in your C code.
+*/
+#define NODE_ID 0x03
+UNS8 gene_SYNC_bDeviceNodeId = NODE_ID;
+
+
+//*****************************************************************************/
+/* Array of message processing information */
+/* Should not be modified */
+
+const UNS8 gene_SYNC_iam_a_slave = 1;
+
+  // Macros definition
+
+/* Beware : 
+index                 *must* be writen 4 numbers in hexa
+sub_index             *must* be writen 2 numbers in hexa
+size_variable_in_UNS8 *must* be writen 2 numbers in hexa
+*/
+#define PDO_MAP(index, sub_index, size_variable_in_bits)\
+0x ## index ## sub_index ## size_variable_in_bits
+
+/** This macro helps creating the object dictionary entries.
+ *  by calling this macro
+ *  it creates an entry in form of: 7 of entries, pointer to the entry. 
+ */
+#define DeclareIndexTableEntry(entryname, index)    { (subindex*)entryname,sizeof(entryname)/sizeof(entryname[0]), index}
+
+//$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$
+//
+//                       OBJECT DICTIONARY
+//                   
+//$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$
+// Make your change, depending of your application
+
+/* index 0x1000 :   Device type. 
+                    You have to change the value below, so
+                    it fits your canopen-slave-module */
+                    /* Not used, so, should not be modified */
+                    
+                    UNS32 gene_SYNC_obj1000 = 0;
+                    subindex gene_SYNC_Index1000[] =
+                    {
+                      { RO, uint32, sizeof(UNS32), (void*)&gene_SYNC_obj1000 }
+                    };
+
+/* index 0x1001 :   Error register. 
+                    Change the entries to fit your application 
+                    Not used, so, should not be modified */
+                    UNS8 gene_SYNC_obj1001 = 0x00000000;
+                    subindex gene_SYNC_Index1001[] =
+                    {
+                      { RO, uint8, sizeof(UNS8), (void*)&gene_SYNC_obj1001 }
+                    };
+
+/* index 0x1005 :   COB_ID SYNC */
+                    /* Should not be modified */
+                    UNS32 gene_SYNC_obj1005 = 0x00000080; // bit 30 = 1 : device can generate a SYNC message
+                                                // Beware, it is over written when the node
+                                                // enters in reset mode
+                                                // See initResetMode() in init.c
+                    /*const*/ subindex gene_SYNC_Index1005[] =
+                    {
+                      { RW, uint32, sizeof(UNS32), (void*)&gene_SYNC_obj1005 }
+                    };
+
+/* index 0x1006 :   SYNC period */
+                    // For producing the SYNC signal every n micro-seconds.
+                    // Put O to not producing SYNC
+                    /*const*/ UNS32 gene_SYNC_obj1006 = 0x0;
+                                         // Default 0 to not produce SYNC //
+                                         // Beware, it is over written when the
+                                         // node enters in reset mode.
+                                         // See initResetMode() in init.c
+                    /*const*/ subindex gene_SYNC_Index1006[] =
+                    {
+                      { RW, uint32, sizeof(UNS32), (void*)&gene_SYNC_obj1006 }
+                    };
+
+/* index 0x1007 :   Synchronous Window Length
+                    Seems to be needed by DS401 to generate the SYNC signal ! */
+                    /*const*/ UNS32 gene_SYNC_obj1007 = 0x0; /* Default 0 */
+                    /*const*/ subindex gene_SYNC_Index1007[] =
+                    {
+                      { RW, uint32, sizeof(UNS32), (void*)&gene_SYNC_obj1007 }
+                    };
+
+/* index 0x1008 :   Manufacturer device name */
+                    UNS8 gene_SYNC_obj1008[] = "Appli_Slave_HC12"; /* Default 0 */
+                    subindex gene_SYNC_Index1008[] =
+                    {
+                      { RO, uint32, sizeof(gene_SYNC_obj1008), (void*)&gene_SYNC_obj1008 }
+                    };
+
+/* index 0x1009 :   Manufacturer hardware version */
+                    UNS8 gene_SYNC_obj1009[] = "__DATE__"; /* Default 0 */
+                    subindex gene_SYNC_Index1009[] =
+                    {
+                      { RO, uint32, sizeof(gene_SYNC_obj1009), (void*)&gene_SYNC_obj1009 }
+                    };
+
+/* index 0x100A :   Manufacturer software version */
+                    UNS8 gene_SYNC_obj100A[] = __TIME__; /* Default 0 */
+                    subindex gene_SYNC_Index100A[] =
+                    {
+                      { RO, uint32, sizeof(gene_SYNC_obj100A), (void*)&gene_SYNC_obj100A}
+                    };
+
+/* index 0x1016 :   HeartBeat consumers 
+                    The nodes which can send a heartbeat */ 
+                    UNS32 gene_SYNC_obj1016[] = {// Consumer time for each node 
+                    0x00000000}; // Format 0x00NNTTTT (N=Node T=time in ms)
+
+                    UNS8 gene_SYNC_obj1016_cnt = 1; // 1 nodes could send me
+                                                  // their heartbeat.
+                    subindex gene_SYNC_Index1016[] = 
+                    {
+                      { RO, uint8, sizeof(UNS8), (void*)&gene_SYNC_obj1016_cnt },
+                      { RW, uint32, sizeof(UNS32), (void*)&gene_SYNC_obj1016[0] }
+                    };
+                   TIMER_HANDLE gene_SYNC_heartBeatTimers[1] = {TIMER_NONE,};
+
+/* index 0x1017 :   Heartbeat producer                    
+                    Every HBProducerTime, the node sends its heartbeat */
+                    UNS16 gene_SYNC_obj1017 = 0; //HBProducerTime in ms. If 0 : not activated 
+                                                     // Beware, it is over written when the 
+                                                     // node enters in reset mode.
+                                                     // See initResetMode() in init.c
+                    subindex gene_SYNC_Index1017[] =
+                    {
+                     { RW, uint16, sizeof(UNS16), &gene_SYNC_obj1017 }
+                    };
+
+/* index 0x1018 :   Identity object */
+                    /** index 1018: identify object. Adjust the entries for your node/company
+                    */
+                    /* Values can be modified */
+
+                    s_identity gene_SYNC_obj1018 =
+                    {
+                      4,       // number of supported entries
+                      0,  // Vendor-ID (given by the can-cia)
+                      0,  // Product Code
+                      0,  // Revision number
+                      0  // serial number
+                    };
+
+                    subindex gene_SYNC_Index1018[] =
+                    {
+                      { RO, uint8,  sizeof(UNS8),  (void*)&gene_SYNC_obj1018.count },
+                      { RO, uint32, sizeof(UNS32), (void*)&gene_SYNC_obj1018.vendor_id},
+                      { RO, uint32, sizeof(UNS32), (void*)&gene_SYNC_obj1018.product_code},
+                      { RO, uint32, sizeof(UNS32), (void*)&gene_SYNC_obj1018.revision_number},
+                      { RO, uint32, sizeof(UNS32), (void*)&gene_SYNC_obj1018.serial_number}
+                    };
+
+/* index 0x1200 :   The SDO Server parameters */
+                    /* BEWARE You cannot define more than one SDO server */
+                    /* The values should not be modified here, 
+                    but can be changed at runtime */
+                    // Beware that the default values that you could put here
+                    // will be over written at the initialisation of the node. 
+                    // See setNodeId() in init.c
+                    s_sdo_parameter gene_SYNC_obj1200  = 
+                      { 3,                   // Number of entries. Always 3 for the SDO               
+                        0x601,     // The cob_id transmited in CAN msg to the server     
+                        0x581,     // The cob_id received in CAN msg from the server  
+                        0x01      // The node id of the client. Should not be modified
+                      };
+                    subindex gene_SYNC_Index1200[] =
+                    {
+                      { RO, uint8,  sizeof( UNS8 ), (void*)&gene_SYNC_obj1200.count },
+                      { RO, uint32, sizeof( UNS32), (void*)&gene_SYNC_obj1200.cob_id_client },
+                      { RO, uint32, sizeof( UNS32), (void*)&gene_SYNC_obj1200.cob_id_server },
+                      { RW, uint8,  sizeof( UNS8),  (void*)&gene_SYNC_obj1200.node_id }
+                    };
+
+/* index 0x1280 :   SDO client parameter */
+                    s_sdo_parameter gene_SYNC_obj1280 = 
+                      { 3,     // Nb of entries 
+                        0x600, // cobid transmited to the server. The good value should be 0x600 + server nodeId
+                        0x580, // cobid received from the server. The good value should be 0x580 + server nodeId
+                        0x01  // server NodeId
+                      };
+                    subindex gene_SYNC_Index1280[] = 
+                      { 
+                        { RO, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1280.count },
+                        { RW, uint8, sizeof( UNS32 ), (void*)&gene_SYNC_obj1280.cob_id_client },
+                        { RW, uint8, sizeof( UNS32 ), (void*)&gene_SYNC_obj1280.cob_id_server },
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1280.node_id }
+                      }; 
+
+/* index 0x1400 :   PDO receive communication parameter */
+                    s_pdo_communication_parameter gene_SYNC_obj1400 = 
+                      { 2, // Largest subindex supported 
+                        0x510, // Default COBID (overwritten at init for index 0x1400 to 0x1403)
+                        255 // Transmission type. See objdictdef.h 
+                      };
+                    subindex gene_SYNC_Index1400[] = 
+                      { 
+                        { RO, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1400.count },
+                        { RW, uint8, sizeof( UNS32 ), (void*)&gene_SYNC_obj1400.cob_id },
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1400.type },
+                      }; 
+
+/* index 0x1401 :   PDO receive communication parameter */
+                    s_pdo_communication_parameter gene_SYNC_obj1401 = 
+                      { 2, // Largest subindex supported 
+                        0x511, // Default COBID (overwritten at init for index 0x1400 to 0x1403)
+                        TRANS_EVENT // Transmission type. See objdictdef.h 
+                      };
+                    subindex gene_SYNC_Index1401[] = 
+                      { 
+                        { RO, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1401.count },
+                        { RW, uint8, sizeof( UNS32 ), (void*)&gene_SYNC_obj1401.cob_id },
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1401.type },
+                      }; 
+
+/* index 0x1402 :   PDO receive communication parameter */
+                    s_pdo_communication_parameter gene_SYNC_obj1402 = 
+                      { 2, // Largest subindex supported 
+                        0x0, // Default COBID (overwritten at init for index 0x1400 to 0x1403)
+                        253 // Transmission type. See objdictdef.h 
+                      };
+                    subindex gene_SYNC_Index1402[] = 
+                      { 
+                        { RO, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1402.count },
+                        { RW, uint8, sizeof( UNS32 ), (void*)&gene_SYNC_obj1402.cob_id },
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1402.type },
+                      }; 
+
+/* index 0x1600 :   PDO receive mapping parameter of PDO communication index 0x1400 */
+                    UNS8 gene_SYNC_obj1600_cnt = 2; // Number of mapped variables
+                    UNS32 gene_SYNC_obj1600_mappedVar[] = { 
+                        0x20000108,
+                        0x20000208,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000
+                      };
+                    subindex gene_SYNC_Index1600[] = 
+                      { 
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1600_cnt },
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1600_mappedVar[0]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1600_mappedVar[1]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1600_mappedVar[2]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1600_mappedVar[3]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1600_mappedVar[4]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1600_mappedVar[5]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1600_mappedVar[6]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1600_mappedVar[7]}
+                      }; 
+
+/* index 0x1601 :   PDO receive mapping parameter of PDO communication index 0x1401 */
+                    UNS8 gene_SYNC_obj1601_cnt = 2; // Number of mapped variables
+                    UNS32 gene_SYNC_obj1601_mappedVar[] = { 
+                        0x20000608,
+                        0x20000508,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000
+                      };
+                    subindex gene_SYNC_Index1601[] = 
+                      { 
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1601_cnt },
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1601_mappedVar[0]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1601_mappedVar[1]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1601_mappedVar[2]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1601_mappedVar[3]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1601_mappedVar[4]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1601_mappedVar[5]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1601_mappedVar[6]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1601_mappedVar[7]}
+                      }; 
+
+/* index 0x1602 :   PDO receive mapping parameter of PDO communication index 0x1402 */
+                    UNS8 gene_SYNC_obj1602_cnt = 0; // Number of mapped variables
+                    UNS32 gene_SYNC_obj1602_mappedVar[] = { 
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000
+                      };
+                    subindex gene_SYNC_Index1602[] = 
+                      { 
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1602_cnt },
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1602_mappedVar[0]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1602_mappedVar[1]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1602_mappedVar[2]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1602_mappedVar[3]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1602_mappedVar[4]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1602_mappedVar[5]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1602_mappedVar[6]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1602_mappedVar[7]}
+                      }; 
+
+/* index 0x1800 :   PDO transmit communication parameter */
+                    s_pdo_communication_parameter gene_SYNC_obj1800 = 
+                      { 2, // Largest subindex supported 
+                        0x505, // Default COBID (overwritten at init for index 0x1400 to 0x1403)
+                        255 // Transmission type. See objdictdef.h 
+                      };
+                    subindex gene_SYNC_Index1800[] = 
+                      { 
+                        { RO, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1800.count },
+                        { RW, uint8, sizeof( UNS32 ), (void*)&gene_SYNC_obj1800.cob_id },
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1800.type },
+                      }; 
+
+/* index 0x1801 :   PDO transmit communication parameter */
+                    s_pdo_communication_parameter gene_SYNC_obj1801 = 
+                      { 2, // Largest subindex supported 
+                        0x506, // Default COBID (overwritten at init for index 0x1400 to 0x1403)
+                        253 // Transmission type. See objdictdef.h 
+                      };
+                    subindex gene_SYNC_Index1801[] = 
+                      { 
+                        { RO, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1801.count },
+                        { RW, uint8, sizeof( UNS32 ), (void*)&gene_SYNC_obj1801.cob_id },
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1801.type },
+                      }; 
+
+/* index 0x1802 :   PDO transmit communication parameter */
+                    s_pdo_communication_parameter gene_SYNC_obj1802 = 
+                      { 2, // Largest subindex supported 
+                        0x0, // Default COBID (overwritten at init for index 0x1400 to 0x1403)
+                        253 // Transmission type. See objdictdef.h 
+                      };
+                    subindex gene_SYNC_Index1802[] = 
+                      { 
+                        { RO, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1802.count },
+                        { RW, uint8, sizeof( UNS32 ), (void*)&gene_SYNC_obj1802.cob_id },
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1802.type },
+                      }; 
+
+/* index 0x1A00 :   PDO transmit mapping parameter of PDO communication index 0x1800 */
+                    UNS8 gene_SYNC_obj1A00_cnt = 1; // Number of mapped variables
+                    UNS32 gene_SYNC_obj1A00_mappedVar[] = { 
+                        0x20000108,    /* index 0x2000, sub 0x1, bits 1-8 */
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000
+                      };
+                    subindex gene_SYNC_Index1A00[] = 
+                      { 
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1A00_cnt },
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A00_mappedVar[0]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A00_mappedVar[1]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A00_mappedVar[2]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A00_mappedVar[3]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A00_mappedVar[4]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A00_mappedVar[5]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A00_mappedVar[6]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A00_mappedVar[7]}
+                      }; 
+
+/* index 0x1A01 :   PDO transmit mapping parameter of PDO communication index 0x1801 */
+                    UNS8 gene_SYNC_obj1A01_cnt = 2; // Number of mapped variables
+                    UNS32 gene_SYNC_obj1A01_mappedVar[] = { 
+                        0x20000108,
+                        0x20000208,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000
+                      };
+                    subindex gene_SYNC_Index1A01[] = 
+                      { 
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1A01_cnt },
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A01_mappedVar[0]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A01_mappedVar[1]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A01_mappedVar[2]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A01_mappedVar[3]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A01_mappedVar[4]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A01_mappedVar[5]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A01_mappedVar[6]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A01_mappedVar[7]}
+                      }; 
+
+/* index 0x1A02 :   PDO transmit mapping parameter of PDO communication index 0x1802 */
+                    UNS8 gene_SYNC_obj1A02_cnt = 0; // Number of mapped variables
+                    UNS32 gene_SYNC_obj1A02_mappedVar[] = { 
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000,
+                        0x00000000
+                      };
+                    subindex gene_SYNC_Index1A02[] = 
+                      { 
+                        { RW, uint8, sizeof( UNS8  ), (void*)&gene_SYNC_obj1A02_cnt },
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A02_mappedVar[0]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A02_mappedVar[1]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A02_mappedVar[2]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A02_mappedVar[3]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A02_mappedVar[4]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A02_mappedVar[5]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A02_mappedVar[6]},
+                        { RW, uint32, sizeof( UNS32 ), (void*)&gene_SYNC_obj1A02_mappedVar[7]}
+                      }; 
+
+
+/* index 0x2000 :   Mapped variable */
+                    UNS8 gene_SYNC_highestSubIndex_2000 = 7; // number of subindex - 1
+                    subindex gene_SYNC_Index2000[] = 
+                     {
+                       { RO, uint8, sizeof (UNS8), (void*)&gene_SYNC_highestSubIndex_2000 },
+                       { RW, uint8, sizeof (UNS8), (void*)&seconds },
+                       { RW, uint8, sizeof (UNS8), (void*)&minutes },
+                       { RW, uint8, sizeof (UNS8), (void*)&hours },
+                       { RW, uint8, sizeof (UNS8), (void*)&day },
+                       { RW, uint8, sizeof (UNS8), (void*)&interval },
+                       { RW, uint8, sizeof (UNS8), (void*)&ledky }
+
+                     };
+
+/* index 0x2001 :   Mapped variable */
+                    UNS8 gene_SYNC_highestSubIndex_2001 = 3; // number of subindex - 1
+                    subindex gene_SYNC_Index2001[] = 
+                     {
+                       { RO, uint8, sizeof (UNS8), (void*)&gene_SYNC_highestSubIndex_2001 },
+                       { RW, uint16, sizeof (UNS16), (void*)&casovac_h },
+                       { RW, uint16, sizeof (UNS16), (void*)&casovac_l },
+                       { RW, uint32, sizeof (UNS32), (void*)&casovac }
+                     };
+
+/* index 0x6000 :   Mapped variable */
+                    UNS8 gene_SYNC_highestSubIndex_6000 = 0; // number of subindex - 1
+                    subindex gene_SYNC_Index6000[] = 
+                     {
+                       { RW, uint32, sizeof (UNS32), (void*)&canopenErrNB }
+                     };
+
+/* index 0x6001 :   Mapped variable */
+                    UNS8 gene_SYNC_highestSubIndex_6001 = 0; // number of subindex - 1
+                    subindex gene_SYNC_Index6001[] = 
+                     {
+                       { RW, uint32, sizeof (UNS32), (void*)&canopenErrVAL }
+                     };
+
+/* index 0x6002 :   Mapped variable */
+                    UNS8 gene_SYNC_highestSubIndex_6002 = 0; // number of subindex - 1
+                    subindex gene_SYNC_Index6002[] = 
+                     {
+                       { RW, visible_string, sizeof (strTest), (void*)&strTest }
+                     };
+
+const indextable gene_SYNC_objdict[] = 
+{
+  DeclareIndexTableEntry(gene_SYNC_Index1000, 0x1000),
+  DeclareIndexTableEntry(gene_SYNC_Index1001, 0x1001),
+  DeclareIndexTableEntry(gene_SYNC_Index1005, 0x1005),
+  DeclareIndexTableEntry(gene_SYNC_Index1006, 0x1006),
+  DeclareIndexTableEntry(gene_SYNC_Index1007, 0x1007),
+  DeclareIndexTableEntry(gene_SYNC_Index1008, 0x1008),
+  DeclareIndexTableEntry(gene_SYNC_Index1009, 0x1009),
+  DeclareIndexTableEntry(gene_SYNC_Index100A, 0x100A),
+  DeclareIndexTableEntry(gene_SYNC_Index1016, 0x1016),
+  DeclareIndexTableEntry(gene_SYNC_Index1017, 0x1017),
+  DeclareIndexTableEntry(gene_SYNC_Index1018, 0x1018),
+  DeclareIndexTableEntry(gene_SYNC_Index1200, 0x1200),
+  DeclareIndexTableEntry(gene_SYNC_Index1280, 0x1280),
+  DeclareIndexTableEntry(gene_SYNC_Index1400, 0x1400),
+  DeclareIndexTableEntry(gene_SYNC_Index1401, 0x1401),
+  DeclareIndexTableEntry(gene_SYNC_Index1402, 0x1402),
+  DeclareIndexTableEntry(gene_SYNC_Index1600, 0x1600),
+  DeclareIndexTableEntry(gene_SYNC_Index1601, 0x1601),
+  DeclareIndexTableEntry(gene_SYNC_Index1602, 0x1602),
+  DeclareIndexTableEntry(gene_SYNC_Index1800, 0x1800),
+  DeclareIndexTableEntry(gene_SYNC_Index1801, 0x1801),
+  DeclareIndexTableEntry(gene_SYNC_Index1802, 0x1802),
+  DeclareIndexTableEntry(gene_SYNC_Index1A00, 0x1A00),
+  DeclareIndexTableEntry(gene_SYNC_Index1A01, 0x1A01),
+  DeclareIndexTableEntry(gene_SYNC_Index1A02, 0x1A02),
+  DeclareIndexTableEntry(gene_SYNC_Index2000, 0x2000),
+  DeclareIndexTableEntry(gene_SYNC_Index2001, 0x2001),
+  DeclareIndexTableEntry(gene_SYNC_Index6000, 0x6000),
+  DeclareIndexTableEntry(gene_SYNC_Index6001, 0x6001),
+  DeclareIndexTableEntry(gene_SYNC_Index6002, 0x6002),
+};
+
+// To count at which received SYNC a PDO must be sent.
+// Even if no pdoTransmit are defined, at least one entry is computed
+// for compilations issues.
+UNS8 gene_SYNC_count_sync[1] = {0, };
+
+quick_index gene_SYNC_firstIndex = {
+    SDO_SVR : 11,
+    SDO_CLT : 12,
+    PDO_RCV : 13,
+    PDO_RCV_MAP : 16,
+    PDO_TRS : 19,
+    PDO_TRS_MAP : 22
+};
+
+quick_index gene_SYNC_lastIndex = {
+    SDO_SVR : 11,
+    SDO_CLT : 12,
+    PDO_RCV : 15,
+    PDO_RCV_MAP : 18,
+    PDO_TRS : 21,
+    PDO_TRS_MAP : 24
+};
+
+UNS16 gene_SYNC_ObjdictSize = sizeof(gene_SYNC_objdict)/sizeof(gene_SYNC_objdict[0]); 
+
+CO_Data gene_SYNC_Data = CANOPEN_NODE_DATA_INITIALIZER(gene_SYNC);
+
diff --git a/app/cantest/canfestival/applislave/objdict.h b/app/cantest/canfestival/applislave/objdict.h
new file mode 100644 (file)
index 0000000..e9bb53d
--- /dev/null
@@ -0,0 +1,42 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+#include "data.h"
+#include "timer.h"
+
+// prototypes of function to be filled by app
+void gene_SYNC_SDOtimeoutError(UNS8 line);
+void gene_SYNC_heartbeatError(UNS8);
+
+UNS8 gene_SYNC_canSend(Message *);
+
+void gene_SYNC_initialisation();
+void gene_SYNC_preOperational();
+void gene_SYNC_operational();
+void gene_SYNC_stopped();
+
+void gene_SYNC_post_sync();
+void gene_SYNC_post_TPDO();
+
+// Master node data struct
+extern CO_Data gene_SYNC_Data;
+
diff --git a/app/cantest/canfestival/applislave/objdict.html b/app/cantest/canfestival/applislave/objdict.html
new file mode 100644 (file)
index 0000000..136bb7f
--- /dev/null
@@ -0,0 +1,128 @@
+<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN">
+<html>
+<head>
+<META http-equiv="Content-Type" content="text/html; charset=UTF-8">
+<title>CANOpen object dictionary Configuration</title>
+<style type="text/css">
+         table {
+         border: 1px solid #200088;
+        }
+         td {
+         border: 1px solid #200088;
+        }
+         h1 {
+          background: #FFDD66;
+          border: 3px solid #AA0000;
+           margin: 2em;
+           padding: 1em;
+        }
+
+         h2, h2.dico, h2.pdo {
+          background: #5577FF;
+          border: 1px solid #AA0000;
+           margin: 1em;
+        }
+        
+         h1 em.node-id {
+         color: #0728FF;
+         padding-left: 1em;
+         padding-right: 1em;
+         }
+
+         h1 em.type-node {
+         color: #26BE08;
+         padding-left: 1em;
+         padding-right: 1em;
+         }
+
+         em.pdo-mode {
+         color: #26BE08;
+         }
+
+         .entree {
+         color: #AA0000;
+         }
+         
+         .nom-var, .node-nom {
+         color: #660000;
+         }
+
+       </style>
+</head>
+<body text="#000000" bgcolor="#ffffff">
+<h1>Object dictionary for Node : </h1>
+<h1>
+<em class="node-id">0x03</em>(default) 
+       <em class="node-nom">Gene_SYNC</em><em class="type-node">slave</em>
+</h1>
+<h2>Overview</h2>
+<p>
+       How to make the object dictionary of the node ?
+       First, use Jaxe (command run_objdict) to edit an xml description file
+of the dictionary : objdict.xml.
+Then, run the php program : makeobjetdict.php. You can launch php through a web browser
+if you have installed a server, or, on Linux, you can launch php in command line :
+php-cgi makeobjetdict.php. It compute the file objdict.c. Link it to
+        your project.
+<br>Note : To define the node id, use in your code the function setNodeId(UNS8 nodeId)
+       </p>
+<p>
+         Then the node can be connected to the network. The master must configure it
+         by sending SDO. It will write values in its index, subindex. What to configure ? 
+         <ul>
+<li>Receiving heartbeats from which nodes ? Waiting time ?</li>
+<li>Emitting heartbeats or not ? time btw 2 heartbeats ? </li>
+<li>Defining a cobId for each PDO receive and transmit</li>
+<li>How to transmit a PDO ? on synchro ? request ? event ?</li>
+<li>What variables to put in each PDO receive and transmit ? </li>
+<li>...</li>
+</ul>
+</p>
+       To avoid configuring the node at the connection, you can put the values directly
+in the dictionary objdict.c. But it is boring and unsafe because it is too easy to make
+a mistake !
+
+      
+       <h2>Number of heartbeat consumers : 
+    <em class="entree">1</em>
+</h2>
+<p>This means that the node can expect heartbeats sent by 1 nodes. </p>
+<h2>Number of SDO clients : 
+    <em class="entree">1</em>
+</h2>
+<p>Usualy, a slave node does not have the use of SDO clients, but
+    today, for the library, you must define one. The Master, which can
+    send SDO to "n" slaves nodes, must define here "n" SDO
+    clients. Remember that in most cases, the SDO protocol is used by
+    the master to configure a slave dictionary or read a value. In
+    this use, the master is the client, and the slave is the server.</p>
+<h2>Mapped variables and tables</h2>
+<p>3 tables are defined for the mapping, starting at index 0x2000, 0x6000 and 0x6200.
+       You must start the mapping at the beginning of one of a table, without holes in index
+or subindex. For example, variables in 0x2000 and 0x2001 is ok, but variables in 0x2000 and 0x2002 is not allowed, because you are loosing room in memory. It is the same for the subindex.
+</p>
+<p>
+       The access of the variable is by default "rw" (read-write) or "ro" (read-only). A read-only variable cannot be mapped in a PDO receive.
+</p>
+<p>Here are some others rules for the mapping : </p>
+<ul>
+<li>At an Index, you can map a variable at subindex 0x0 or 0x1, as you like.</li>
+<li>To map several variables at the same Index, you must start at subindex 0x1,
+         because in this case, the subindex 0x0 contains the number of subindex.</li>
+<li>You cannot map variables and tables at the same index.</li>
+<li>The mapping of a table is always starting at subindex 0x1.</li>
+</ul>
+<table class="mapping">
+<tr>
+<td>Var Name</td><td>Bits</td><td>Index</td><td>Sub-index</td><td>access</td>
+</tr>
+<tr>
+<td><em>canopenErrNB</em></td><td><em class="entree">32</em></td><td><em class="entree">0x6000</em></td><td><em class="entree">0x01</em></td><td><em class="entree"></em></td>
+</tr>
+<tr>
+<td><em>canopenErrVAL</em></td><td><em class="entree">32</em></td><td><em class="entree">0x6000</em></td><td><em class="entree">0x02</em></td><td><em class="entree"></em></td>
+</tr>
+<td>Table Name</td><td>Bits</td><td>Index</td><td>Sub-index</td><td>access</td>
+</table>
+</body>
+</html>
diff --git a/app/cantest/canfestival/applislave/objdict.xml b/app/cantest/canfestival/applislave/objdict.xml
new file mode 100644 (file)
index 0000000..b78c88b
--- /dev/null
@@ -0,0 +1,7 @@
+<?xml version="1.0" encoding="ISO-8859-1"?>
+<node manufacturer_device_name_1008="Gene_SYNC" name="Gene_SYNC" node_id="0x03" type_node="slave">
+<heartbeat_consumers nombre="1"/>
+<sdo_clients nombre="1"/>
+<mapped_variable index="0x6000" name="canopenErrNB" size_in_bits="32" sub_index="0x01"/>
+<mapped_variable index="0x6000" name="canopenErrVAL" size_in_bits="32" sub_index="0x02"/>
+</node>
\ No newline at end of file
diff --git a/app/cantest/canfestival/driver/Makefile b/app/cantest/canfestival/driver/Makefile
new file mode 100644 (file)
index 0000000..f595272
--- /dev/null
@@ -0,0 +1,14 @@
+# Generic directory or leaf node makefile for OCERA make framework
+
+ifndef MAKERULES_DIR
+MAKERULES_DIR := $(shell ( old_pwd="" ;  while [ ! -e Makefile.rules ] ; do if [ "$$old_pwd" == `pwd`  ] ; then exit 1 ; else old_pwd=`pwd` ; cd -L .. 2>/dev/null ; fi ; done ; pwd ) )
+endif
+
+ifeq ($(MAKERULES_DIR),)
+all : default
+.DEFAULT::
+       @echo -e "\nThe Makefile.rules has not been found in this or partent directory\n"
+else   
+include $(MAKERULES_DIR)/Makefile.rules
+endif
+
diff --git a/app/cantest/canfestival/driver/Makefile.omk b/app/cantest/canfestival/driver/Makefile.omk
new file mode 100644 (file)
index 0000000..5157e01
--- /dev/null
@@ -0,0 +1,7 @@
+lib_LIBRARIES = candriver
+
+candriver_SOURCES = canOpenDriver.c interrupt.c timerhw.c variahw.c
+
+#lib_LOADLIBES = 
+#bin_PROGRAMS = 
+
diff --git a/app/cantest/canfestival/driver/canOpenDriver.c b/app/cantest/canfestival/driver/canOpenDriver.c
new file mode 100644 (file)
index 0000000..2c2979e
--- /dev/null
@@ -0,0 +1,673 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+
+#include <stddef.h> /* for NULL */
+
+#include "applicfg.h"
+#include "candriver.h"
+#include "interrupt.h"
+
+#include "canOpenDriver.h"
+#include "can.h"
+#include "objdictdef.h"
+#include "timer.h"
+
+#define DEBUG 0
+
+
+/* Debug variables */
+#if DEBUG
+  int prerus_hcan0, prerus_hcan0_rec;
+  int prerus_hcan0_old, prerus_hcan0_rec_old;
+#endif
+
+
+#if DEBUG
+ #ifndef DEB_LED_OUT
+  #define DEB_LED_OUT
+  static void deb_led_out(char val)
+  {
+    if (val&1)
+      DEB_LED_ON(0);
+    else
+      DEB_LED_OFF(0);
+    if (val&2)
+      DEB_LED_ON(1);
+    else
+      DEB_LED_OFF(1);
+    if (val&4)
+      DEB_LED_ON(2);
+    else
+      DEB_LED_OFF(2);
+    if (val&8)
+      DEB_LED_ON(3);
+    else
+      DEB_LED_OFF(3);
+   }
+ #endif
+#endif
+
+__u16 name2mask[16]= {0x0100, 0x0200, 0x0400, 0x0800, 0x1000, 0x2000, 0x4000, 0x8000,
+                        0x0001, 0x0002, 0x0004, 0x0008, 0x0010, 0x0020, 0x0040, 0x0080};
+
+/* match betwen bit and mailbox number represented by this bit */
+__u8 bit2name[16]= {8, 9, 10, 11, 12, 13, 14, 15,
+                    0, 1, 2, 3, 4, 5, 6, 7};
+
+/* Settings bound for auto baudrate on MCU H8S/2638 */
+can_calc_const_t can_calc_const_2638 = {
+  .sync=1,
+  .sjw_max=3,
+  .tseg1_min=4,
+  .tseg1_max=16,
+  .tseg2_min=2,
+  .tseg2_max=8,
+  .brp_min=2,
+  .brp_max=128,
+  .brp_inc=2,
+  .fix_div=2 /* not used */
+};
+/* Default HCAN settings for 200 kbps */
+can_settings_t can_settings_hcan0 =
+{
+  .mcr=0x00,
+  .bcr_sjw=0x02,
+  .bcr_brp=0x1,
+  .bcr_bsp=0x00,
+  .bcr_tseg1=0x0f,
+  .bcr_tseg2=0x05,
+  .mbcr=0x00,  /* not used */
+  .mbimr=0x00, /* not used */
+  .imr=0x00,   /* not used */
+  .lafml=0x0000,
+  .lafmh=0xe0ff        /* accept all messages */
+};
+can_settings_t can_settings_hcan1 =
+{
+  .mcr=0x00,
+  .bcr_sjw=0x02,
+  .bcr_brp=0x01,
+  .bcr_bsp=0x00,
+  .bcr_tseg1=0x0f,
+  .bcr_tseg2=0x05,
+  .mbcr=0x00,  /* not used */
+  .mbimr=0x00, /* not used */
+  .imr=0x00,   /* not used */
+  .lafml=0x0000,
+  .lafmh=0xe0ff        /* accept all messages */
+};
+
+volatile static Message stackMsgRcv[NB_LINE_CAN][MAX_STACK_MSG_RCV]; 
+volatile static t_pointerStack ptrMsgRcv[NB_LINE_CAN];
+
+/* Prototypes */
+UNS8 f_can_receive(UNS8 notused, Message *m);
+UNS8 canSend(UNS8 notused, Message *m);
+
+/* Copy from the stack of the message to treat */
+//static Message msgRcv;
+
+#if 0 /* In CanFestival rc-1 is this function removed */
+/***************************************************************************/
+/* receiveMsgHandler : call the receive function 
+ and call the implied process function
+ Parameters : the function used to receive can messages. 
+ Function used only when platform is Linux or hcs12*/
+UNS8 receiveMsgHandler(UNS8 bus_id)
+{ 
+  Message *m = &msgRcv;
+  UNS8 fc;            //the function code
+
+  if(!(f_can_receive(bus_id, m))){
+    fc = (m->cob_id.w >> 7);
+    if(proceed_infos[fc].process_function!=NULL) {
+      return proceed_infos[fc].process_function(bus_id,m);
+    }
+    else
+      return 0xFF;
+  }
+  return 0;
+}
+#endif /* In CanFestival rc-1 is this function removed */
+/***************************************************************************/
+char canAddIdToFilter(int can_chanel, UNS8 nFilter, UNS16 id)
+{
+  __u32 lafm, hwid_tmp;
+  __u16 lafml, lafmh;
+  __u16 id_std, id_in;
+
+  id_in=id;
+  if (! canTestInitMode(can_chanel)) {
+    /* Error because not init mode */
+    MSG_WAR(0X2600, "Not in init mode ", 0);
+    return 1;
+  }
+  switch (nFilter) {
+    case 0:
+      nFilter = 0;//CANIDAR0; /* First  bank */
+      break;
+    case 1:
+      nFilter = 1;//CANIDAR2; /* First  bank */
+      break;
+    case 2:
+      nFilter = 2;//CANIDAR4; /* Second bank */
+      break;
+    case 3:
+      nFilter = 3;//CANIDAR6; /* Second bank */
+  }
+
+
+  lafml=*(HCAN0_LAFML+can_chanel*HCAN_LAFML_o);
+  lafmh=*(HCAN0_LAFML+can_chanel*HCAN_LAFML_o);
+
+  read_can_id(can_chanel, 0, &hwid_tmp);
+  id_std=CAN_HWID2ID_STD(hwid_tmp);
+  if (!id_std) {
+    /* if CANIDARx = 0 */
+    write_can_id(can_chanel, 0, CAN_ID_FLG2HWID(id_in, 0, 0));
+    //IO_PORTS_8(adrCAN + nFilter) = idMsb;
+    //IO_PORTS_8(adrCAN + nFilter + 1) = idLsb;
+  }
+  read_can_id(can_chanel, 0, &hwid_tmp);
+  id_std=CAN_HWID2ID_STD(hwid_tmp);
+  id_std^=id_in;
+  //fiMsb = IO_PORTS_8(adrCAN + nFilter) ^ idMsb;
+  //fiLsb = IO_PORTS_8(adrCAN + nFilter + 1) ^ idLsb;
+  /* address of CANIDMRx */
+  write_can_id(can_chanel, 0, CAN_ID_FLG2HWID(id_std, 0, 0)); /* Not filtering on rtr value */
+  //IO_PORTS_8(adrCAN + nFilter + 4) = IO_PORTS_8(adrCAN + nFilter + 4) | fiMsb;
+  //IO_PORTS_8(adrCAN + nFilter + 5) = IO_PORTS_8(adrCAN + nFilter + 5) | fiLsb;
+  //IO_PORTS_8(adrCAN + nFilter + 5) |= 0x10;
+  return 0;
+}
+
+
+char canInit(int can_chanel, long baud_rate)
+{
+  can_settings_t *pcan_settings_hcan;
+
+  printf("canInit: can_chanel=%d, baud_rate=%ld\n", can_chanel, baud_rate);
+  switch(can_chanel){
+    case 0: 
+      can_chanel=0;
+      pcan_settings_hcan=&can_settings_hcan0;
+      break;
+    case 1: 
+      can_chanel=1;
+      pcan_settings_hcan=&can_settings_hcan1;
+      break;
+    default: return -1;
+  }
+  if(Can_Enable(can_chanel))
+    MSG_WAR(0X26A0, "Error CAN chanel error ", 0);
+  /* compute and set CAN speed settings */
+  if(Can_AutoBaud(can_chanel, baud_rate))
+    MSG_WAR(0X26A0, "Error in CAN auto baudrate ", 0);
+  /* set registers, module must be in bit configuration mode */
+  if(can_set_registers(can_chanel,pcan_settings_hcan))
+    MSG_WAR(0X26A0, "Error in CAN set registers ", 0);
+  /* HCAN is now ready to receive messages and send messages */
+  MSG_WAR(0X26A0, "HCAN is set and running ", can_chanel);
+  return 0;
+};
+
+
+int Can_AutoBaud(int can_chanel, long baud_rate)
+{
+  can_settings_t *pcan_settings_hcan;
+  int brp,tseg1,tseg2;
+
+  printf("Auto baud: can_chanel=%d, baud_rate=%ld\n", can_chanel, baud_rate);
+  switch(can_chanel){
+    case 0: 
+      can_chanel=0;
+      pcan_settings_hcan=&can_settings_hcan0;
+      break;
+    case 1: 
+      can_chanel=1;
+      pcan_settings_hcan=&can_settings_hcan1;
+      break;
+    default: return -1;
+  }
+  /* compute settings for baud rate */
+  if(can_auto_baud(baud_rate, &brp, &tseg1, &tseg2, 75, &can_calc_const_2638)) {
+      MSG_WAR(0X26C1, "Settings for baud rate is not possible. ", 0);
+    return -1;
+  }
+  /* store CAN speed settings in structure */
+  pcan_settings_hcan->bcr_brp=brp;
+  pcan_settings_hcan->bcr_tseg1=tseg1;
+  pcan_settings_hcan->bcr_tseg2=tseg2;
+  if(tseg2<=can_calc_const_2638.sjw_max)
+    pcan_settings_hcan->bcr_sjw=tseg2;
+  else
+    pcan_settings_hcan->bcr_sjw=can_calc_const_2638.sjw_max;
+  return 0;
+};
+
+/***************************************************************************/
+/*  Init intetrrupts vectors 
+     0 - HCAN0 module, 1 - HCAN1 module
+    return 1 if OK
+*/
+int Can_Enable(int can_chanel)
+{
+   /* set interrupts vectors for HCAN module and enable HCAN module */
+   printf("Can_Enable: can_chanel=%d\n", can_chanel);
+   switch(can_chanel) {
+     case 0:
+       if(!(*SYS_MSTPCRC&MSTPCRC_MSTPC3m))
+         MSG_WAR(0X26C0, "Warning HCAN0 is not in module stop ", 0);
+       excptvec_set(108,can0HdlRcv);
+       excptvec_set(109,can0HdlRcv);
+       *SYS_MSTPCRC&=~MSTPCRC_MSTPC3m;         /* enable HCAN power */
+       #if DEBUG
+         printf("HCAN0 isr set:\n");
+       #endif
+       break;
+     case 1:
+       if(!(*SYS_MSTPCRC&MSTPCRC_MSTPC2m))
+         MSG_WAR(0X26C0, "Warning HCAN1 is not in module stop ", 0);
+       excptvec_set(106,can1HdlRcv);
+       excptvec_set(107,can1HdlRcv);
+       *SYS_MSTPCRC&=~MSTPCRC_MSTPC2m;         /* enable HCAN power */
+       #if DEBUG
+         printf("HCAN1 isr set:\n");
+       #endif
+     default:
+       return(-1);
+   };
+   return(0); /* selected HCAN chanel is in bit configuration mode */
+};
+
+/***************************************************************************/
+int can_auto_baud(long baud_rate, int *pbrp, int *ptseg1, int *ptseg2, int  sampl_pt, can_calc_const_t *c)
+{
+       long best_error = 1000000000, error;
+       int best_tseg=0, best_brp=0, brp=0;
+        unsigned long best_rate=0, best_rate_h8s=0;
+       int tseg=0, tseg1=0, tseg2=0;
+        long clock;
+       
+       clock=CPU_REF_HZ;  /* CPU_SYS_HZ */ /* get system clock */
+       //clock /= c->brp_min;//c->fix_div;
+
+       /* tseg even = round down, odd = round up */
+       for (tseg=(c->sync+c->tseg1_min+c->tseg2_min)*2; tseg<=(c->sync+c->tseg1_max+c->tseg2_max)*2+1; tseg++) 
+        { /* Compute all posibilities of tseg choices (tseg=tseg1+tseg2) */
+               brp = clock/((1+tseg/2)*baud_rate)+tseg%2;
+               brp=(brp/c->brp_inc)*c->brp_inc; /* chose brp step which is possible in system */
+               if ((brp < c->brp_min) || (brp > c->brp_max))
+                       continue;
+               error = baud_rate - clock/(brp*(1+tseg/2));
+               if (error < 0)
+                       error = -error;
+               if (error <= best_error) {
+                       best_error = error;
+                       best_tseg = tseg/2;
+                       best_brp = brp;
+                       best_rate = clock/(brp*(1+tseg/2));
+               }
+       }
+       if (best_error && (baud_rate/best_error < 10)) {
+               return -1;
+       }
+       tseg2 = best_tseg-(sampl_pt*(best_tseg+1))/100;
+       if (tseg2 < c->tseg2_min)
+               tseg2 = c->tseg2_min;
+       if (tseg2 > c->tseg2_max)
+               tseg2 = c->tseg2_max;
+       tseg1 = best_tseg-tseg2;
+       if (tseg1>c->tseg1_max) {
+               tseg1 = c->tseg1_max;
+               tseg2 = best_tseg-tseg1;
+       }
+       /* Example for H8S/2638 */
+       best_rate_h8s = clock/(2*(best_brp/2-1+1)*(3+(tseg1-1)+(tseg2-1)));
+       MSG_WAR(0X26C1, "Curret speed kb/s is: ", best_rate_h8s);
+        /* This is speed computed from equation in H8S/2638 manual. */
+       /* best_brp ... real brp in system, (int) (best_brp/2-1) ... value in register of brp
+                  tseg1 ... real tseg1 in system, (tseg1-1) ... value in register of tseg1
+          tseg2 ... real tseg2 in system, (tseg2-1) ... value in register of tseg2 */
+       /* Get settings for H8S/2638. */
+       *pbrp=best_brp/2-1; //brp;
+       *ptseg1=tseg1-1;
+       *ptseg2=tseg2-1;
+       return 0;
+};
+
+/***************************************************************************/
+int can_set_registers(int can_chanel, can_settings_t *can_settings_hcan)
+{  /* Seting HCAN registers */
+  unsigned int hcanChS,i,bank;
+
+  switch(can_chanel) {
+     case 0:
+       if(*SYS_MSTPCRC&MSTPCRC_MSTPC3m) {
+         MSG_WAR(0X26C2, "Warning HCAN0 is in module stop, in fun. set reg. ", 0);
+         *SYS_MSTPCRC&=~MSTPCRC_MSTPC3m;       /* enable HCAN power */
+       };
+       break;
+     case 1:
+       if(*SYS_MSTPCRC&MSTPCRC_MSTPC2m) {
+         MSG_WAR(0X26C2, "Warning HCAN1 is in module stop, in fun. set reg. ", 0);
+         *SYS_MSTPCRC&=~MSTPCRC_MSTPC2m;       /* enable HCAN power */
+       };
+     default:
+       return(-1);
+  };
+  //printf("can_set_registers HCAN%d\n", can_chanel);
+  hcanChS=can_chanel;
+  if(can_chanel<NB_LINE_CAN) {
+   /* ** Bit Configuration mode ** */
+   /* bit configuration mode - setting BCR */
+     *(HCAN0_BCR+hcanChS*HCAN_BCR_o)=((*(HCAN0_BCR+hcanChS*HCAN_BCR_o)&~BCR_BRPm)
+                                     |CAN_BRP2BRPM(can_settings_hcan->bcr_brp));//0x00
+     *(HCAN0_BCR+hcanChS*HCAN_BCR_o)=((*(HCAN0_BCR+hcanChS*HCAN_BCR_o)&~BCR_SJWm)
+                                     |CAN_SJW2SJWM(can_settings_hcan->bcr_sjw));//0x02
+     *(HCAN0_BCR+hcanChS*HCAN_BCR_o)=((*(HCAN0_BCR+hcanChS*HCAN_BCR_o)&~BCR_TSEG1m)
+                                     |CAN_TSEG12TSEG1M(can_settings_hcan->bcr_tseg1));//0x04
+     *(HCAN0_BCR+hcanChS*HCAN_BCR_o)=((*(HCAN0_BCR+hcanChS*HCAN_BCR_o)&~BCR_TSEG2m)
+                                     |CAN_TSEG22TSEG2M(can_settings_hcan->bcr_tseg2));//0x03
+     *(HCAN0_BCR+hcanChS*HCAN_BCR_o)=((*(HCAN0_BCR+hcanChS*HCAN_BCR_o)&~BCR_BCR15m)
+                                     |(BCR_BCR15m&((can_settings_hcan->bcr_bsp)<<7)));
+   /* bit configuration mode - setting MBCR */
+     *(HCAN0_MBCR+hcanChS*HCAN_MBCR_o) &= ~(MBCR_MBCR14m|MBCR_MBCR15m); /* mailbox set for transmission */
+     *(HCAN0_MBCR+hcanChS*HCAN_MBCR_o) |= (MBCR_MBCR1m|MBCR_MBCR2m); /* mailbox set for reception */
+   /* mailbox RAM initialization - crear all registers MC and MD */
+     for(bank=0;bank<16;bank++) {
+       for(i=0;i<8;i++) {
+         *(HCAN0_MC0+hcanChS*HCAN_MC_o+bank*HCAN_MC_LENGTH+i)=0x00;
+         *(HCAN0_MD0+hcanChS*HCAN_MD_o+bank*HCAN_MD_LENGTH+i)=0x00;
+       };
+     };
+   /* set Message transmission Method */
+     //*HCAN0_MCR &= ~MCR_MCR2m /* by message identifier priority -> 0 (initial value) */
+   /* Exit bit configuration mode */
+     *(HCAN0_MCR+hcanChS*HCAN_MCR_o)&=~MCR_MCR0m; /* Transition into normal operation mode */
+     while(*(HCAN0_GSR+hcanChS*HCAN_GSR_o)&GSR_GSR3m); /* Wait for transition end */
+   /* ** Normal configuration mode ** */
+   /* setting communication */
+     *(HCAN0_IMR+hcanChS*HCAN_IMR_o)&=~(IMR_IMR1m); /* (initial=0xffff) */ /* interrupt mask register */
+     *(HCAN0_MBIMR+hcanChS*HCAN_MBIMR_o)&=~(MBIMR_MBIMR0m|MBIMR_MBIMR1m|MBIMR_MBIMR14m|MBIMR_MBIMR15m); 
+               /* 1 - disable individual interrupt requests (initial 0xffff) */
+   /* MC[x], MD[x] settings */
+
+   /* Local acceptance filter masks */
+     *(HCAN0_LAFML+hcanChS*HCAN_LAFML_o)=can_settings_hcan->lafml;
+     *(HCAN0_LAFMH+hcanChS*HCAN_LAFMH_o)=can_settings_hcan->lafmh;
+  }
+  #if DEBUG
+    printf("can_set_registers finished\n");
+  #endif
+  return(0);
+};
+
+/***************************************************************************/
+char canTestInitMode(int can_chanel)
+{
+  return (*(HCAN0_GSR+can_chanel*HCAN_GSR_o)&GSR_GSR3m); /* Test the bit INITAK */
+}
+
+/***************************************************************************/
+char canMsgTransmit(int can_chanel, Message msg)
+{
+  /* Remind : only CAN A msg implemented. ie id on 11 bits, not 29 */
+  UNS16 cantflg;
+  UNS8 i;
+  int mailbox;
+  __u32 m_hwid;
+  __u8 *hcan_mc, *hcan_md;
+  __u8 *hcan=NULL;
+
+  switch(can_chanel) {
+    case 0:
+      hcan = (__u8 *) HCAN0_MCR;
+      break;
+    case 1:
+      hcan = (__u8*) HCAN1_MCR;
+      break;
+  };
+  /* Looking for a free buffer */
+  cantflg = ~((*(HCAN0_TXPR+can_chanel*HCAN_TXPR_o))|(*(HCAN0_MBCR+can_chanel*HCAN_MBCR_o)));
+  #if DEBUG
+    printf("cantflg=0x%x, TXPR=0x%x, MBCR=0x%x\n", cantflg, *(HCAN0_TXPR+can_chanel*HCAN_TXPR_o), *(HCAN0_MBCR+can_chanel*HCAN_MBCR_o));
+  #endif
+  if (!cantflg) { /* all the TXEx are set */
+    MSG_WAR(0X2604, "No buffer free. Msg to transmit is losted ", 0);
+    return 1; /* No buffer free */
+  }
+  else{
+    /* Selecting a buffer */
+    for(i=0;cantflg;cantflg>>=1,i++) {
+      mailbox=bit2name[i];
+      if(cantflg&0x01)
+        break;
+    };
+    /* Set pointer to correct mailbox control and data */
+    hcan_mc=(__u8 *)(HCAN0_MC0+can_chanel*HCAN_MC_o+mailbox*HCAN_MC_LENGTH);
+    hcan_md=(__u8 *)(HCAN0_MD0+can_chanel*HCAN_MD_o+mailbox*HCAN_MD_LENGTH);
+    /* We put ide = 0 because id is on 11 bits only */
+    m_hwid=CAN_ID_FLG2HWID(msg.cob_id.w, 0, msg.rtr);
+    write_can_id(can_chanel, mailbox, m_hwid);
+    *hcan_mc=msg.len & 0x0f;
+    /* For the priority, we put the highter bits of the cob_id */
+      /* Seted in canInit */
+    #if DEBUG
+      printf("id=0x%x, len=0x%x, rtr=0x%x \n", msg.cob_id.w, msg.len, msg.rtr);
+      printf("data: ");
+    #endif
+    for (i = 0 ; i < msg.len ; i++) {
+      *(hcan_md + i) = msg.data[i];
+      #if DEBUG
+        printf("%02x ", msg.data[i]);
+      #endif
+    }
+    #if DEBUG
+      printf(" \n");
+    #endif
+    /* Transmitting the message */
+    printf("zprm send: id=0x%x, len=%d, rtr=%d\n data: ", msg.cob_id.w, msg.len, msg.rtr);
+    for (i = 0 ; i < msg.len; i++)
+       printf("%x ", msg.data[i]);
+    printf("\n");
+    *(HCAN0_TXPR+can_chanel*HCAN_TXPR_o) |= name2mask[mailbox];  /* Ready to transmit ! */
+  }
+  return 0;
+};
+
+/***************************************************************************/
+int can_recive_msg(int can_chanel, int can_mailbox, int idx)
+{ /* !Caled in interrupt routine ! */
+  //int rel_addr,id_byte;
+  int i,can_mailbox_c_offset,can_mailbox_d_offset;
+  uint32_t temp32;
+
+  UNS8 NewPtrW; 
+  /* We are obliged to save the message while the interruption is pending */
+  /* Increment the writing stack pointer before writing the msg */
+  if (ptrMsgRcv[can_chanel].w == (MAX_STACK_MSG_RCV - 1)) 
+    NewPtrW = 0;
+  else
+    NewPtrW = ptrMsgRcv[can_chanel].w + 1;
+
+  if (NewPtrW == ptrMsgRcv[can_chanel].r) {
+    /* The stack is full. The last msg received before this one is lost */
+    ;/* Can`t use SCI in interrupt */
+    //MSG_WAR(0X2620, "Stack for received msg is full", 0);
+  }
+  else
+    ptrMsgRcv[can_chanel].w = NewPtrW;
+
+  /* Set addres of HCAN message and msg. buffer - not used */
+  can_mailbox_c_offset=can_mailbox*HCAN_MC_LENGTH;
+  can_mailbox_d_offset=can_mailbox*HCAN_MD_LENGTH;
+
+  /* read message */
+  for(i=0,temp32=0;i<4;i++) {
+    temp32<<=8;
+    temp32|=(*(HCAN0_MC0+can_chanel*HCAN_MC_o+can_mailbox_c_offset+4+i));//zprava->id.hwid;
+  };
+  if(CAN_HWID_IDE&temp32) {
+    //id_ext=CAN_HWID2IDE(zprava.id.hwid);
+    return -1;  /* CanFestival don`t use extended id */
+  }
+  else {
+    /* Store the message */
+    stackMsgRcv[can_chanel][ptrMsgRcv[can_chanel].w].cob_id.w=CAN_HWID2ID_STD(temp32);
+  };
+  stackMsgRcv[can_chanel][ptrMsgRcv[can_chanel].w].len = *(HCAN0_MC0+can_chanel*HCAN_MC_o+can_mailbox_c_offset+00) & 0x0F;
+  if(CAN_HWID_RTR&temp32)
+    stackMsgRcv[can_chanel][ptrMsgRcv[can_chanel].w].rtr = 1;
+  else stackMsgRcv[can_chanel][ptrMsgRcv[can_chanel].w].rtr = 0;
+  for (i = 0 ; i < stackMsgRcv[can_chanel][ptrMsgRcv[can_chanel].w].len ; i++)
+    stackMsgRcv[can_chanel][ptrMsgRcv[can_chanel].w].data[i] = *(HCAN0_MD0+can_chanel*HCAN_MD_o+can_mailbox_d_offset+i);
+  return(0);
+};
+
+/***************************************************************************/
+UNS8 f_can_send(UNS8 notused, Message *m)
+{
+  canMsgTransmit(CANOPEN_LINE_NUMBER_USED, *m);
+  return 0;
+}
+
+/***************************************************************************/
+UNS8 canSend(UNS8 notused, Message *m)
+{
+  canMsgTransmit(CANOPEN_LINE_NUMBER_USED, *m);
+  return 0;
+}
+
+/**************************************************************************/
+UNS8 f_can_receive(UNS8 notused, Message *msgRcv)
+{
+  UNS8 i, j;
+  //unsigned short saveif;
+
+  j=CANOPEN_LINE_NUMBER_USED;
+  /* See if a message is pending in the stack */
+  if (ptrMsgRcv[j].r == ptrMsgRcv[j].w)
+    return 0; // No new message
+
+  //save_and_cli(saveif);      /* Disable interrupt when reading msg. from stack */
+  /* Increment the reading pointer of the stack */
+  if (ptrMsgRcv[j].r == (MAX_STACK_MSG_RCV - 1)) 
+     ptrMsgRcv[j].r = 0;
+  else
+    ptrMsgRcv[j].r ++;
+
+  /* Store the message from the stack*/
+  msgRcv->cob_id.w = stackMsgRcv[j][ptrMsgRcv[j].r].cob_id.w;
+  msgRcv->len = stackMsgRcv[j][ptrMsgRcv[j].r].len;
+  msgRcv->rtr = stackMsgRcv[j][ptrMsgRcv[j].r].rtr;
+  for (i = 0 ; i < stackMsgRcv[j][ptrMsgRcv[j].r].len ; i++)
+    msgRcv->data[i] = stackMsgRcv[j][ptrMsgRcv[j].r].data[i];
+  //restore_flags(saveif);        /* interruptions restore end enable */
+  printf("zprm rec: id=0x%x, len=%d, rtr=%d\n data: ", msgRcv->cob_id.w, msgRcv->len, msgRcv->rtr);
+  for (i = 0 ; i < msgRcv->len; i++)
+    printf("%x ", msgRcv->data[i]);
+  printf("\n");
+  return 0xFF; // new message received
+}
+
+/**************************************************************************/
+inline int write_can_id(int can_chanel, int mailbox, __u32 hwid)
+{
+  int i;
+
+  for(i=0;i<4;i++) { /* Write id */
+   *(HCAN0_MC0+can_chanel*HCAN_MC_o+mailbox*HCAN_MC_LENGTH+4+(3-i))=hwid&0xff;
+   hwid=(hwid>>8);
+  };
+  return 0;
+};
+
+/**************************************************************************/
+inline int read_can_id(int can_chanel, int mailbox, __u32 *hwid)
+{
+  int i;
+  __u32 hwid_tmp;
+
+  for(i=0, hwid_tmp=0;i<4;i++, hwid_tmp<<=8)
+    hwid_tmp|=*(HCAN0_MC0+can_chanel*HCAN_MC_o+mailbox*HCAN_MC_LENGTH+4+i);
+  *hwid = hwid_tmp;
+  return 0;
+};
+
+
+/* Handle interrupts */
+/**************************************************************************/
+void can0HdlRcv (void)
+{
+  uint16_t mask;
+  int idx;
+  unsigned short saveif;
+
+  save_and_cli(saveif);
+  //deb_led_out(0);
+  //FlWait(1*100000);
+  #if DEBUG
+    prerus_hcan0++;
+  #endif
+  if (*HCAN0_IRR&IRR_IRR0m) ;
+    *HCAN0_IRR |= IRR_IRR0m; /* set register to handled */
+  if (*HCAN0_IRR&IRR_IRR1m)
+  {
+    /* a message stored in  a mailbox */
+    for (idx=0, mask=1;*HCAN0_RXPR;idx++,mask<<=1) {
+      if (!(mask&*HCAN0_RXPR)) 
+        continue;
+     //deb_led_out(1);
+     //FlWait(1*100000);
+      #if DEBUG
+        prerus_hcan0_rec++;
+      #endif
+      if(idx<8)
+        can_recive_msg(0, idx+8, 0); /* move message to buffer */
+      else
+        can_recive_msg(0, idx-8, 0); /* move message to buffer */
+      *HCAN0_RXPR|=mask; /* clear RXPR */
+      break;
+    }
+  };
+
+  if(*HCAN0_IRR&IRR_IRR8m) { /* a message send from mailbox */
+    for (idx=0, mask=1;*HCAN0_TXACK;idx++,mask<<=1) {
+      if (!(mask&*HCAN0_TXACK)) continue;
+        *HCAN0_TXACK|=mask; /* clear TXACK */
+    };
+    *HCAN0_IRR|=IRR_IRR8m;
+    // deb_led_out(2);
+    // FlWait(1*100000);
+  };
+  restore_flags(saveif);        /* interruptions restore end enable */
+  //deb_led_out(3);
+  //FlWait(1*100000);
+};
+
+/**************************************************************************/
+void can1HdlRcv (void)
+{
+};
+
diff --git a/app/cantest/canfestival/driver/interrupt.c b/app/cantest/canfestival/driver/interrupt.c
new file mode 100644 (file)
index 0000000..e888536
--- /dev/null
@@ -0,0 +1,60 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+/*
+Functions called by interrupts vectors.
+*/
+/*
+This is a part of the driver, of course !
+But you have to put your code in this functions,
+if you plan to use interruptions.
+*/
+
+#include "applicfg.h"
+#include "error.h"
+#include "candriver.h"
+#include "interrupt.h"
+
+extern volatile char msgRecu;
+extern volatile Message canMsgRcv;
+
+/* Inhibe les interruptions */
+
+void lock (void)
+{  
+/*
+   unsigned short mask;
+   __asm__ __volatile__ ("tpa\n\tsei" : "=d"(mask));
+*/
+}
+
+/* Autorise les interruptions */
+void unlock (void)
+{ 
+/*
+   __asm__ __volatile__ ("cli");
+*/
+}
+
+
+
+
diff --git a/app/cantest/canfestival/driver/timerhw.c b/app/cantest/canfestival/driver/timerhw.c
new file mode 100644 (file)
index 0000000..12ec737
--- /dev/null
@@ -0,0 +1,224 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+#include "applicfg.h"
+#include "interrupt.h"
+#include "timerhw.h"
+#include "../include/timer.h"
+
+#include <cpu_def.h>
+#include <h8s2638h.h>
+#include <system_def.h>
+
+/* !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!! */
+//#define PORT_DIS_FUNC /* projekt nebude fungovat, ale lze kompilovat 
+
+#define max(a,b) a>b?a:b
+
+/* global variable */
+static UNS32 tpu_tcnt2H=0, tpu_tgr2aH=0;
+
+/* Function called every 1 ms by the timer channel 4
+*  This function call timerInterrupt()
+*/
+/*
+void __attribute__((interrupt)) timer4Hdl (void);
+
+void resetTimer(void)
+{
+
+}
+*/
+extern UNS16 casovac_l;        // Mapped at index 0x2001, subindex 0x02
+
+ #ifndef DEB_LED_OUT
+  #define DEB_LED_OUT
+  static void deb_led_out(char val)
+  {
+    if (val&1)
+      DEB_LED_ON(0);
+    else
+      DEB_LED_OFF(0);
+    if (val&2)
+      DEB_LED_ON(1);
+    else
+      DEB_LED_OFF(1);
+    if (val&4)
+      DEB_LED_ON(2);
+    else
+      DEB_LED_OFF(2);
+    if (val&8)
+      DEB_LED_ON(3);
+    else
+      DEB_LED_OFF(3);
+   }
+ #endif
+
+/* Timer new CanFestival3-rc1 */
+
+volatile static TIMEVAL last_time_set = TIMEVAL_MAX;
+static UNS8 timer_is_set = 0;
+
+/******************************************************************************/
+void setTimer(TIMEVAL value)
+{ 
+#if 1
+  /*
+  IO_PORTS_16(TC4H) += value;
+  */
+  *TPU_TGR2A = 0xffff&value;   /* interrupt request on value 0x480 for 1 ms, compare TGRA */
+  tpu_tgr2aH = (value>>16);    /* vrite high bits of virtual counter extension to 32 bit */
+  timer_is_set = 1;
+#endif
+}
+
+
+/******************************************************************************/
+TIMEVAL getTime()
+{
+  UNS16 counter_h_1, counter_h_2, counter_l;
+  UNS32 tpu_tcnt2;
+
+  counter_h_1 = tpu_tcnt2H;
+  counter_l = *TPU_TCNT2;
+  counter_h_2 = tpu_tcnt2H;
+  //printf("horni1:0x%x, horni2:0x%x, cely:0x%x\n", counter_h_1, counter_h_2, tpu_tcnt2);
+ if (counter_h_1&counter_h_2) {        /* counter register hadn't change during reading */
+    tpu_tcnt2 = counter_h_1;
+    tpu_tcnt2 = tpu_tcnt2<<16;
+    tpu_tcnt2 |=counter_l; /* not tested */
+  }
+  else 
+    if (counter_l&0x8000) {    /* TPU_TCNT2 readed before overflow */
+      tpu_tcnt2 = counter_h_1;
+      tpu_tcnt2 = tpu_tcnt2<<16;
+      tpu_tcnt2 |= counter_l; /* not tested */
+    }
+    else {                     /* TPU_TCNT2 readed after overflow */
+      tpu_tcnt2 = counter_h_2;
+      tpu_tcnt2 = tpu_tcnt2<<16;
+      tpu_tcnt2 |= counter_l; /* not tested */
+    };
+  //tpu_tcnt2 = 0x12345678;
+  //printf("cely:0x%04x%04x\n", (tpu_tcnt2>>16), tpu_tcnt2&0xffff);
+  //tpu_tcnt2 = counter_h_1;
+  //printf("horni:0x%x, dolni:0x%x, cely:0x%04x%04x\n", tpu_tcnt2H, counter_l, (tpu_tcnt2>>16), tpu_tcnt2&0xffff);
+  return (tpu_tcnt2);
+  //return (tpu_tcnt2 > last_time_set ? tpu_tcnt2 - last_time_set : (0xffffffff - last_time_set + tpu_tcnt2));
+}
+
+/******************************************************************************/
+TIMEVAL getElapsedTime()
+{
+#if 1
+  UNS16 counter_h_1, counter_h_2, counter_l;
+  UNS32 tpu_tcnt2;
+
+  counter_h_1 = tpu_tcnt2H;
+  counter_l = *TPU_TCNT2;
+  counter_h_2 = tpu_tcnt2H;
+  if (counter_h_1&counter_h_2) {       /* counter register hadn't change during reading */
+    tpu_tcnt2 = counter_h_1;
+    tpu_tcnt2 = tpu_tcnt2<<16;
+    tpu_tcnt2 |=counter_l; /* not tested */
+  }
+  else 
+    if (counter_l&0x8000) {    /* TPU_TCNT2 readed before overflow */
+      tpu_tcnt2 = counter_h_1;
+      tpu_tcnt2 = tpu_tcnt2<<16;
+      tpu_tcnt2 |= counter_l; /* not tested */
+    }
+    else {                     /* TPU_TCNT2 readed after overflow */
+      tpu_tcnt2 = counter_h_2;
+      tpu_tcnt2 = tpu_tcnt2<<16;
+      tpu_tcnt2 |= counter_l; /* not tested */
+    };
+  //return (tpu_tcnt2);
+  return (tpu_tcnt2 > last_time_set ? tpu_tcnt2 - last_time_set : (0xffffffff - last_time_set + tpu_tcnt2));
+#endif
+return 0;
+}
+
+
+/******************************************************************************/
+void resetTimer(void)
+{
+
+}
+
+
+/* Timer old CanFestival3 */
+void timer2Hdl(void) __attribute__ ((interrupt_handler));
+void timer2Hdl(void)
+{
+  //unsigned short saveif;
+  //UNS16 tpu_tcnt2H;
+
+  //save_and_cli(saveif);      /* interrupts save and disable */
+  //cli();
+  *TPU_TSR2 &= ~TSR2_TGFAm ;   /* clear compare match */
+  //if(tpu_tcnt2H == tpu_tgr2aH);      /* if right time achieved */
+  TimeDispatch();              /* if is used do not use serial chanel in TimeDispatch */
+  casovac_l++;
+  //timerInterrupt(0);
+  //restore_flags(saveif);     /* interruptions restore end enable */
+  //sti();
+};
+
+void timerOverflow2Hdl(void) __attribute__ ((interrupt_handler));
+void timerOverflow2Hdl(void)
+{
+  tpu_tcnt2H++;
+  *TPU_TSR2 &= ~TSR2_TCFVm;    /* clear overflow */
+};
+
+void initTimer(void)
+{
+#if 1
+  unsigned short saveif;
+
+  save_and_cli(saveif);        /* interrupts save and disable */
+  excptvec_set(44,timer2Hdl);  /* register interrup routine for this timer TGI2A compare */
+  //excptvec_set(45,timer?Hdl);        /* register interrup routine for this timer TGI2B compare */
+  excptvec_set(46,timerOverflow2Hdl);  /* register interrup routine for this timer TCI2V overflow */
+  //excptvec_set(47,timerUnderflow?Hdl);       /* register interrup routine for this timer TGI2U underflow */
+  if(*SYS_MSTPCRA&MSTPCRA_TPUm)        /* when module is stoped do */
+    *SYS_MSTPCRA &= ~MSTPCRA_TPUm; // power TPU unit
+  *TPU_TSTR &=~TSTR_CST2m;     // stop timer in all case
+//  *TPU_TCR2 =(TCR_TPSC2m|TCR_TPSC1m|TCR_TPSC0m); /* rising edge, f divided by 1024, free running */ /* (TCR1_CCLR0m) */
+  *TPU_TMDR2 =0x00;            /* normal mode */
+  *TPU_TIOR2=0x00;             /* output compare is disabled */
+//  *TPU_TSR2 &= ~TSR_TGFAm ;  /* clear flag for TGRA compare */
+  /* *TPU_TSR1 &= ~TSR_TGFBm ; not used */     /* clear flag for TGRB compare */
+//  *TPU_TIER2 |= TIER_TGIEAm|TIER_TCIEVm;     /* enable interrupt on compare with TGFA and on overflow  */
+  /* *TPU_TIER1 |= TIER_TGIEBm; not used */    /* enable interrupt on compare with TGFB  */
+//  *TPU_TIER2 &= ~(TIER_TTGEm|TIER_TCIEUm); /* disable A/D, underflow */
+  *TPU_TCNT2 = 0x00;           /* start value 0 */
+  tpu_tgr2aH = 0x00;           /* high 16 bits of virtual 32 bit counter */
+  *TPU_TGR2A = 0x0480;         /* interrupt request on value 0x480 for 1 ms, compare TGRA */
+  tpu_tgr2aH = 0x0;            /* high 16 bits of virtual 32 bit counter, for compare */
+  /* *TPU_TGR1B not used */
+  *TPU_TSTR |=TSTR_CST2m;      //start timer
+  restore_flags(saveif);       /* interruptions restore end enable */
+#endif
+}
+
diff --git a/app/cantest/canfestival/driver/variahw.c b/app/cantest/canfestival/driver/variahw.c
new file mode 100644 (file)
index 0000000..3d92c5b
--- /dev/null
@@ -0,0 +1,135 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+
+#include "applicfg.h"
+
+/* !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!! */
+//#define PORT_DIS_FUNC /* projekt nebude fungovat, ale lze kompilovat */
+
+/******************************************************************************/
+void initSCI_0(void)
+{
+ #ifdef PORT_DIS_FUNC /* vyrazeno port */
+  IO_PORTS_16(SCI0 + SCIBDH) = 
+    ((1000000 / SERIAL_SCI0_BAUD_RATE) * BUS_CLOCK) >> 4 ;  
+  IO_PORTS_8(SCI0  + SCICR1) = 0;    // format 8N1
+  IO_PORTS_8(SCI0  + SCICR2) = 0x08; // Transmit enable only
+ #endif /* PORT_DIS_FUNC */
+}
+
+/******************************************************************************/
+void initSCI_1(void)
+{
+ #ifdef PORT_DIS_FUNC /* vyrazeno port */
+  IO_PORTS_16(SCI1 + SCIBDH) = 
+    ((1000000 / SERIAL_SCI1_BAUD_RATE) * BUS_CLOCK) >> 4 ;  
+  IO_PORTS_8(SCI1  + SCICR1) = 0;    // format 8N1
+  IO_PORTS_8(SCI1  + SCICR2) = 0x08; // Transmit enable only
+ #endif /* PORT_DIS_FUNC */
+}
+
+
+/******************************************************************************/
+char *
+hex_convert (char *buf, unsigned long value, char lastCar)
+{
+  //Thanks to St�hane Carrez for this function
+  char num[32];
+  int pos;
+
+  *buf++ = '0';
+  *buf++ = 'x';
+
+  pos = 0;
+  while (value != 0) {
+    char c = value & 0x0F;
+    num[pos++] = "0123456789ABCDEF"[(unsigned) c];
+    value = (value >> 4) & (0x0fffffffL);
+    }
+  if (pos == 0)
+    num[pos++] = '0';
+
+  while (--pos >= 0)
+    *buf++ = num[pos];
+
+  *buf++ = lastCar;
+  *buf = 0;
+  return buf;
+}
+
+/******************************************************************************/
+void printSCI_str(char sci, const char * str) 
+{
+ #ifdef PORT_DIS_FUNC /* vyrazeno port */
+  char i = 0;
+  
+  while ((*(str + i) != 0) && (i < 0xFF)) {
+    if (*(str + i) == '\n')
+      {
+       while ((IO_PORTS_8(sci + SCISR1) & 0X80) == 0); // wait if buffer not empty     
+       IO_PORTS_8(sci + SCIDRL) = 13; // return to start of line
+      }
+    while ((IO_PORTS_8(sci + SCISR1) & 0X80) == 0); // wait if buffer not empty
+    IO_PORTS_8(sci + SCIDRL) = *(str + i++);
+  }
+ #endif /* PORT_DIS_FUNC */
+}
+
+/******************************************************************************/
+void printSCI_nbr(char sci, unsigned long nbr, char lastCar) 
+{
+ #ifdef PORT_DIS_FUNC /* vyrazeno port */
+  char strNbr[12];
+  hex_convert(strNbr, nbr, lastCar);
+  printSCI_str(sci, strNbr);
+ #endif /* PORT_DIS_FUNC */
+}
+
+/******************************************************************************/
+// PLL 24 MHZ if quartz on board is 16 MHZ
+void initPLL(void)
+{
+ #ifdef PORT_DIS_FUNC /* vyrazeno port */
+  IO_PORTS_8(CLKSEL) &= ~0x80; // unselect the PLL
+  IO_PORTS_8(PLLCTL) |= 0X60;  // PLL ON and bandwidth auto
+  IO_PORTS_8(SYNR) = 0x02;
+  IO_PORTS_8(REFDV) = 0x01;
+  while ((IO_PORTS_8(CRGFLG) & 0x08) == 0);
+  IO_PORTS_8(CLKSEL) |= 0x80;
+ #endif /* PORT_DIS_FUNC */
+}
+
+/******************************************************************************/
+void initHCS12(void)
+{
+#ifdef PORT_DIS_FUNC /* vyrazeno port */
+# ifdef USE_PLL
+  MSG_WAR(0x3620, "Use the PLL ", 0);
+  initPLL();
+# endif
+#endif /* PORT_DIS_FUNC */
+}
+
+
+
+
diff --git a/app/cantest/canfestival/include/Makefile b/app/cantest/canfestival/include/Makefile
new file mode 100644 (file)
index 0000000..f595272
--- /dev/null
@@ -0,0 +1,14 @@
+# Generic directory or leaf node makefile for OCERA make framework
+
+ifndef MAKERULES_DIR
+MAKERULES_DIR := $(shell ( old_pwd="" ;  while [ ! -e Makefile.rules ] ; do if [ "$$old_pwd" == `pwd`  ] ; then exit 1 ; else old_pwd=`pwd` ; cd -L .. 2>/dev/null ; fi ; done ; pwd ) )
+endif
+
+ifeq ($(MAKERULES_DIR),)
+all : default
+.DEFAULT::
+       @echo -e "\nThe Makefile.rules has not been found in this or partent directory\n"
+else   
+include $(MAKERULES_DIR)/Makefile.rules
+endif
+
diff --git a/app/cantest/canfestival/include/Makefile.omk b/app/cantest/canfestival/include/Makefile.omk
new file mode 100644 (file)
index 0000000..1996a6c
--- /dev/null
@@ -0,0 +1,16 @@
+SUBDIRS = hc12
+#lib_LIBRARIES = canfestival
+
+#shared_LIBRARIES = 
+
+include_HEADERS = can.h config.h data.h def.h lifegrd.h \
+                lss.h nmtMaster.h nmtSlave.h objacces.h objdictdef.h \
+                pdo.h sdo.h states.h sync.h timer.h
+
+#include_HEADERS += config.h
+
+#renamed_include_HEADERS = hc12/pplicfg.h hc12/canOpenDriver.h hc12/candriver.h hc12/error.h
+
+#lib_LOADLIBES = 
+#bin_PROGRAMS = 
+
diff --git a/app/cantest/canfestival/include/can.h b/app/cantest/canfestival/include/can.h
new file mode 100644 (file)
index 0000000..7af921a
--- /dev/null
@@ -0,0 +1,50 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+#ifndef __can_h__
+#define __can_h__
+/** Used for the Can message structure */
+/*
+union SHORT_CAN {
+  struct { UNS8 b0,b1; } b;
+  UNS32 w;
+};
+*/
+
+typedef struct {
+  UNS32 w; // 32 bits
+} SHORT_CAN;
+
+
+/** Can message structure */
+typedef struct {
+  SHORT_CAN cob_id;    // l'ID du mesg
+  UNS8 rtr;                    // remote transmission request. 0 if not rtr, 
+                                // 1 for a rtr message
+  UNS8 len;                    // message length (0 to 8)
+  UNS8 data[8];        // data 
+} Message;
+
+
+typedef UNS8 (*canSend_t)(Message *);
+
+#endif // __can_h__
diff --git a/app/cantest/canfestival/include/config.h b/app/cantest/canfestival/include/config.h
new file mode 100644 (file)
index 0000000..5f3c52e
--- /dev/null
@@ -0,0 +1,38 @@
+/* 
+This file is part of CanFestival, a library implementing CanOpen Stack.
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+#ifndef _CONFIG_H_
+#define _CONFIG_H_
+
+#define MAX_CAN_BUS_ID 1
+#define SDO_MAX_LENGTH_TRANSFERT 32
+#define SDO_MAX_SIMULTANEOUS_TRANSFERTS 4
+#define NMT_MAX_NODE_ID 128
+#define NB_OF_HEARTBEAT_PRODUCERS 10
+#define SDO_TIMEOUT_MS 3000
+#define TIMER_RESOLUTION_MS 50
+#define TIMER_RESOLUTION_US 50000
+#define CANOPEN_BIG_ENDIAN
+// CANOPEN_LITTLE_ENDIAN
+
+#define MAX_NB_TIMER 32
+
+#endif /* _CONFIG_H_ */
diff --git a/app/cantest/canfestival/include/data.h b/app/cantest/canfestival/include/data.h
new file mode 100644 (file)
index 0000000..33da865
--- /dev/null
@@ -0,0 +1,162 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+
+#ifndef __data_h__
+#define __data_h__
+
+// declaration of CO_Data type let us include all necessary headers
+// struct struct_CO_Data can then be defined later
+typedef struct struct_CO_Data CO_Data;
+
+#include <applicfg.h>
+#include "def.h"
+#include "can.h"
+#include "objdictdef.h"
+#include "objacces.h"
+#include "sdo.h"
+#include "pdo.h"
+#include "states.h"
+#include "lifegrd.h"
+#include "sync.h"
+#include "nmtMaster.h"
+
+// This structurs contains all necessary information for a CanOpen node
+struct struct_CO_Data {
+       // Object dictionary
+       UNS8 *bDeviceNodeId;
+       const indextable *objdict;
+       UNS8 *count_sync;
+       quick_index *firstIndex;
+       quick_index *lastIndex;
+       UNS16 *ObjdictSize;
+       const UNS8 *iam_a_slave;
+       valueRangeTest_t valueRangeTest;
+       
+       // SDO
+       s_transfer transfers[SDO_MAX_SIMULTANEOUS_TRANSFERTS];
+       SDOtimeoutError_t SDOtimeoutError;
+       //s_sdo_parameter *sdo_parameters;
+
+       // State machine
+       e_nodeState nodeState;
+       s_state_communication CurrentCommunicationState;
+       initialisation_t initialisation;
+       preOperational_t preOperational;
+       operational_t operational;
+       stopped_t stopped;
+
+       // NMT-heartbeat
+       UNS8 *ConsumerHeartbeatCount;
+       UNS32 *ConsumerHeartbeatEntries;
+       TIMER_HANDLE *ConsumerHeartBeatTimers;
+       UNS16 *ProducerHeartBeatTime;
+       TIMER_HANDLE ProducerHeartBeatTimer;
+       heartbeatError_t heartbeatError;
+       e_nodeState NMTable[NMT_MAX_NODE_ID]; 
+
+       // SYNC
+       TIMER_HANDLE syncTimer;
+       UNS32 *COB_ID_Sync;
+       UNS32 *Sync_Cycle_Period;
+       /*UNS32 *Sync_window_length*/;
+       post_sync_t post_sync;
+       post_TPDO_t post_TPDO;
+       
+       // PDO
+       s_process_var process_var;
+       
+       // General
+       UNS8 toggle;
+       canSend_t canSend;      
+};
+
+// A macro to initialize the data in client app.
+#define CANOPEN_NODE_DATA_INITIALIZER(NODE_PREFIX) {\
+       /* Object dictionary*/\
+       bDeviceNodeId:& NODE_PREFIX ## _bDeviceNodeId,\
+       objdict: NODE_PREFIX ## _objdict,\
+       count_sync: NODE_PREFIX ## _count_sync,\
+       firstIndex: & NODE_PREFIX ## _firstIndex,\
+       lastIndex: & NODE_PREFIX ## _lastIndex,\
+       ObjdictSize: & NODE_PREFIX ## _ObjdictSize,\
+       iam_a_slave: & NODE_PREFIX ## _iam_a_slave,\
+       valueRangeTest: NODE_PREFIX ## _valueRangeTest,\
+       \
+       /* SDO */\
+       transfers:{{\
+               nodeId: 0,\
+               index: 0,\
+               subIndex: 0,\
+               state: SDO_RESET,\
+               toggle: 0,\
+               count: 0,\
+               offset: 0,\
+               data: {0,},\
+               dataType: 0,\
+               timer: -1},},\
+       SDOtimeoutError: &NODE_PREFIX ## _SDOtimeoutError,\
+       \
+       /* State machine */\
+       nodeState:Unknown_state,\
+       CurrentCommunicationState:{\
+               csBoot_Up: 0,\
+               csSDO: 0,\
+               csEmergency: 0,\
+               csSYNC: 0,\
+               csHeartbeat: 0,\
+               csPDO: 0},\
+       initialisation: &NODE_PREFIX ## _initialisation,\
+       preOperational: &NODE_PREFIX ## _preOperational,\
+       operational: &NODE_PREFIX ## _operational,\
+       stopped: &NODE_PREFIX ## _stopped,\
+       \
+       /* NMT-heartbeat */\
+       ConsumerHeartbeatCount: & NODE_PREFIX ## _obj1016_cnt,\
+       ConsumerHeartbeatEntries: NODE_PREFIX ## _obj1016,\
+       ConsumerHeartBeatTimers: NODE_PREFIX ## _heartBeatTimers,\
+       ProducerHeartBeatTime: & NODE_PREFIX ## _obj1017,\
+       ProducerHeartBeatTimer: TIMER_NONE,\
+       heartbeatError: NODE_PREFIX ## _heartbeatError,\
+       NMTable:{Unknown_state,},\
+       \
+       /* SYNC */\
+       syncTimer: TIMER_NONE,\
+       COB_ID_Sync: & NODE_PREFIX ## _obj1005,\
+       Sync_Cycle_Period: & NODE_PREFIX ## _obj1006,\
+       /*Sync_window_length: & NODE_PREFIX ## _obj1007,*/\
+       post_sync: NODE_PREFIX ## _post_sync,\
+       post_TPDO: NODE_PREFIX ## _post_TPDO,\
+       \
+       /* PDO */\
+       process_var: {\
+               count: 0,\
+               data: {0,}},\
+       \
+       /* General */\
+       toggle: 0,\
+       canSend: NODE_PREFIX ## _canSend\
+}
+
+#endif // __data_h__
+
+
diff --git a/app/cantest/canfestival/include/def.h b/app/cantest/canfestival/include/def.h
new file mode 100644 (file)
index 0000000..5678664
--- /dev/null
@@ -0,0 +1,126 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+
+#ifndef __def_h__
+#define __def_h__
+
+#include "config.h"
+
+/** definitions used for object dictionary access. ie SDO Abort codes . (See DS 301 v.4.02 p.48)
+ */
+#define OD_SUCCESSFUL               0x00000000
+#define OD_READ_NOT_ALLOWED          0x06010001
+#define OD_WRITE_NOT_ALLOWED         0x06010002
+#define OD_NO_SUCH_OBJECT            0x06020000
+#define OD_NOT_MAPPABLE              0x06040041
+#define OD_LENGTH_DATA_INVALID       0x06070010
+#define OD_NO_SUCH_SUBINDEX         0x06090011
+#define OD_VALUE_TOO_LOW             0x06090031 /* Value range test result */
+#define OD_VALUE_TOO_HIGH            0x06090032 /* Value range test result */
+/* Others SDO abort codes 
+ */
+#define SDOABT_TOGGLE_NOT_ALTERNED   0x05030000
+#define SDOABT_TIMED_OUT             0x05040000
+#define SDOABT_OUT_OF_MEMORY         0x05040005 /* Size data exceed SDO_MAX_LENGTH_TRANSFERT */
+#define SDOABT_GENERAL_ERROR         0x08000000 /* Error size of SDO message */
+#define SDOABT_LOCAL_CTRL_ERROR      0x08000021 
+
+/******************** CONSTANTS ****************/
+
+/** Constantes which permit to define if a PDO frame
+   is a request one or a data one
+*/
+/* Should not be modified */
+#define REQUEST 1
+#define NOT_A_REQUEST 0
+
+/// Misc constants
+// --------------
+/* Should not be modified */
+#define Rx 0
+#define Tx 1
+#define TRUE  1
+#define FALSE 0
+
+//TODO: remove this limitation. do bit granularity mapping
+#define PDO_MAX_LEN 8    
+                               
+/** Status of the SDO transmission
+ */
+#define SDO_RESET                0x0      // Transmission not started. Init state.
+#define SDO_FINISHED             0x1      // data are available                            
+#define        SDO_ABORTED_RCV          0x80     // Received an abort message. Data not available 
+#define        SDO_ABORTED_INTERNAL     0x85     // Aborted but not because of an abort message.
+#define        SDO_DOWNLOAD_IN_PROGRESS 0x2 
+#define        SDO_UPLOAD_IN_PROGRESS   0x3   
+
+// Status of the node during the SDO transfert :
+#define SDO_SERVER  0x1
+#define SDO_CLIENT  0x2
+#define SDO_UNKNOWN 0x3             
+
+/*  Function Codes 
+  --------------- 
+  defined in the canopen DS301 
+*/
+#define NMT       0x0
+#define SYNC       0x1
+#define TIME_STAMP 0x2
+#define PDO1tx     0x3
+#define PDO1rx     0x4
+#define PDO2tx     0x5
+#define PDO2rx     0x6
+#define PDO3tx     0x7
+#define PDO3rx     0x8
+#define PDO4tx     0x9
+#define PDO4rx     0xA
+#define SDOtx      0xB
+#define SDOrx      0xC
+#define NODE_GUARD 0xE
+
+/// NMT Command Specifier, sent by master to change a slave state
+// -------------------------------------------------------------
+/* Should not be modified */
+#define NMT_Start_Node              0x01
+#define NMT_Stop_Node               0x02
+#define NMT_Enter_PreOperational    0x80
+#define NMT_Reset_Node              0x81
+#define NMT_Reset_Comunication      0x82
+
+/// constantes used in the different state machines
+// -----------------------------------------------
+/* Must not be modified */
+#define state1  0x01
+#define state2  0x02
+#define state3  0x03
+#define state4  0x04
+#define state5  0x05
+#define state6  0x06
+#define state7  0x07
+#define state8  0x08
+#define state9  0x09
+#define state10 0x0A
+#define state11 0x0B
+
+#endif // __def_h__
+
diff --git a/app/cantest/canfestival/include/hc12/Makefile b/app/cantest/canfestival/include/hc12/Makefile
new file mode 100644 (file)
index 0000000..f595272
--- /dev/null
@@ -0,0 +1,14 @@
+# Generic directory or leaf node makefile for OCERA make framework
+
+ifndef MAKERULES_DIR
+MAKERULES_DIR := $(shell ( old_pwd="" ;  while [ ! -e Makefile.rules ] ; do if [ "$$old_pwd" == `pwd`  ] ; then exit 1 ; else old_pwd=`pwd` ; cd -L .. 2>/dev/null ; fi ; done ; pwd ) )
+endif
+
+ifeq ($(MAKERULES_DIR),)
+all : default
+.DEFAULT::
+       @echo -e "\nThe Makefile.rules has not been found in this or partent directory\n"
+else   
+include $(MAKERULES_DIR)/Makefile.rules
+endif
+
diff --git a/app/cantest/canfestival/include/hc12/Makefile.omk b/app/cantest/canfestival/include/hc12/Makefile.omk
new file mode 100644 (file)
index 0000000..746ac5d
--- /dev/null
@@ -0,0 +1,9 @@
+#lib_LIBRARIES = canfestival
+
+#shared_LIBRARIES = 
+
+include_HEADERS = applicfg.h canOpenDriver.h candriver.h error.h timerhw.h interrupt.h
+
+#lib_LOADLIBES = 
+#bin_PROGRAMS = 
+
diff --git a/app/cantest/canfestival/include/hc12/applicfg.h b/app/cantest/canfestival/include/hc12/applicfg.h
new file mode 100644 (file)
index 0000000..c3ac463
--- /dev/null
@@ -0,0 +1,138 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+#ifndef __APPLICFG_HC12__
+#define __APPLICFG_HC12__
+
+#include <string.h>
+#include <stdio.h>
+
+
+/// Define the architecture : little_endian or big_endian
+// -----------------------------------------------------
+// Test :
+// UNS32 v = 0x1234ABCD;
+// char *data = &v;
+//
+// Result for a little_endian architecture :
+// data[0] = 0xCD;
+// data[1] = 0xAB;
+// data[2] = 0x34;
+// data[3] = 0x12;
+//
+// Result for a big_endian architecture :
+// data[0] = 0x12;
+// data[1] = 0x34;
+// data[2] = 0xAB;
+// data[3] = 0xCD;
+
+// Use or not the PLL
+//#define USE_PLL
+
+
+// Several hardware definitions functions
+// --------------------------------------
+
+
+/// Convert an integer to a string in hexadecimal format
+/// If you do not wants to use a lastCar, put lastCar = '\0' (end of string)
+/// ex : value = 0XABCDEF and lastCar = '\n'
+/// buf[0] = '0'
+/// buf[1] = 'X'
+/// buf[2] = 'A'
+/// ....
+/// buf[7] = 'F'
+/// buf[8] = '\n'
+/// buf[9] = '\0'
+extern char *
+hex_convert (char *buf, unsigned long value, char lastCar);
+
+// Integers
+#define INTEGER8 signed char
+#define INTEGER16 short
+#define INTEGER24
+#define INTEGER32 long
+#define INTEGER40
+#define INTEGER48
+#define INTEGER56
+#define INTEGER64
+// Unsigned integers
+#define UNS8   unsigned char
+#define UNS16  unsigned short
+#define UNS32  unsigned long
+#define UNS24
+#define UNS40
+#define UNS48
+#define UNS56
+#define UNS64 
+
+// Whatever your microcontroller, the timer wont work if 
+// TIMEVAL is not at least on 32 bits
+#define TIMEVAL UNS32 
+
+// The timer of the hcs12 counts from 0000 to 0xFFFF
+#define TIMEVAL_MAX 0xFFFF
+
+// The timer is incrementing every 4 us.
+#define MS_TO_TIMEVAL(ms) (ms*0x12)/* (ms * 250) */
+#define US_TO_TIMEVAL(us) (us>>2)
+
+
+// Reals
+#define REAL32 float
+#define REAL64 double
+
+#include "can.h"
+
+#define DEBUG_WAR_CONSOLE_ON
+#define DEBUG_ERR_CONSOLE_ON
+
+
+/// Definition of MSG_ERR
+// ---------------------
+#ifdef DEBUG_ERR_CONSOLE_ON
+#    define MSG_ERR(num, str, val)  ({          \
+          printf("0X%X ", num);                 \
+          /* large printing on console  */      \
+          printf("%s ", str);                   \
+          printf("0x%lx \n",(unsigned long) val);})
+#else
+#    define MSG_ERR(num, str, val)
+#endif
+
+/// Definition of MSG_WAR
+// ---------------------
+#ifdef DEBUG_WAR_CONSOLE_ON
+#    define MSG_WAR(num, str, val) ({         \
+          printf("0X%X ", num);                 \
+          /* large printing on console  */      \
+          printf("%s ", str);                   \
+          printf("0x%lx \n",(unsigned long) val);})
+#else
+#    define MSG_WAR(num, str, val)
+#endif
+
+
+#endif
+
+
diff --git a/app/cantest/canfestival/include/hc12/canOpenDriver.h b/app/cantest/canfestival/include/hc12/canOpenDriver.h
new file mode 100644 (file)
index 0000000..9837fc3
--- /dev/null
@@ -0,0 +1,43 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+
+#ifndef __CANOPENDRIVER__
+#define __CANOPENDRIVER__
+
+
+
+// ---------  to be called by user app ---------
+
+void initTimer(void);
+void resetTimer(void);
+void TimerLoop(void);
+
+/** 
+Returns 0 if no message received, 0xFF if the receiving stack is not empty.
+May be call in polling.
+You can also call canDispatch(...) in void __attribute__((interrupt)) can0HdlRcv (void)
+(see include/hcs12/canOpenDriver.c)
+ */
+UNS8 f_can_receive(UNS8 notused, Message *m);
+
+#endif
diff --git a/app/cantest/canfestival/include/hc12/candriver.h b/app/cantest/canfestival/include/hc12/candriver.h
new file mode 100644 (file)
index 0000000..bc9b76a
--- /dev/null
@@ -0,0 +1,340 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+#ifndef __CANDRIVER__
+#define __CANDRIVER__
+
+//#include DEBUG_CAN
+
+#include <can.h>
+#include <objdictdef.h>
+
+#include <cpu_def.h>
+#include <h8s2638h.h>
+#include <system_def.h>
+
+
+/*
+The CAN message received are stored in a fifo stack
+We consider one stack for all the 5 can devices. It is a choice !
+*/
+
+/* Be free to change this value */
+#define MAX_STACK_MSG_RCV 20 //5
+
+/* Number of incomings and outcomings CAN Line. The layer CanOpen must be
+used only for ONE line CAN. But you may used one or more CAN drivers, without
+a CanOpen layer.
+Only 2 lines are implemented. If more lines are needed, copy void __attribute__((interrupt)) can0HdlRcv (void) to void __attribute__((interrupt)) canXHdlRcv (void) and make 
+changes : [0] to [x], CAN0 to CANX, etc
+*/
+#define NB_LINE_CAN 1
+
+/* Whose hardware HCS12 CAN block is used for CanOpen ? Chose between CAN0, ..., CAN4
+If you use CANOPEN_LINE_NUMBER_USED = CANI, the value of NB_LINE_CAN must be
+more or equal to I + 1
+Value other than CAN0 not tested, but should work fine.
+ */
+#define CANOPEN_LINE_NUMBER_USED 0//CAN0
+
+/* Stack of received messages 
+MSG received on CAN0 module is stored in stackMsgRcv[0], etc
+*/
+extern volatile Message stackMsgRcv[NB_LINE_CAN][MAX_STACK_MSG_RCV];
+
+
+/* Copy from the stack of the message to treat */
+extern Message msgRcv;
+
+
+/* To move on the stack of messages 
+ */
+typedef struct {
+  UNS8 w ; /* received */
+  UNS8 r ; /* To transmit */
+} t_pointerStack;
+
+
+/* Pointer for write or read a message in/from the reception stack */
+extern volatile t_pointerStack ptrMsgRcv[NB_LINE_CAN];
+
+/* 
+Parameters to init the filters for received messages
+*/
+typedef struct {
+  UNS8  idam;        /* Put 0x01 for 16 bits acceptance filter    */
+  UNS8  canidar0;
+  UNS8  canidmr0;
+  UNS8  canidar1;
+  UNS8  canidmr1;
+  UNS8  canidar2;
+  UNS8  canidmr2;
+  UNS8  canidar3;
+  UNS8  canidmr3;
+  UNS8  canidar4;
+  UNS8  canidmr4;
+  UNS8  canidar5;
+  UNS8  canidmr5;
+  UNS8  canidar6;
+  UNS8  canidmr6;
+  UNS8  canidar7;
+  UNS8  canidmr7;
+} canBusFilterInit;
+
+
+/* *************************************************************************** */
+/* can_fn.h used for aplications with HCAN H8S2638 */
+
+/* macros for CAN messages */
+#define CAN_HWID2IDE(hwid) ({ __u32 id=hwid; \
+                            (((id&0x00ff0000)<<5)|((id&0xe0000000)>>(5+6))|((id&0x03000000)>>8)|((id&0x000000ff)<<8)|((id&0x0000ff00)>>8)); })
+#define CAN_IDE2HWID(idin) ({ __u32 id=idin; \
+                            (((id&0x1fe00000)>>5)|((id&0x001c0000)<<(5+6))|((id&0x00030000)<<8)|((id&0x0000ff00)>>8)|((id&0x000000ff)<<8)); })
+#define CAN_HWID2ID_STD(hwid) ( { __u32 id=hwid; \
+                               (((id&0xe0000000)>>(5+8+16))|((id&0x00ff0000)>>(8+5))); } )
+#define CAN_ID_STD2HWID(idin) ( { __u32 id=idin; \
+                               (((id&0x00000007)<<(5+8+16))|((id&0x000007f8)<<(8+5))); })
+#define CAN_ID_FLG2HWID(idin,ext,rtr) ( \
+           ext?(CAN_IDE2HWID(idin)|CAN_HWID_IDE|(rtr?CAN_HWID_RTR:0)): \
+                ((CAN_ID_STD2HWID(idin)|(rtr?CAN_HWID_RTR:0))) \
+         )
+#define CAN_IDM2LAFM(idin)             ({ __u32 id=idin; \
+                                       (((id&0x00000007)<<(16+8+5))|((id&0x000007f8)<<(8+5))); })
+#define CAN_IDEM2LAFM(lafm)            ({ __u32 id=lafm; \
+                                       (((id&0x000000ff)<<(0+8))|((id&0x0000ff00)>>(0+8))|(id&0x00030000) \
+                                       |((id&0x00000007)<<(16+8+5))|((id&0x000007f8)<<(8+5))); })
+
+/* To main header h8s2638h.h */
+#define   LAFM_IDm     0xe0ff0000      /* Mask for standard identifier */
+#define   LAFM_IDEm    0xe3ffffff      /* Mask for extended idenifier */
+
+/* ((CAN_ID_STD2HWID(idin)|(rtr?CAN_HWID_RTR:0))<<16)  */
+#define CAN_STDID_RTR
+#define CAN_HWID_IDE 0x08000000        /* 1 for extended ID format */
+
+#define CAN_HWID_RTR 0x10000000        /* RTR for distinguish between data or remote frames 0 - Data */
+
+#define CAN_BRP2BRPM(brp) ({ __u16 id=brp; \
+                             ((id&0x003f)<<8); })
+#define CAN_TSEG12TSEG1M(tseg1)  ({ __u16 id=tseg1; \
+                                   ((id&0x000f)); })
+#define CAN_TSEG22TSEG2M(tseg2) ({ __u16 id=tseg2; \
+                             ((id&0x0007)<<4); })
+#define CAN_SJW2SJWM(sjw) ({ __u16 id=sjw; \
+                             ((id&0x0003)<<(8+6)); })
+
+/* Define offsets for HCAN chanels */
+#define HCAN_MCR_o (HCAN1_MCR-HCAN0_MCR)
+#define HCAN_GSR_o (HCAN1_GSR-HCAN0_GSR)
+#define HCAN_BCR_o (HCAN1_BCR-HCAN0_BCR)
+#define HCAN_MBCR_o (HCAN1_MBCR-HCAN0_MBCR)
+#define HCAN_TXPR_o (HCAN1_TXPR-HCAN0_TXPR)
+#define HCAN_TXCR_o (HCAN1_TXCR-HCAN0_TXCR)
+#define HCAN_TXACK_o (HCAN1_TXACK-HCAN0_TXACK)
+#define HCAN_ABACK_o (HCAN1_ABACK-HCAN0_ABACK)
+#define HCAN_RXPR_o (HCAN1_RXPR-HCAN0_RXPR)
+#define HCAN_RFPR_o (HCAN1_RFPR-HCAN0_RFPR)
+#define HCAN_IRR_o (HCAN1_IRR-HCAN0_IRR)
+#define HCAN_MBIMR_o (HCAN1_MBIMR-HCAN0_MBIMR)
+#define HCAN_IMR_o (HCAN1_IMR-HCAN0_IMR)
+#define HCAN_REC_o (HCAN1_REC-HCAN0_REC)
+#define HCAN_TEC_o (HCAN1_TEC-HCAN0_TEC)
+#define HCAN_UMSR_o (HCAN1_UMSR-HCAN0_UMSR)
+#define HCAN_LAFML_o (HCAN1_LAFML-HCAN0_LAFML)
+#define HCAN_LAFMH_o (HCAN1_LAFMH-HCAN0_LAFMH)
+#define HCAN_MC_o (HCAN1_MC0-HCAN0_MC0)
+#define HCAN_MD_o (HCAN1_MD0-HCAN0_MD0)
+
+/* H8S 2638 architekture dependencies */
+#define HCAN_MC_LENGTH 8 /* HCAN_MC0+8=HCAN_MC1  */
+#define HCAN_MD_LENGTH 8 /* HCAN_MD0+8=HCAN_MD1  */
+/* *************************************************************************** */
+
+/* structure to store HCAN settings */
+typedef struct
+{
+  __u8 mcr;
+  __u8 bcr_sjw;
+  __u8 bcr_brp;
+  __u8 bcr_bsp;
+  __u8 bcr_tseg1;
+  __u8 bcr_tseg2;
+  __u16 mbcr;  /* mailbox control register */
+  __u16 mbimr; /* mailbox interrupt mask register */
+  __u16 imr;   /* interrup mask register */
+  __u16 lafml;
+  __u16 lafmh;
+} can_settings_t;
+
+/* structure for HCAN speed bounds, used by autobaudrate */
+typedef struct {
+  int sync;
+  int sjw_max;
+  int tseg1_min;
+  int tseg1_max;
+  int tseg2_min;
+  int tseg2_max;
+  int brp_min;
+  int brp_max;
+  int brp_inc;
+  int fix_div;
+} can_calc_const_t;
+
+
+/*
+For the received messsage, add a Identificator to
+the list of ID to accept.
+You can use several times this function to accept several messages.
+It configures registers on 16 bits.
+Automatically, it configure the filter to
+- not accepting the msg on 29 bits (ide=1 refused)
+- not filtering on rtr state (rtr = 1 and rtr = 0 are accepted)
+Algo :
+if CANIDARx = 0 then  CANIDARx = id . else do nothing
+CANIDMRx = CANIDMRx OR (CANIDARx XOR id )
+nFilter : 0 to 3
+Must be in init mode before.
+*/
+char canAddIdToFilter (
+                      int can_chanel, //UNS16 adrCAN,
+                      UNS8 nFilter,
+                      UNS16 id /* 11 bits, the 5 msb not used */
+                      );
+
+
+/*
+Enable one of the 5 MSCAN.
+Must be done only one time after a reset of the CPU.
+To do before any CAN initialisation
+*/
+char canEnable (
+               UNS16 adrCAN /* First address of MSCANx registers */
+               );
+
+
+/* 
+Initialize one of the 2 hcan
+can be done multiple times in your code
+Return 0 : OK
+When it return from the function,
+mscan is on sleep mode with wake up disabled.
+      is not on init mode
+*/
+char canInit (
+             int can_chanel,
+             long baud_rate // speed in bps //UNS16 adrCAN,   /* First address of MSCANx registers  */
+             //canBusInit 
+             //bi       /* All the parameters to init the bus */
+             );
+
+
+/* 
+Initialize one filter for acceptance of received msg.
+Filters MUST be configured on 16 bits 
+(See doc Motorola mscan bloc guide fig 4.3)
+Must be in init mode before.
+adrCAN  : adress of the first register of the mscan module
+nFilter : the filter : 0 to 3.
+ar : Value to write in acceptance register
+     Beware ! hight byte and low byte inverted.
+     for example if nFilter = 0, hight byte of ar -> CANIDAR0
+                                 low   byte of ar -> CANIDAR1
+mr : Value to write in mask register
+     Beware ! hight byte and low byte inverted.
+     for example if nFilter = 2, hight byte of ar -> CANIDMR4
+                                 low   byte of ar -> CANIDMR5
+*/
+
+char canInit1Filter (
+                    int can_chanel,//UNS16 adrCAN, 
+                    UNS8 nFilter,
+                    UNS16 ar,
+                    UNS16 mr
+                    );
+
+/*
+Initialise the parameters for filtering the messages received.
+You must put the MSCAN in init mode before with canInitMode()
+Return 0 : OK
+       1 : Not in init mode. Unable to init MSCAN 
+*/
+
+char canInitFilter (
+                   UNS16 adrCAN, /* First address of MSCANx registers */
+                   canBusFilterInit fi);
+
+/*
+Test if a message is received on CAN "adrCan"
+If msg received, it is put in "msg"
+Return : 0      No msg received
+         other  Message received
+Not used. Must be rewrited.
+Use  f_can_receive instead
+*/     
+
+char canMsgReceived (
+                    int can_chanel, //UNS16 adrCAN,  /* First address of MSCANx registers */
+                    Message msg /* Message received                  */
+                    );
+
+/*
+Transmit a msg on CAN "adrCan"
+Return : 0      No error
+         other  error : no buffer available to make the transmission
+*/     
+
+char canMsgTransmit (
+                    int can_chanel, //UNS16 adrCAN,  /* First address of MSCANx registers */
+                    Message msg  /* Message to transmit                */
+                    );
+
+/*
+Test if one of the 2 hcan is in init mode.
+Return 
+       0     -> Not in init mode
+       other -> In init mode
+*/
+char canTestInitMode (
+                     int can_chanel//UNS16 adrCAN /* First address of MSCANx registers */
+                     );
+/* return 0 OK */
+inline int write_can_id(int can_chanel, int mailbox, __u32 hwid);
+//int write_can_data(int can_chanel, int mailbox, __u8 data[], int length);
+
+inline int read_can_id(int can_chanel, int mailbox, __u32 *hwid);
+//int read_can_data(int can_chanel, int mailbox, __u8 data[], int *length);
+/*
+0x260f Warning HCAN0 is not in module stop, canEnable
+*/
+
+/* function in canOpenDriver */
+int Can_AutoBaud(int can_chanel, long baud_rate);
+int Can_Enable(int can_chanel);
+int can_auto_baud(long baud_rate, int *pbrp, int *ptseg1, int *ptseg2, int  sampl_pt, can_calc_const_t *c);
+int can_set_registers(int can_chanel, can_settings_t *can_settings_hcan);
+
+void can0HdlRcv (void) __attribute__ ((interrupt_handler));
+
+void can1HdlRcv (void) __attribute__ ((interrupt_handler));
+
+#endif /*__CANDRIVER__*/
+
diff --git a/app/cantest/canfestival/include/hc12/error.h b/app/cantest/canfestival/include/hc12/error.h
new file mode 100644 (file)
index 0000000..f92c856
--- /dev/null
@@ -0,0 +1,37 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+#ifndef __ERROR__
+#define __ERROR__
+
+#define ERR_CAN_ADD_ID_TO_FILTER        "1      Not in init mode"
+#define ERR_CAN_INIT_CLOCK              "4      Not in init mode"
+#define ERR_CAN_INIT_1_FILTER           "5      Not in init mode"
+#define ERR_CAN_INIT_FILTER             "6      Not in init mode" 
+#define ERR_CAN_MSG_TRANSMIT            "7      No buffer free "
+#define ERR_CAN_SLEEP_MODE              "8      Is in init mode"
+#define ERR_CAN_SLEEP_MODE_Q            "9      Is in init mode"
+#define ERR_CAN_SLEEP_WUP_MODE          "10     Is in init mode"
+#define ERR_CAN0HDLRCV_STACK_FULL       "11     Stack R full"
+
+#endif /* __ERROR__ */ 
diff --git a/app/cantest/canfestival/include/hc12/interrupt.h b/app/cantest/canfestival/include/hc12/interrupt.h
new file mode 100644 (file)
index 0000000..2d8a52b
--- /dev/null
@@ -0,0 +1,144 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+#ifndef __INTERRUPT__
+#define __INTERRUPT__
+
+/**
+Disable interrupts
+*/
+void lock (void);
+
+/**
+Enable interrupts
+*/
+void unlock (void);
+#if 0
+/**
+Timer overflow
+*/
+void __attribute__((interrupt)) timerOvflHdl (void);
+
+/**
+Message transmitted on MSCAN 0
+*/
+void __attribute__((interrupt)) can0HdlTra (void);
+
+/**
+Message received on MSCAN 0
+*/
+void __attribute__((interrupt)) can0HdlRcv (void);
+
+/**
+Message error on MSCAN 0
+
+*/
+void __attribute__((interrupt)) can0HdlWup (void);
+
+/**
+Message error on MSCAN 0
+*/
+void __attribute__((interrupt)) can0HdlErr (void);
+
+/**
+Message transmited on MSCAN 1
+*/
+void __attribute__((interrupt)) can1HdlTra (void);
+
+/**
+Message received on MSCAN 1
+*/
+void __attribute__((interrupt)) can1HdlRcv (void);
+
+/**
+Message error on MSCAN 1
+*/
+void __attribute__((interrupt)) can1HdlWup (void);
+
+/**
+Message error on MSCAN 1
+*/
+void __attribute__((interrupt)) can1HdlErr (void);
+
+/**
+Message transmited on MSCAN 2
+*/
+void __attribute__((interrupt)) can2HdlTra (void);
+
+/**
+Message received on MSCAN 2
+*/
+void __attribute__((interrupt)) can2HdlRcv (void);
+
+/*
+Message error on MSCAN 2
+*/
+void __attribute__((interrupt)) can2HdlWup (void);
+
+/**
+Message error on MSCAN 2
+*/
+void __attribute__((interrupt)) can2HdlErr (void);
+
+/**
+Message transmited on MSCAN 3
+*/
+void __attribute__((interrupt)) can3HdlTra (void);
+
+/**
+Message received on MSCAN 3
+*/
+void __attribute__((interrupt)) can3HdlRcv (void);
+
+/**
+Message error on MSCAN 3
+*/
+void __attribute__((interrupt)) can3HdlWup (void);
+
+/**
+Message error on MSCAN 3
+*/
+void __attribute__((interrupt)) can3HdlErr (void);
+
+/**
+Message error on MSCAN 4
+*/
+void __attribute__((interrupt)) can4HdlTra (void);
+
+/**
+Message received on MSCAN 4
+*/
+void __attribute__((interrupt)) can4HdlRcv (void);
+
+/*
+Message error on MSCAN 4
+*/
+void __attribute__((interrupt)) can4HdlWup (void);
+
+/**
+Message error on MSCAN 4
+*/
+void __attribute__((interrupt)) can4HdlErr (void);
+
+#endif /* 0 */
+#endif /* __INTERRUPT__  */
diff --git a/app/cantest/canfestival/include/hc12/timerhw.h b/app/cantest/canfestival/include/hc12/timerhw.h
new file mode 100644 (file)
index 0000000..1da51e2
--- /dev/null
@@ -0,0 +1,47 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+#ifndef  __TIMER_HW__
+#define  __TIMER_HW__
+
+/** Initiates the timer. Normally the timer should create an overflow every 1ms.
+ *  but on linux it is a bit complicated to do this. Thats the reason why
+ *  it only generates an overflow every 100ms at the moment
+ */
+void initTimer (void);
+
+
+/** Resets the timer. This is mainly needed for microcontrollers where interrupt
+ *  flags have to be set back and initial values for the timer registers have
+ *  to be set.
+ */
+void resetTimer (void);
+
+
+
+
+#endif
+
+
+
+
+
diff --git a/app/cantest/canfestival/include/led.h b/app/cantest/canfestival/include/led.h
new file mode 100644 (file)
index 0000000..d4665da
--- /dev/null
@@ -0,0 +1,61 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack.
+  ____    _    _   _
+ / ___|  / \  | \ | | ___  _ __   ___ _ __
+| |     / _ \ |  \| |/ _ \| '_ \ / _ \ '_ \
+| |___ / ___ \| |\  | (_) | |_) |  __/ | | |
+ \____/_/   \_\_| \_|\___/| .__/ \___|_| |_|
+                          |_|
+          ____                      _
+         / ___|__ _ _ __   __ _  __| | __ _
+        | |   / _` | '_ \ / _` |/ _` |/ _` |
+        | |__| (_| | | | | (_| | (_| | (_| |
+         \____\__,_|_| |_|\__,_|\__,_|\__,_|
+
+                   canfestival@canopencanada.ca
+/_/_/_/_/_/_/_/_/_/_/_/_/_/_/_/_/_/_/_/_/_/_/
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+
+#if !defined(_LED_INDICATORS_H_)
+#define _LED_INDICATORS_H_
+
+
+enum 
+{
+       LED_NO_ERROR = 0,
+       LED_AUTOBITRATE,
+       LED_INVALID_CONFIG,
+       LED_WARNING_LIMIT_REACH,
+       LED_ERROR_CTRL_EVENT,
+       LED_SYNC_ERROR,
+       LED_EVENT_TIMER_ERROR,
+       LED_BUS_OFF,
+       LED_PRE_OPS,
+       LED_STOP,
+       LED_PRG_DOWNLOAD,
+       LED_OPS
+};
+
+
+int led_init(void);
+void led_set_state(CO_Data *d, int state);
+
+
+#endif
diff --git a/app/cantest/canfestival/include/lifegrd.h b/app/cantest/canfestival/include/lifegrd.h
new file mode 100644 (file)
index 0000000..b09fc87
--- /dev/null
@@ -0,0 +1,62 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+#ifndef __lifegrd_h__
+#define __lifegrd_h__
+
+
+#include <applicfg.h>
+
+typedef void (*heartbeatError_t)(UNS8);
+
+#include "data.h"
+
+//*************************************************************************/
+//Functions
+//*************************************************************************/
+
+
+/** To read the state of a node
+ *  This can be used by the master after having sent a life guard request,
+ *  of by any node if it is waiting for heartbeat.
+ */
+e_nodeState getNodeState (CO_Data* d, UNS8 nodeId);
+
+/** Start heartbeat consumer and producer
+ *  with respect to 0x1016 and 0x1017
+ *  object dictionary entries
+ */
+void heartbeatInit(CO_Data* d);
+
+/** Stop heartbeat consumer and producer
+ */
+void heartbeatStop(CO_Data* d);
+
+/** This function is responsible to process a canopen-message which seams to be an NMT Error Control
+ *  Messages. At them moment we assume that every NMT error control message
+ *  is a heartbeat message.
+ *  \param Message The CAN-message which has to be analysed.
+ *  If a BootUp message is detected, it will return the nodeId of the Slave who booted up
+ */
+void proceedNODE_GUARD (CO_Data* d, Message* m);
+
+#endif //__lifegrd_h__
diff --git a/app/cantest/canfestival/include/lss.h b/app/cantest/canfestival/include/lss.h
new file mode 100644 (file)
index 0000000..dffcdcd
--- /dev/null
@@ -0,0 +1,31 @@
+#if !defined(_LSS_H_)
+#define _LSS_H_
+
+
+void lss_SwitchModeGlobal(unsigned int mode);
+void lss_SwitchModeSelective(unsigned long *LSSaddr);
+void lss_ConfigureNode_ID(unsigned int node_id);
+
+void lss_ConfigureBitTimingParameters(unsigned int table_selector, 
+                                      unsigned int table_index);
+
+void lss_ActivateBitTimingParameters_master(unsigned short switch_delay);
+void lss_ActivateBitTimingParameters_slave(UNS8 data1, UNS8 data2);
+
+void lss_StoreConfiguredParameters(void);
+int lss_InquireLSSAddress(unsigned long *LSSaddr);
+
+void lss_IdentifyRemoteSlaves(unsigned long vendor_id,
+                              unsigned long product_code,
+                              unsigned long rev_low,
+                              unsigned long rev_high,
+                              unsigned long serial_low,
+                              unsigned long serial_high);
+
+int lss_validate_address(void);
+
+void lss_IdentifySlave(void);
+
+
+#endif
+
diff --git a/app/cantest/canfestival/include/nmtMaster.h b/app/cantest/canfestival/include/nmtMaster.h
new file mode 100644 (file)
index 0000000..e7ad306
--- /dev/null
@@ -0,0 +1,64 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+#ifndef __nmtMaster_h__
+#define __nmtMaster_h__
+
+#include "data.h"
+
+/** Transmit a NMT message on the bus number bus_id
+ * to the slave whose node_id is ID
+ * bus_id is hardware dependant
+ * cs represents the order of state changement:
+ * cs =  NMT_Start_Node            // Put the node in operational mode             
+ * cs =         NMT_Stop_Node             // Put the node in stopped mode
+ * cs =         NMT_Enter_PreOperational  // Put the node in pre_operational mode  
+ * cs =  NMT_Reset_Node                   // Put the node in initialization mode 
+ * cs =  NMT_Reset_Comunication           // Put the node in initialization mode 
+ * The mode is changed according to the slave state machine mode :
+ *        initialisation  ---> pre-operational (Automatic transition)
+ *        pre-operational <--> operational
+ *        pre-operational <--> stopped
+ *        pre-operational, operational, stopped -> initialisation
+ *
+ * return canSend(bus_id,&m)               
+ */
+UNS8 masterSendNMTstateChange (CO_Data* d, UNS8 Node_ID, UNS8 cs);
+
+/** Transmit a Node_Guard message on the bus number bus_id
+ * to the slave whose node_id is nodeId
+ * bus_id is hardware dependant
+ * return canSend(bus_id,&m)
+ */
+UNS8 masterSendNMTnodeguard (CO_Data* d, UNS8 nodeId);
+
+
+/** Prepare a Node_Guard message transmission on the bus number bus_id
+ * to the slave whose node_id is nodeId
+ * Put nodeId = 0 to send an NMT broadcast.
+ * This message will ask for the slave, whose node_id is nodeId, its state
+ * bus_id is hardware dependant
+ */
+void masterRequestNodeState (CO_Data* d, UNS8 nodeId);
+
+
+#endif // __nmtMaster_h__
diff --git a/app/cantest/canfestival/include/nmtSlave.h b/app/cantest/canfestival/include/nmtSlave.h
new file mode 100644 (file)
index 0000000..42b7d2d
--- /dev/null
@@ -0,0 +1,45 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+#ifndef __nmtSlave_h__
+#define __nmtSlave_h__
+
+#include <applicfg.h>
+#include "data.h"
+
+/** Threat the reception of a NMT message from the master
+ * *m is a pointer to the message received
+ * bus_id is hardware dependant
+ * return 0 if OK, -1 if the slave is not allowed, by its state,
+ * to receive the message
+ */
+void proceedNMTstateChange (CO_Data* d, Message * m);
+
+/** Transmit the boot-Up frame when the slave is moving from initialization
+ * state to pre_operational state.
+ * bus_id is hardware dependant
+ * return canSend(bus_id,&m)
+ */
+UNS8 slaveSendBootUp (CO_Data* d);
+
+
+#endif // __nmtSlave_h__
diff --git a/app/cantest/canfestival/include/nvram.h b/app/cantest/canfestival/include/nvram.h
new file mode 100644 (file)
index 0000000..5977d89
--- /dev/null
@@ -0,0 +1,7 @@
+#if !defined(_NVRAM_H_)
+#define _NVRAM_H_
+
+int canSaveData(indextable *dict, int max_index);
+int canReadData(indextable *dict, int max_index);
+
+#endif
diff --git a/app/cantest/canfestival/include/objacces.h b/app/cantest/canfestival/include/objacces.h
new file mode 100644 (file)
index 0000000..47ca671
--- /dev/null
@@ -0,0 +1,134 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+/** \file
+ *  \brief Responsible for accessing the object dictionary.
+ *
+ *  This file contains functions for accessing the object dictionary and
+ *  variables that are contained by the object dictionary.
+ *  Accessing the object dictionary contains setting local variables
+ *  as PDOs and accessing (read/write) all entries of the object dictionary
+ *  \warning Only the basic entries of an object dictionary are included
+ *           at the moment.
+ */
+
+#ifndef __objacces_h__
+#define __objacces_h__
+
+#include <applicfg.h>
+
+typedef UNS32 (*valueRangeTest_t)(UNS8 typeValue, UNS32 unsValue, REAL32 realValue);
+
+#include "data.h"
+
+
+
+/**
+Print MSG_WAR (s) if error to the access to the object dictionary occurs.
+You must uncomment the lines 
+//#define DEBUG_CAN
+//#define DEBUG_WAR_CONSOLE_ON
+//#define DEBUG_ERR_CONSOLE_ON
+in the file objaccess.c
+sizeDataDict : Size of the data defined in the dictionary
+sizeDataGiven : Size data given by the user.
+code : error code to print. (SDO abort code. See file def.h)
+Beware that sometimes, we force the sizeDataDict or sizeDataGiven to 0, when we wants to use
+this function but we do not have the access to the right value. One example is
+getSDOerror(). So do not take attention to these variables if they are null.
+*/
+UNS8 accessDictionaryError(UNS16 index, UNS8 subIndex, 
+                          UNS8 sizeDataDict, UNS8 sizeDataGiven, UNS32 code);
+
+/** Reads an entry from the object dictionary.\n
+ *  \code
+ *  // Example usage:
+ *  UNS8  *pbData;
+ *  UNS8 length;
+ *  UNS32 returnValue;
+ *
+ *  returnValue = getODentry( (UNS16)0x100B, (UNS8)1, 
+ *  (void * *)&pbData, (UNS8 *)&length );
+ *  if( returnValue != SUCCESSFUL )
+ *  {
+ *      // error handling
+ *  }
+ *  \endcode 
+ *  \param wIndex The index in the object dictionary where you want to read
+ *                an entry
+ *  \param bSubindex The subindex of the Index. e.g. mostly subindex 0 is
+ *                   used to tell you how many valid entries you can find
+ *                   in this index. Look at the canopen standard for further
+ *                   information
+ *  \param ppbData Pointer to the pointer which points to the variable where
+ *                 the value of this object dictionary entry should be copied
+ *  \param pdwSize This function writes the size of the copied value (in Byte)
+ *                 into this variable.
+ *  \param pDataType : The type of the data. See objdictdef.h
+ *  \param CheckAccess if other than 0, do not read if the data is Write Only
+ *                     [Not used today. Put always 0].
+ *  \return OD_SUCCESSFUL or SDO abort code. (See file def.h)
+ */
+UNS32 getODentry (CO_Data* d,
+                  UNS16 wIndex,
+                 UNS8 bSubindex,
+                 void * * ppbData,
+                 UNS8 * pdwSize, 
+                 UNS8 * pDataType,
+                 UNS8 checkAccess);
+
+
+/** By this function you can write an entry into the object dictionary\n
+ *  \code
+ *  // Example usage:
+ *  UNS8 B;
+ *  B = 0xFF; // set transmission type
+ *
+ *  retcode = setODentry( (UNS16)0x1800, (UNS8)2, &B, sizeof(UNS8), 1 );
+ *  \endocde
+ *  \param wIndex The index in the object dictionary where you want to write
+ *                an entry
+ *  \param bSubindex The subindex of the Index. e.g. mostly subindex 0 is
+ *                   used to tell you how many valid entries you can find
+ *                   in this index. Look at the canopen standard for further
+ *                   information
+ *  \param pbData Pointer to the variable that holds the value that should
+ *                 be copied into the object dictionary
+ *  \param dwSize The size of the value (in Byte).
+ *  \param CheckAccess if other than 0, do not read if the data is Read Only or Constant
+ *  \return OD_SUCCESSFUL or SDO abort code. (See file def.h)
+ */
+UNS32 setODentry (CO_Data* d,
+                  UNS16 wIndex,
+                 UNS8 bSubindex,
+                 void * pbData,
+                 UNS8 dwSize,
+                 UNS8 checkAccess);
+
+
+/** Scan the index of object dictionary. Used only by setODentry and getODentry.
+ *  *errorCode :  OD_SUCCESSFUL if index foundor SDO abort code. (See file def.h)
+ *  Return NULL if index not found. Else : return the table part of the object dictionary.
+ */
+ const indextable * scanIndexOD (CO_Data* d, UNS16 wIndex, UNS32 *errorCode);
+
+#endif // __objacces_h__
diff --git a/app/cantest/canfestival/include/objdictdef.h b/app/cantest/canfestival/include/objdictdef.h
new file mode 100644 (file)
index 0000000..541fca0
--- /dev/null
@@ -0,0 +1,248 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+#ifndef __objdictdef_h__
+#define __objdictdef_h__
+
+/************************* CONSTANTES **********************************/
+/** this are static defined datatypes taken fCODE the canopen standard. They
+ *  are located at index 0x0001 to 0x001B. As described in the standard, they
+ *  are in the object dictionary for definition purpose only. a device does not
+ *  to support all of this datatypes.
+ */
+#define boolean         0x01
+#define int8            0x02
+#define int16           0x03
+#define int32           0x04
+#define uint8           0x05
+#define uint16          0x06
+#define uint32          0x07
+#define real32          0x08
+#define visible_string  0x09
+#define octet_string    0x0A
+#define unicode_string  0x0B
+#define time_of_day     0x0C
+#define time_difference 0x0D
+
+#define domain          0x0F
+#define int24           0x10
+#define real64          0x11
+#define int40           0x12
+#define int48           0x13
+#define int56           0x14
+#define int64           0x15
+#define uint24          0x16
+
+#define uint40          0x18
+#define uint48          0x19
+#define uint56          0x1A
+#define uint64          0x1B
+
+#define pdo_communication_parameter 0x20
+#define pdo_mapping                 0x21
+#define sdo_parameter               0x22
+#define identity                    0x23
+
+// CanFestival is using 0x24 to 0xFF to define some types containing a 
+// value range (See how it works in objdict.c)
+
+
+
+/** definitions of the different types of PDOs' transmission
+ * 
+ * SYNCHRO(n) means that the PDO will be transmited every n SYNC signal.
+ */
+#define TRANS_EVERY_N_SYNC(n) (n) /*n = 1 to 240 */
+#define TRANS_SYNC_MIN        1    /* Trans after reception of n SYNC. n = 1 to 240 */
+#define TRANS_SYNC_MAX        240  /* Trans after reception of n SYNC. n = 1 to 240 */
+#define TRANS_RTR_SYNC        252  /* Transmission on request */
+#define TRANS_RTR             253  /* Transmission on request */
+#define TRANS_EVENT           255  /* Transmission on event */
+
+/** Each entry of the object dictionary can be READONLY (RO), READ/WRITE (RW),
+ *  WRITE-ONLY (WO)
+ */
+//enum e_accessAttribute { RW, WO, RO, RW_S, WO_S, RO_S};
+/*
+       CANOPEN CANADA 2006-04-10
+       on ajoute un etat a l'attribute : SAVE
+       ca indique de sauvegarder le sub-index dans une memoire non-volatile
+
+       (ref. DS-301, p.93  index 0x1010)
+       XX    : do not save the sub-index in the non-volatile memory (default)
+       XX_SA : save the sub-index autonomously
+       XX_SM : save the sub-index on command
+       XX_SF : save factory
+                if a condition is encountered (eg. a DIP at the correct position)
+               e.g. a serial number
+       XX_SS : save sevice - idem as SF but with less restriction
+               e.g. operationnal limit of a device
+       XX_S1 : save user defined 1
+       XX_S2 : save user defined 2
+*/
+#define RW     0x00  
+#define WO     0x01
+#define RO     0x02
+#define RW_SA  0x04
+#define WO_SA  0x05
+#define RO_SA  0x06
+#define RW_SM  0x08
+#define WO_SM  0x09
+#define RO_SM  0x0A
+#define RW_SF  0x10
+#define WO_SF  0x11
+#define RO_SF  0x12
+#define RW_SS  0x20
+#define WO_SS  0x21
+#define RO_SS  0x22
+#define RW_S1  0x40
+#define WO_S1  0x41
+#define RO_S1  0x42
+#define RW_S2  0x80
+#define WO_S2  0x81
+#define RO_S2  0x82
+
+
+
+/************************ STRUCTURES ****************************/
+
+/** Below follows some more datatypes (complex ones) defined by the CANopen
+ *  standard.
+ */
+
+/** This is the datatype for the communication parameter of PDOs defined
+ *  by the CANopen standard
+ */
+typedef struct td_s_pdo_communication_parameter  // Index: 0x20
+{
+    /** number of supported entries = nb subindex - 1
+     */
+    UNS8   count;
+    /** COB-ID
+     */
+    UNS32  cob_id;
+    /** transmission type: 
+       255 (0XFF) : Transmission on event
+       253 (0XFD) : Transmission on request. Use instead the #define RTR 253
+        1 - 240    : Transmission on synchro. Use instead the macro SYNCHRO(n)
+                     n : to transmit every n SYNC message.
+     */
+    UNS8   type;
+    /** inhibit time: not supported yet.
+     */
+    UNS16  inhibit_time;
+    /** reserved (by CANopen standard)
+     */
+    UNS8   reserved;
+    /** event timer: not supported yet.
+     */
+    UNS16  event_timer;
+} s_pdo_communication_parameter;
+
+// s_pdo_mapping_parameter // Index: 0x21 is defined in objdict.c
+// ---------------------------------------------------------------
+
+/** Struct needed for SDO parameter. Defined by the CANopen standard
+ */
+typedef struct td_s_sdo_parameter // Index: 0x22
+{
+    /** number of supported entries
+     */
+    UNS8   count;
+    /** COB-ID client->server
+     */
+    UNS32  cob_id_client;
+    /** COB-ID server->client
+     */
+    UNS32  cob_id_server;
+    /** node ID of SDO's client resp. server
+     */
+    UNS8   node_id;
+} s_sdo_parameter;
+
+/** Struct needed for the idendity of a CANopen device. Defined
+ *  by the CANopen standard
+ */
+typedef struct td_s_identity  // Index: 0x23
+{
+    /** number of supported entries
+     */
+    UNS8   count;
+    /** Vendor-ID (given by the CAN-CIA)
+     */
+    UNS32  vendor_id;
+    /** Product code
+     */
+    UNS32  product_code;
+    /** Revision number
+     */
+    UNS32  revision_number;
+    /** Serial number of this device
+     */
+    UNS32  serial_number;
+} s_identity;
+
+
+/** This are some structs which are neccessary for creating the entries
+ *  of the object dictionary.
+ */
+typedef struct td_subindex
+{
+//    enum e_accessAttribute  bAccessType;// Access type (RO, RW, ...)
+/*
+       OREMEQ 2006-04-07
+       on remplace le enum par des UNS8 pour sauver de la memoire
+       un enum prends 32bits !
+*/
+    UNS8                    bAccessType;
+    UNS8                    bDataType; // Defines of what datatype the entry is
+    UNS8                    size;      // The size (in Byte) of the variable
+    void*                   pObject;   // This is the pointer of the Variable
+} subindex;
+
+/** Struct for creating entries in the communictaion profile
+ */
+typedef struct td_indextable
+{
+    subindex*   pSubindex;   // Pointer to the subindex
+    UNS8   bSubCount;   // the count of valid entries for this subindex
+                        // This count here defines how many memory has been
+                        // allocated. this memory does not have to be used.
+    UNS16   index;
+} indextable;
+
+typedef struct s_quick_index{
+       UNS16 SDO_SVR;
+       UNS16 SDO_CLT;
+       UNS16 PDO_RCV;
+       UNS16 PDO_RCV_MAP;
+       UNS16 PDO_TRS;
+       UNS16 PDO_TRS_MAP;
+}quick_index;
+
+/************************** MACROS *********************************/
+
+///CANopen usefull helpers
+#define GET_NODE_ID(m)         (m.cob_id.w & 0x7f)
+#define GET_FUNCTION_CODE(m)     (m.cob_id.w >> 7)
+
+#endif // __objdictdef_h__
diff --git a/app/cantest/canfestival/include/pdo.h b/app/cantest/canfestival/include/pdo.h
new file mode 100644 (file)
index 0000000..aecdb93
--- /dev/null
@@ -0,0 +1,94 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+#ifndef __pdo_h__
+#define __pdo_h__
+
+#include <applicfg.h>
+#include <def.h>
+
+/* The process_var structure
+ Used to store the PDO before the transmission or the reception.
+*/
+typedef struct struct_s_process_var {
+  UNS8 count; // Size of data. Ex : for a PDO of 6 bytes of data, count = 6
+  UNS8 data[PDO_MAX_LEN];
+}s_process_var;
+
+#include "data.h"
+
+/** The PDO structure */
+typedef struct struct_s_PDO {
+  UNS32 cobId;   // COB-ID
+  UNS8           len;    // Number of data transmitted (in data[])
+  UNS8           data[8]; // Contain the data
+}s_PDO;
+
+/** Transmit a PDO data frame on the bus bus_id
+ * pdo is a structure which contains the pdo to transmit
+ * bus_id is hardware dependant
+ * return canSend(bus_id,&m) or 0xFF if error
+ * request can take the value  REQUEST or NOT_A_REQUEST
+ */
+UNS8 sendPDO (CO_Data* d, s_PDO pdo, UNS8 request);
+
+/** Prepare a PDO frame transmission, 
+ * whose different parameters are stored in process_var table,
+ * to the slave.
+ * bus_id is hardware dependant
+ * call the function sendPDO
+ * return the result of the function sendPDO or 0xFF if error
+ */
+UNS8 PDOmGR (CO_Data* d, UNS32 cobId);
+
+/** Prepare the PDO defined at index to be sent by  PDOmGR
+ * Copy all the data to transmit in process_var
+ * *pwCobId : returns the value of the cobid. (subindex 1)
+ * Return 0 or 0xFF if error.
+ */
+UNS8 buildPDO (CO_Data* d, UNS16 index);
+
+/** Transmit a PDO request frame on the bus bus_id
+ * to the slave.
+ * bus_id is hardware dependant
+ * Returns 0xFF if error, other in success.
+ */
+UNS8 sendPDOrequest (CO_Data* d, UNS32 cobId);
+
+/** Compute a PDO frame reception
+ * bus_id is hardware dependant
+ * return 0xFF if error, else return 0
+ */
+UNS8 proceedPDO (CO_Data* d, Message *m);
+
+/* used by the application to send a variable by PDO.
+ * Check in which PDO the variable is mapped, and send the PDO. 
+ * of course, the others variables mapped in the PDO are also sent !
+ * ( ie when a specific event occured)
+ * bus_id is hardware dependant
+ * variable is a pointer to the variable which has to be sent. Must be
+ * defined in the object dictionary
+ * return 0xFF if error, else return 0
+ */
+UNS8 sendPDOevent (CO_Data* d, void * variable);
+
+#endif
diff --git a/app/cantest/canfestival/include/peak/applicfg.h b/app/cantest/canfestival/include/peak/applicfg.h
new file mode 100644 (file)
index 0000000..b30fd0d
--- /dev/null
@@ -0,0 +1,166 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+#ifndef __APPLICFG_LINUX__
+#define __APPLICFG_LINUX__
+
+#include <string.h>
+#include <stdio.h>
+
+#include "libpcan.h"
+
+// Define the architecture : little_endian or big_endian
+// -----------------------------------------------------
+// Test :
+// UNS32 v = 0x1234ABCD;
+// char *data = &v;
+//
+// Result for a little_endian architecture :
+// data[0] = 0xCD;
+// data[1] = 0xAB;
+// data[2] = 0x34;
+// data[3] = 0x12;
+//
+// Result for a big_endian architecture :
+// data[0] = 0x12;
+// data[1] = 0x34;
+// data[2] = 0xAB;
+// data[3] = 0xCD;
+
+// Integers
+#define INTEGER8
+#define INTEGER16
+#define INTEGER24
+#define INTEGER32
+#define INTEGER40
+#define INTEGER48
+#define INTEGER56
+#define INTEGER64
+
+// Unsigned integers
+#define UNS8   unsigned char
+#define UNS16  unsigned short
+#define UNS32  unsigned long
+#define UNS24
+#define UNS40
+#define UNS48
+#define UNS56
+#define UNS64 
+
+// Reals
+#define REAL32 float
+#define REAL64 double
+
+#include "can.h"
+
+// this function is used to send PDO with the value and number of error
+extern UNS8 sendPDOevent (UNS8 bus_id, void * variable );
+
+
+// the number of the error, to send in a PDO
+extern UNS32 canopenErrNB;
+
+// the value, to send in a PDO
+extern UNS32 canopenErrVAL;
+
+// if not null, allow the printing of message to the console
+// Could be managed by PDO
+extern UNS8 printMsgErrToConsole;
+extern UNS8 printMsgWarToConsole;
+
+/// Definition of error and warning macros
+// --------------------------------------
+#if defined DEBUG_ERR_CONSOLE_ON || defined PDO_ERROR || defined DEBUG_WAR_CONSOLE_ON
+extern e_nodeState  nodeState;
+#endif
+
+/// Definition of MSG_ERR
+// ---------------------
+#ifdef DEBUG_ERR_CONSOLE_ON
+#  ifdef DEBUG_CAN
+#    define MSG_ERR(num, str, val)            \
+      {                                       \
+        if (printMsgErrToConsole) {              \
+          printf("0X%x %s 0X%x \n", num, str, val); \
+        }                                     \
+        /* the code here to send by PDO */    \
+        if( nodeState == Operational ){ \
+         canopenErrNB = num;                 \
+         canopenErrVAL= val;                 \
+         sendPDOevent ( 0, &canopenErrNB);            \
+       }                                     \
+      }
+#  else
+#    define MSG_ERR(num, str, val)            \
+      {                                       \
+        if (printMsgErrToConsole) {              \
+          /* short printing on console */     \
+          printf("0X%x 0X%x \n", num, val);   \
+        }\
+          /* the code here to send by PDO */    \
+        if(nodeState == Operational){ \
+         canopenErrNB = num;                 \
+         canopenErrVAL = val;                \
+         sendPDOevent ( 0, &canopenErrNB);            \
+        }\
+      }
+#  endif
+#else
+# ifdef PDO_ERROR
+#  define MSG_ERR(num, str, val)              \
+    {                                         \
+             /* the code here to send by PDO */    \
+        if(nodeState == Operational){\
+         canopenErrNB = num;                 \
+         canopenErrVAL = val;                \
+         sendPDOevent ( 0, &canopenErrNB);            \
+       }                                     \
+    }
+#else
+#  define MSG_ERR(num, str, val)             
+#endif
+#endif
+
+/// Definition of MSG_WAR
+// ---------------------
+#ifdef DEBUG_WAR_CONSOLE_ON
+#  ifdef DEBUG_CAN
+#    define MSG_WAR(num, str, val)          \
+      if (printMsgWarToConsole) {              \
+        /* large printing on console */     \
+        printf("0X%X %s 0X%X \n", num, str, val); \
+      }
+#  else
+#    define MSG_WAR(num, str, val)          \
+      if (printMsgWarToConsole) {              \
+        /* Short printing on console */     \
+        printf("0X%x 0X%x \n", num, val); \
+      }  
+#  endif
+#else
+#  define MSG_WAR(num, str, val) 
+#endif
+
+
+
+
+#endif
diff --git a/app/cantest/canfestival/include/peak/linuxCan.h b/app/cantest/canfestival/include/peak/linuxCan.h
new file mode 100644 (file)
index 0000000..7c5a655
--- /dev/null
@@ -0,0 +1,49 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+#ifndef __LINUX_CAN_PEAK__
+#define __LINUX_CAN_PEAK__
+
+
+struct struct_s_BOARD {
+  char * busname;
+  int baudrate;
+};
+
+typedef struct struct_s_BOARD s_BOARD;
+
+/* open the communication with the board
+ * return a file descriptor or -1 if error
+ */
+void * f_can_open (s_BOARD * board);
+
+/* close the communication
+ * return 0 if ok, other if failure
+ */
+int f_can_close (void);
+
+
+
+
+
+#endif
+
diff --git a/app/cantest/canfestival/include/peak/timerhw.h b/app/cantest/canfestival/include/peak/timerhw.h
new file mode 100644 (file)
index 0000000..afb712d
--- /dev/null
@@ -0,0 +1,45 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+#ifndef  __TIMER_HW__
+#define  __TIMER_HW__
+
+/** Initiates the timer. Normally the timer should create an overflow every 1ms.
+ *  but on linux it is a bit complicated to do this. Thats the reason why
+ *  it only generates an overflow every 100ms at the moment
+ */
+void initTimer (void);
+
+
+/** Resets the timer. This is mainly needed for microcontrollers where interrupt
+ *  flags have to be set back and initial values for the timer registers have
+ *  to be set.
+ */
+void resetTimer (void);
+
+
+/** The interrupt function called by the timer
+ */
+void timerIT (int iValue);
+
+
+#endif
\ No newline at end of file
diff --git a/app/cantest/canfestival/include/sdo.h b/app/cantest/canfestival/include/sdo.h
new file mode 100644 (file)
index 0000000..f3f20aa
--- /dev/null
@@ -0,0 +1,247 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+#ifndef __sdo_h__
+#define __sdo_h__
+
+typedef void (*SDOtimeoutError_t)(UNS8 line);
+struct struct_s_transfer;
+
+#include "timer.h"
+
+/* The Transfer structure
+Used to store the different segments of 
+ - a SDO received before writing in the dictionary  
+ - the reading of the dictionary to put on a SDO to transmit 
+*/
+
+struct struct_s_transfer {
+  UNS8           nodeId;     //own ID if server, or node ID of the server if client
+  
+  UNS8           whoami;     // Takes the values SDO_CLIENT or SDO_SERVER
+  UNS8           state;      // state of the transmission : Takes the values SDO_...
+  UNS8           toggle;
+  UNS32          abortCode;  // Sent or received
+  // index and subindex of the dictionary where to store
+  // (for a received SDO) or to read (for a transmit SDO)
+  UNS16          index; 
+  UNS8           subIndex; 
+  UNS32          count;      // Number of data received or to be sent.
+  UNS32          offset;     // stack pointer of data[]
+                             // Used only to tranfer part of a line to or from a SDO.
+                             // offset is always pointing on the next free cell of data[].
+  UNS8           data [SDO_MAX_LENGTH_TRANSFERT];
+  UNS8           dataType;   // Defined in objdictdef.h Value is visible_string 
+                             // if it is a string, any other value if it is not a string, 
+                             // like 0. In fact, it is used only if client.
+  TIMER_HANDLE   timer;    // Time counter to implement a timeout in milliseconds.
+                             // It is automatically incremented whenever 
+                             // the line state is in SDO_DOWNLOAD_IN_PROGRESS or 
+                             // SDO_UPLOAD_IN_PROGRESS, and reseted to 0 
+                             // when the response SDO have been received.
+};
+typedef struct struct_s_transfer s_transfer;
+  
+
+#include "data.h"
+
+/// The 8 bytes data of the SDO
+struct BODY{
+    UNS8 data[8];
+};
+
+/// The SDO structure ...
+struct struct_s_SDO {
+  UNS8 nodeId;         //in any case, Node ID of the server (case sender or receiver).
+  struct BODY body;
+};
+
+
+typedef struct struct_s_SDO s_SDO;
+
+/** Reset all sdo buffers
+ */
+void resetSDO (CO_Data* d);
+
+
+/** Copy the data received from the SDO line transfert to the object dictionary
+ * Returns SDO error code if error. Else, returns 0; 
+ */
+UNS32 SDOlineToObjdict (CO_Data* d, UNS8 line);
+
+/** Copy the data from the object dictionary to the SDO line for a network transfert.
+ * Returns SDO error code if error. Else, returns 0; 
+ */
+UNS32 objdictToSDOline (CO_Data* d, UNS8 line);
+
+/** copy data from an existant line in the argument "* data"
+ * Returns 0xFF if error. Else, returns 0; 
+ */
+UNS8 lineToSDO (CO_Data* d, UNS8 line, UNS8 nbBytes, UNS8 * data);
+
+/** Add data to an existant line
+ * Returns 0xFF if error. Else, returns 0; 
+ */
+UNS8 SDOtoLine (CO_Data* d, UNS8 line, UNS8 nbBytes, UNS8 * data);
+
+/** Called when an internal SDO abort occurs.
+ * Release the line * Only if server * 
+ * If client, the line must be released manually in the core application.
+ * The reason of that is to permit the program to read the transfers[][] structure before its reset,
+ * because many informations are stored on it : index, subindex, data received or trasmited, ...
+ * In all cases, sends a SDO abort.
+ * Returns 0
+ */
+UNS8 failedSDO (CO_Data* d, UNS8 nodeId, UNS8 whoami, UNS16 index, 
+               UNS8 subIndex, UNS32 abortCode);
+
+/** Reset an unused line.
+ * 
+ */
+void resetSDOline (CO_Data* d, UNS8 line);
+
+/** Initialize some fields of the structure.
+ * Returns 0
+ */
+UNS8 initSDOline (CO_Data* d, UNS8 line, UNS8 nodeId, UNS16 index, UNS8 subIndex, UNS8 state);
+
+/** Search for an unused line in the transfers array
+ * to store a new SDO.
+ * ie a line which value of the field "state" is "SDO_RESET"
+ * An unused line have the field "state" at the value SDO_RESET
+ * bus_id is hardware dependant
+ * whoami : create the line for a SDO_SERVER or SDO_CLIENT.
+ * return 0xFF if all the lines are on use. Else, return 0
+ */
+UNS8 getSDOfreeLine (CO_Data* d, UNS8 whoami, UNS8 *line);
+
+/** Search for the line, in the transfers array, which contains the
+ * beginning of the reception of a fragmented SDO
+ * whoami takes 2 values : look for a line opened as SDO_CLIENT or SDO_SERVER
+ * bus_id is hardware dependant
+ * nodeId correspond to the message node-id 
+ * return 0xFF if error.  Else, return 0
+ */
+UNS8 getSDOlineOnUse (CO_Data* d, UNS8 nodeId, UNS8 whoami, UNS8 *line);
+
+/** Close a transmission.
+ * nodeId : Node id of the server if both server or client
+ * whoami : Line opened as SDO_CLIENT or SDO_SERVER
+ */
+UNS8 closeSDOtransfer (CO_Data* d, UNS8 nodeId, UNS8 whoami);
+
+/** Bytes in the line structure which must be transmited (or received)
+ * bus_id is hardware dependant.
+ * return 0.
+ */
+UNS8 getSDOlineRestBytes (CO_Data* d, UNS8 line, UNS8 * nbBytes);
+
+/** Store in the line structure the nb of bytes which must be transmited (or received)
+ * bus_id is hardware dependant.
+ * return 0 if success, 0xFF if error.
+ */
+UNS8 setSDOlineRestBytes (CO_Data* d, UNS8 line, UNS8 nbBytes);
+
+/** Transmit a SDO frame on the bus bus_id
+ * sdo is a structure which contains the sdo to transmit
+ * bus_id is hardware dependant
+ * whoami takes 2 values : SDO_CLIENT or SDO_SERVER
+ * return canSend(bus_id,&m) or 0xFF if error
+ */
+UNS8 sendSDO (CO_Data* d, UNS8 whoami, s_SDO sdo);
+
+/** Transmit a SDO error to the client. The reasons may be :
+ * Read/Write to a undefined object
+ * Read/Write to a undefined subindex
+ * Read/write a not valid length object
+ * Write a read only object
+ * whoami takes 2 values : SDO_CLIENT or SDO_SERVER
+ */
+UNS8 sendSDOabort (CO_Data* d, UNS8 whoami, UNS16 index, UNS8 subIndex, UNS32 abortCode);
+
+/** Treat a SDO frame reception
+ * bus_id is hardware dependant
+ * call the function sendSDO
+ * return 0xFF if error
+ *        0x80 if transfert aborted by the server
+ *        0x0  ok
+ */
+UNS8 proceedSDO (CO_Data* d, Message *m);
+
+/** Used by the application to send a SDO request frame to write the data *data
+ * at the index and subIndex indicated
+ * in the dictionary of the slave whose node_id is nodeId
+ * Count : nb of bytes to write in the dictionnary.
+ * datatype (defined in objdictdef.h) : put "visible_string" for strings, 0 for integers or reals or other value.
+ * bus_id is hardware dependant
+ * return 0xFF if error, else return 0
+ */
+UNS8 writeNetworkDict (CO_Data* d, UNS8 nodeId, UNS16 index, 
+                      UNS8 subIndex, UNS8 count, UNS8 dataType, void *data); 
+
+/** Used by the application to send a SDO request frame to read
+ * in the dictionary of a server node whose node_id is ID
+ * at the index and subIndex indicated
+ * bus_id is hardware dependant
+ * datatype (defined in objdictdef.h) : put "visible_string" for strings, 0 for integers or reals or other value.
+ * return 0xFF if error, else return 0
+ */
+UNS8 readNetworkDict (CO_Data* d, UNS8 nodeId, UNS16 index, 
+                     UNS8 subIndex, UNS8 dataType);
+
+/** Use this function after a readNetworkDict to get the result.
+  Returns : SDO_FINISHED             // data is available
+            SDO_ABORTED_RCV          // Transfert failed. (abort SDO received)
+            SDO_ABORTED_INTERNAL     // Transfert failed. Internal abort.
+            SDO_UPLOAD_IN_PROGRESS   // Data not yet available
+           SDO_DOWNLOAD_IN_PROGRESS // Should not arrive ! 
+
+  dataType (defined in objdictdef.h) : type expected. put "visible_string" for strings, 0 for integers or reals.
+  abortCode : 0 = not available. Else : SDO abort code. (received if return SDO_ABORTED_RCV)
+  example :
+  UNS32 data;
+  UNS8 size;
+  readNetworkDict(0, 0x05, 0x1016, 1, 0) // get the data index 1016 subindex 1 of node 5
+  while (getReadResultNetworkDict (0, 0x05, &data, &size) != SDO_UPLOAD_IN_PROGRESS);
+*/
+UNS8 getReadResultNetworkDict (CO_Data* d, UNS8 nodeId, void* data, 
+                              UNS8 *size, UNS32 * abortCode);
+
+/**
+  Use this function after a writeNetworkDict to get the result of the write
+  It is mandatory to call this function because it is releasing the line used for the transfer.
+  Returns : SDO_FINISHED             // data is available
+            SDO_ABORTED_RCV          // Transfert failed. (abort SDO received)
+            SDO_ABORTED_INTERNAL     // Transfert failed. Internal abort.
+            SDO_DOWNLOAD_IN_PROGRESS // Data not yet available
+           SDO_UPLOAD_IN_PROGRESS   // Should not arrive ! 
+  abortCode : 0 = not available. Else : SDO abort code. (received if return SDO_ABORTED_RCV)
+  example :
+  UNS32 data = 0x50;
+  UNS8 size;
+  UNS32 abortCode;
+  writeNetworkDict(0, 0x05, 0x1016, 1, size, &data) // write the data index 1016 subindex 1 of node 5
+  while ( getWriteResultNetworkDict (0, 0x05, &abortCode) != SDO_DOWNLOAD_IN_PROGRESS);  
+*/
+UNS8 getWriteResultNetworkDict (CO_Data* d, UNS8 nodeId, UNS32 * abortCode);
+
+#endif
diff --git a/app/cantest/canfestival/include/states.h b/app/cantest/canfestival/include/states.h
new file mode 100644 (file)
index 0000000..05962ef
--- /dev/null
@@ -0,0 +1,100 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+#ifndef __states_h__
+#define __states_h__
+
+#include <applicfg.h>
+
+///The nodes states 
+//-----------------
+/// values are choosen so, that they can be sent directly
+/// for heartbeat messages...
+/// Must be coded on 7 bits only
+/* Should not be modified */
+enum enum_nodeState {
+  Initialisation  = 0x00, 
+  Disconnected    = 0x01,
+  Connecting      = 0x02,
+  Preparing       = 0x02,
+  Stopped         = 0x04,
+  Operational     = 0x05,
+  Pre_operational = 0x7F,
+  Unknown_state   = 0x0F
+};
+
+typedef enum enum_nodeState e_nodeState;
+
+typedef struct
+{
+       UNS8 csBoot_Up;
+       UNS8 csSDO;
+       UNS8 csEmergency;
+       UNS8 csSYNC;
+       UNS8 csHeartbeat;
+       UNS8 csPDO;
+} s_state_communication;
+
+/** Function that user app must provide
+ * 
+ */
+typedef void (*initialisation_t)(void);
+typedef void (*preOperational_t)(void);
+typedef void (*operational_t)(void);
+typedef void (*stopped_t)(void);
+
+#include "data.h"
+
+/************************* prototypes ******************************/
+
+/** Called by driver/app when receiving messages
+*/
+void canDispatch(CO_Data* d, Message *m);
+
+/** Returns the state of the node 
+*/
+e_nodeState getState (CO_Data* d);
+
+/** Change the state of the node 
+*/
+UNS8 setState (CO_Data* d, e_nodeState newState);
+
+/** Returns the nodId 
+*/
+UNS8 getNodeId (CO_Data* d);
+
+/** Define the node ID. Initialize the object dictionary
+*/
+void setNodeId (CO_Data* d, UNS8 nodeId);
+
+/** Some stuff to do when the node enter in reset mode
+ *
+ */
+//void initResetMode (CO_Data* d);
+
+
+/** Some stuff to do when the node enter in pre-operational mode
+ *
+ */
+void initPreOperationalMode (CO_Data* d);
+
+#endif
diff --git a/app/cantest/canfestival/include/sync.h b/app/cantest/canfestival/include/sync.h
new file mode 100644 (file)
index 0000000..cf83581
--- /dev/null
@@ -0,0 +1,57 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+#ifndef __SYNC_h__
+#define __SYNC_h__
+
+void startSYNC(CO_Data* d);
+
+void stopSYNC(CO_Data* d);
+
+typedef void (*post_sync_t)(void);
+
+typedef void (*post_TPDO_t)(void);
+
+/** transmit a SYNC message on the bus number bus_id
+ * bus_id is hardware dependant
+ * return canSend(bus_id,&m)
+ */
+UNS8 sendSYNC (CO_Data* d, UNS32 cob_id);
+
+/** This function is called when the node is receiving a SYNC 
+ * message (cob-id = 0x80).
+ * What does the function :
+ * check if the node is in OERATIONAL mode. (other mode : return 0 but does nothing).
+ * Get the SYNC cobId by reading the dictionary index 1005. (Return -1 if it does not correspond 
+ * to the cobId received).
+ * Scan the dictionary from index 0x1800 to the last PDO defined (dict_cstes.max_count_of_PDO_transmit)
+ *   for each PDO whose transmission type is on synchro (transmission type < 241) and if the msg must
+ *   be send at this SYNC. read the COBID. Verify that the nodeId inside the 
+ *   nodeId correspond to bDeviceNodeId. (Assume that the cobId of a PDO Transmit is made 
+ *   with the node id of the node who transmit), get the mapping, launch PDOmGR to send the PDO
+ * *m is a pointer to the message received
+ * bus_id is hardware dependant
+ * return 0 if OK, 0xFF if error
+ */
+UNS8 proceedSYNC (CO_Data* d, Message * m);
+
+#endif
diff --git a/app/cantest/canfestival/include/timer.h b/app/cantest/canfestival/include/timer.h
new file mode 100644 (file)
index 0000000..28e11d7
--- /dev/null
@@ -0,0 +1,63 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+#ifndef __timer_h__
+#define __timer_h__
+
+#include <applicfg.h>
+
+#define TIMER_HANDLE INTEGER16
+
+#include "data.h"
+
+// --------- types et constants definitions ---------
+#define TIMER_FREE 0
+#define TIMER_ARMED 1
+#define TIMER_TRIG 2
+#define TIMER_TRIG_PERIOD 3
+
+#define TIMER_NONE -1
+
+typedef void (*TimerCallback_t)(CO_Data* d, UNS32 id);
+
+struct struct_s_timer_entry {
+       UNS8 state;
+       CO_Data* d;
+       TimerCallback_t callback; // The callback func.
+       UNS32 id; // The callback func.
+       TIMEVAL val;
+       TIMEVAL interval; // Periodicity
+};
+
+typedef struct struct_s_timer_entry s_timer_entry;
+
+// ---------  prototypes ---------
+//#define SetAlarm(d, id, callback, value, period) printf("%s, %d, SetAlarm(%s, %s, %s, %s, %s)\n",__FILE__, __LINE__, #d, #id, #callback, #value, #period); _SetAlarm(d, id, callback, value, period)
+TIMER_HANDLE SetAlarm(CO_Data* d, UNS32 id, TimerCallback_t callback, TIMEVAL value, TIMEVAL period);
+TIMER_HANDLE DelAlarm(TIMER_HANDLE handle);
+void TimeDispatch(void);
+
+// ---------  to be defined in user app ---------
+void setTimer(TIMEVAL value);
+TIMEVAL getElapsedTime(void);
+
+#endif // #define __timer_h__
diff --git a/app/cantest/canfestival/odstraneni-potize.txt b/app/cantest/canfestival/odstraneni-potize.txt
new file mode 100644 (file)
index 0000000..510a700
--- /dev/null
@@ -0,0 +1,15 @@
+home/mareks1/edk2638/mareks1-canfestival/libs4c/canfestival/src/lifegrd.c:89: warning: implicit declaration of function `sendPDOevent'
+    - jenom warning, reseni pridam pdo.h
+    
+stav: Initialisation(); -> initTimer();
+
+
+dacas:
+MSG_WAR(0x3400, "NMT received. for node :  ", (*m).data[1]);
+
+veci co se mi nelibi:
+v appli.c se mi to nelibi :(
+// Interruption timer 3
+void __attribute__((interrupt)) timer3Hdl (void)
+
+07062006 - Timer for CANopen timing
\ No newline at end of file
diff --git a/app/cantest/canfestival/src/Makefile b/app/cantest/canfestival/src/Makefile
new file mode 100644 (file)
index 0000000..f595272
--- /dev/null
@@ -0,0 +1,14 @@
+# Generic directory or leaf node makefile for OCERA make framework
+
+ifndef MAKERULES_DIR
+MAKERULES_DIR := $(shell ( old_pwd="" ;  while [ ! -e Makefile.rules ] ; do if [ "$$old_pwd" == `pwd`  ] ; then exit 1 ; else old_pwd=`pwd` ; cd -L .. 2>/dev/null ; fi ; done ; pwd ) )
+endif
+
+ifeq ($(MAKERULES_DIR),)
+all : default
+.DEFAULT::
+       @echo -e "\nThe Makefile.rules has not been found in this or partent directory\n"
+else   
+include $(MAKERULES_DIR)/Makefile.rules
+endif
+
diff --git a/app/cantest/canfestival/src/Makefile.omk b/app/cantest/canfestival/src/Makefile.omk
new file mode 100644 (file)
index 0000000..8ccb3c3
--- /dev/null
@@ -0,0 +1,10 @@
+lib_LIBRARIES = canfestival
+
+#include_HEADERS = 
+
+canfestival_SOURCES = lifegrd.c nmtMaster.c nmtSlave.c \
+               objacces.c pdo.c sdo.c sync.c timer.c lss.c states.c
+
+#lib_LOADLIBES = 
+#bin_PROGRAMS = 
+
diff --git a/app/cantest/canfestival/src/lifegrd.c b/app/cantest/canfestival/src/lifegrd.c
new file mode 100644 (file)
index 0000000..1f320e6
--- /dev/null
@@ -0,0 +1,158 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+#include <data.h>
+#include "lifegrd.h"
+
+e_nodeState getNodeState (CO_Data* d, UNS8 nodeId)
+{
+       e_nodeState networkNodeState = d->NMTable[nodeId];
+       return networkNodeState;
+}
+
+// The Consumer Timer Callback
+void ConsumerHearbeatAlarm(CO_Data* d, UNS32 id)
+{
+        //MSG_WAR(0x00, "ConsumerHearbeatAlarm", 0x00);
+       
+       // call heartbeat error with NodeId
+       (*d->heartbeatError)((UNS8)( ((d->ConsumerHeartbeatEntries[id]) & (UNS32)0x00FF0000) >> (UNS8)16 ));
+}
+
+/* Retourne le node-id */
+void proceedNODE_GUARD(CO_Data* d, Message* m )
+{
+  UNS8 nodeId = (UNS8) GET_NODE_ID((*m));
+  
+  if((m->rtr == 1) ) /* Notice that only the master can have sent this node guarding request */
+  { // Receiving a NMT NodeGuarding (request of the state by the master)
+    //  only answer to the NMT NodeGuarding request, the master is not checked (not implemented)
+    if (nodeId == *d->bDeviceNodeId )
+    {
+      Message msg;
+      msg.cob_id.w = *d->bDeviceNodeId + 0x700;
+      msg.len = (UNS8)0x01;
+      msg.rtr = 0;
+      msg.data[0] = d->nodeState; 
+      if (d->toggle)
+      {
+        msg.data[0] |= 0x80 ;
+        d->toggle = 0 ;
+      }
+      else
+        d->toggle = 1 ; 
+      // send the nodeguard response.
+      MSG_WAR(0x3130, "Sending NMT Nodeguard to master, state: ", d->nodeState);
+      (*d->canSend)(&msg );
+    }  
+
+  }else{ // Not a request CAN  
+
+    MSG_WAR(0x3110, "Received NMT nodeId : ", nodeId);
+    /* the slave's state receievd is stored in the NMTable */
+      // The state is stored on 7 bit
+    d->NMTable[nodeId] = (e_nodeState) ((*m).data[0] & 0x7F) ;
+    
+    /* Boot-Up frame reception */
+    if ( d->NMTable[nodeId] == Initialisation)
+      {
+        // The device send the boot-up message (Initialisation)
+        // to indicate the master that it is entered in pre_operational mode
+        // Because the  device enter automaticaly in pre_operational mode,
+        // the pre_operational mode is stored 
+//        NMTable[bus_id][nodeId] = Pre_operational;
+        MSG_WAR(0x3100, "The NMT is a bootup from node : ", nodeId);
+      }
+      
+    if( d->NMTable[nodeId] != Unknown_state ) {
+        UNS8 index, ConsummerHeartBeat_nodeId ;
+        for( index = (UNS8)0x00; index < *d->ConsumerHeartbeatCount; index++ )
+        {
+            ConsummerHeartBeat_nodeId = (UNS8)( ((d->ConsumerHeartbeatEntries[index]) & (UNS32)0x00FF0000) >> (UNS8)16 );
+            if ( nodeId == ConsummerHeartBeat_nodeId )
+            {
+                TIMEVAL time = ( (d->ConsumerHeartbeatEntries[index]) & (UNS32)0x0000FFFF ) ;
+               // Renew alarm for next heartbeat.
+               DelAlarm(d->ConsumerHeartBeatTimers[index]);
+               d->ConsumerHeartBeatTimers[index] = SetAlarm(d, index, &ConsumerHearbeatAlarm, MS_TO_TIMEVAL(time), 0);
+            }
+        }
+    }
+  }
+}
+
+// The Consumer Timer Callback
+void ProducerHearbeatAlarm(CO_Data* d, UNS32 id)
+{
+       if(*d->ProducerHeartBeatTime)
+       {
+               Message msg;
+               // Time expired, the heartbeat must be sent immediately
+               // generate the correct node-id: this is done by the offset 1792
+               // (decimal) and additionaly
+               // the node-id of this device.
+               msg.cob_id.w = *d->bDeviceNodeId + 0x700;
+               msg.len = (UNS8)0x01;
+               msg.rtr = 0;
+               msg.data[0] = d->nodeState; // No toggle for heartbeat !
+               // send the heartbeat
+               MSG_WAR(0x3130, "Producing heartbeat: ", d->nodeState);
+               (*d->canSend)(&msg );
+       }else{
+               d->ProducerHeartBeatTimer = DelAlarm(d->ProducerHeartBeatTimer);
+       }
+}
+
+
+void heartbeatInit(CO_Data* d)
+{
+  UNS8 index; // Index to scan the table of heartbeat consumers
+
+    for( index = (UNS8)0x00; index < *d->ConsumerHeartbeatCount; index++ )
+    {
+        TIMEVAL time = (UNS16) ( (d->ConsumerHeartbeatEntries[index]) & (UNS32)0x0000FFFF ) ;
+        //MSG_WAR(0x3121, "should_time : ", should_time ) ;
+        if ( time )
+        {
+               d->ConsumerHeartBeatTimers[index] = SetAlarm(d, index, &ConsumerHearbeatAlarm, MS_TO_TIMEVAL(time), 0);
+        }
+    }
+
+    if ( *d->ProducerHeartBeatTime )
+    {
+       TIMEVAL time = *d->ProducerHeartBeatTime;
+       d->ProducerHeartBeatTimer = SetAlarm(d, 0, &ProducerHearbeatAlarm, MS_TO_TIMEVAL(time), MS_TO_TIMEVAL(time));
+    }
+}
+
+
+void heartbeatStop(CO_Data* d)
+{
+    UNS8 index;
+    for( index = (UNS8)0x00; index < *d->ConsumerHeartbeatCount; index++ )
+    {
+        d->ConsumerHeartBeatTimers[index + 1] = DelAlarm(d->ConsumerHeartBeatTimers[index + 1]);;
+    }
+
+    d->ProducerHeartBeatTimer = DelAlarm(d->ProducerHeartBeatTimer);;
+}
+
diff --git a/app/cantest/canfestival/src/lss.c b/app/cantest/canfestival/src/lss.c
new file mode 100644 (file)
index 0000000..ac2e411
--- /dev/null
@@ -0,0 +1,730 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack.
+
+ Author: Christian Fortin (canfestival@canopencanada.ca)
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+#include <applicfg.h>
+#include <def.h>
+
+#include <can.h>
+#include <objdictdef.h>
+#include <objacces.h>
+//#include "can_driver.h"
+
+#ifdef LED_ENABLE
+//#include "led.h"
+#endif
+
+#include "lss.h"
+
+
+
+/*
+       NOTES
+
+       1. since in the LSS protocol all LSS Slave use the same COB, only 1 Slave
+       must be allowed to communicate with the Master
+
+       2. the Master always take the iniative. the Slave is only allowed to transmit
+       within a confirmed service
+
+       3. requesting message (from the Master) using COB-ID 2021 and response messages
+       (from the Slave) using COB-ID 2020
+*/
+
+/*
+       0 = this is a slave
+       1 = this is the Master 
+*/
+int    i_am_the_master; 
+
+/*
+       0 = this slave is not talking to the master
+       1 = this slave is talking to the master (this slave has been selected via )
+*/
+int    slave_selector;
+
+int    current_mode;
+
+int    lss_table_selector, lss_table_index;
+
+
+/* slave storing the information sent by the master */
+unsigned long lss_buffer[10];
+/*
+       how this buffer is used
+
+       for a SLAVE 
+       [0..3]  used to store the LSS Address
+       [4..9]  use by LSS Identify Remort Slave
+
+       for the MASTER
+       [0..3] hold the answer from the slave regarding its ID
+*/
+
+
+void lss_copy(UNS8 *data, unsigned long value)
+/* transfert 32 bits value into uns8 data vector */
+{
+       data[0] = value & 0xff;
+       data[1] = (value>>8) & 0xff;
+       data[2] = (value>>16) & 0xff;
+       data[3] = (value>>24) & 0xff;
+}
+
+
+unsigned long lss_get_value(UNS8 *data)
+/* build a 'unsigned long' value from a 'unsigned char' vector */
+{
+       return data[0] + (data[1]<<8) + (data[2]<<16) + (data[3]<<24);
+}
+
+
+void lss_init_msg(Message *msg)
+{
+       msg->cob_id.w = 0;
+       msg->rtr = 0;
+       msg->len = 0;
+       msg->data[0] = 0;
+       msg->data[1] = 0;
+       msg->data[2] = 0;
+       msg->data[3] = 0;
+       msg->data[4] = 0;
+       msg->data[5] = 0;
+       msg->data[6] = 0;
+       msg->data[7] = 0;
+}
+
+
+void lss_SwitchModeGlobal(unsigned int mode)
+/*
+       this service is used to switch all LSS slaves in the network between operation
+       mode and configuration mode.
+*/
+{      
+       Message msg;
+       lss_init_msg(&msg);
+
+       /* 
+               sending a COB-ID 2021
+               [0] = 4 (for switch mode global)
+               [1] = 0 for operation mode, = 1 for configuration mode
+               [2..7] = 0 reserved
+       */
+       
+       if (i_am_the_master == 1)
+       {
+               msg.cob_id.w = 0x07E5 /* 2021 */;
+
+               msg.len = 2;
+               msg.data[0] = 4;
+               msg.data[1] = (UNS8)mode;
+       
+               /* transmit */
+               f_can_send(0, &msg);
+       }
+       else
+       {
+               /* set mode global */
+               current_mode = mode;
+       }
+}
+
+
+void lss_SwitchModeSelective_master(unsigned long *LSSaddr)
+/*
+       LSS address : <vendor-id> <product-code> <revision-number> <serial-number>
+       vendor-id : provided by CiA
+       identical to the CANopen identity object
+
+       select the slave corresponding to this ADDRESS
+*/
+{
+       Message msg;
+       lss_init_msg(&msg);
+
+       if (i_am_the_master == 0) /* not the master */
+               return; 
+
+       msg.cob_id.w = 0x07E5 /* 2021 */;
+       msg.len=5;
+
+       msg.data[0] = 64;
+       lss_copy(msg.data+1, LSSaddr[0]); 
+       /* transmit */
+       f_can_send(0, &msg);
+
+       msg.data[0] = 65;
+       lss_copy(msg.data+1, LSSaddr[1]); 
+       /* transmit */
+       f_can_send(0, &msg);
+
+       msg.data[0] = 66;
+       lss_copy(msg.data+1, LSSaddr[2]); 
+       /* transmit */
+       f_can_send(0, &msg);
+
+       msg.data[0] = 67;
+       lss_copy(msg.data+1, LSSaddr[3]); 
+       /* transmit */
+       f_can_send(0, &msg);
+}
+
+
+int lss_validate_address()
+{
+       extern s_identity obj1018;
+
+       /* maybe we should go throught getODentry but those
+       data are 1) RO and 2) the proper ID of this device */
+#if 0 
+       UNS32  r, vendor_id, product_code, revision_number, serial_number;
+
+       r = getODentry(0x1018, 1, (void *)&vendor_id, &sz, &dt, 0);
+       r = getODentry(0x1018, 2, (void *)&product_code, &sz, &dt, 0);
+       r = getODentry(0x1018, 3, (void *)&revision_number, &sz, &dt, 0);
+       r = getODentry(0x1018, 4, (void *)&serial_number, &sz, &dt, 0);
+#endif
+       /*
+               if
+               lss_buffer[0] == vendor-id
+               lss_buffer[1] == product code
+               lss_buffer[2] == revision
+               lss_buffer[3] == serial
+
+               then return 1
+               else return 0;
+       */
+
+       if (lss_buffer[0] == obj1018.vendor_id  &&
+           lss_buffer[1] == obj1018.product_code &&
+           lss_buffer[2] == obj1018.revision_number &&
+           lss_buffer[3] == obj1018.serial_number)
+       {
+               return 1;
+       }
+
+       return 0;
+}
+
+
+void lss_SwitchModeSelective_slave(void)
+/* 
+       SwitchModeSelective for the SLAVE
+       received the frames from the master and start building 
+       the lss address 
+*/
+{
+       Message msg;
+       lss_init_msg(&msg);
+
+       /*
+               the master broadcast the address of a particular slave
+               for 64,65 and 66 store the partial address
+               when 67 arrive process the call and asknowledge if necessary
+       */
+
+       if (lss_validate_address())
+       {
+               /* slave should transmit cob_id 2020  */
+               msg.cob_id.w = 0x07E4 /* 2020 */;
+
+               msg.len = 2;
+               msg.data[0] = 68;
+               msg.data[1] = (UNS8)current_mode;
+
+               /* transmit */
+               f_can_send(0, &msg);
+       }
+
+       /* reset the address */
+       lss_buffer[0] = 0;
+       lss_buffer[1] = 0;
+       lss_buffer[2] = 0;
+       lss_buffer[3] = 0;
+}
+
+
+void lss_ConfigureNode_ID(unsigned int node_id)
+/*
+       through this service the LSS Master configures the NMT-address
+       parameter of a LSS slave.
+*/
+{
+       Message msg;
+       lss_init_msg(&msg);
+
+       if (i_am_the_master == 1)
+       {
+               msg.cob_id.w = 0x07E5 /* 2021 */;
+
+               msg.len = 2;
+               msg.data[0] = 17;
+               msg.data[1] = (UNS8)node_id;
+
+               /* transmit */
+               f_can_send(0, &msg);
+       }
+       else
+       {
+               /*
+                       receiving NODE ID from the master
+               */
+
+               /*
+                       error code 
+                       0 = success
+                       1 = node id out of range
+                       2..254 = reserved
+                       255 = implementation specific error occured
+                               spec error = mode detailed error
+               */
+               msg.cob_id.w = 0x07E4 /* 2020 */;
+
+               msg.len = 3;
+               msg.data[0] = 17;
+               /* msg.data[1] = error code */
+               /* msg.data[2] = spec error */
+
+               /* transmit */
+               f_can_send(0, &msg);
+       }
+}
+
+
+void lss_ConfigureBitTimingParameters(unsigned int table_selector,
+                                      unsigned int table_index)
+/*
+       this service allows all LSS slaves in configuration mode.
+       must be followed by an Activate Bit Timing Parameters
+*/
+{
+       Message msg;
+       lss_init_msg(&msg);
+
+       if (i_am_the_master == 1)
+       {
+               msg.cob_id.w = 0x07E5 /* 2021 */;
+
+               msg.len = 3;
+               msg.data[0] = 19;
+               msg.data[1] = (UNS8)table_selector;
+               msg.data[2] = (UNS8)table_index;
+
+               /* transmit */
+               f_can_send(0, &msg);
+       }
+       else
+       {
+               UNS8 error_code;
+
+               /* validate if this baudrate is possible */
+               if (table_selector == 0  &&  baudrate_valid(table_index) == 1)
+               {
+                       lss_table_selector = table_selector;
+                       lss_table_index = table_index;
+               }
+               else
+                       error_code = 1; /* bit timing not supported */
+
+               msg.cob_id.w = 0x07E4 /* 2020 */;
+
+               msg.len = 3;
+               msg.data[0] = 19;
+               msg.data[1] = error_code;
+               msg.data[2] = 0;
+
+               /* transmit */
+               f_can_send(0, &msg);
+       }
+}
+
+
+void lss_ActivateBitTimingParameters_master(unsigned short switch_delay)
+/*
+       switch_delay in ms
+
+       switch_delay has to be longer than the longest timeof any node
+       in the network to avoid that a node already switches while another
+       stills transmist the old bit timing parameters
+*/
+{
+       Message msg;
+       lss_init_msg(&msg);
+
+       if (i_am_the_master == 0)
+               return;
+       
+       msg.cob_id.w = 0x07E5 /* 2021 */;
+
+       msg.len = 3;
+       msg.data[0] = 21;
+       msg.data[1] = (UNS8)(switch_delay &  0xff);
+       msg.data[2] = (UNS8)((switch_delay >> 8) & 0xff);
+
+#ifdef LED_ENABLE
+       led_set_state(LED_AUTOBITRATE);         
+#endif
+       /* transmit */
+       f_can_send(0, &msg);
+}
+
+
+void lss_ActivateBitTimingParameters_slave(UNS8 data1, UNS8 data2)
+{
+       /* rebuild the delay value (short) from the 2 (UNS8) data */
+       unsigned short switch_delay = data1 + (((unsigned short)data2)<<8);
+
+       /* set the baudrate to the value proposed by the master */
+       if (lss_table_selector == 0)
+               baudrate_set(lss_table_index);
+
+       /* wait for switch_delay ms before continuing */
+}
+
+
+void lss_StoreConfiguredParameters()
+/*
+       store configured parameters into non-volatile storage
+*/
+{
+       Message msg;
+       lss_init_msg(&msg);
+
+       if (i_am_the_master == 1)
+       {
+               msg.cob_id.w = 0x07E5 /* 2021 */;
+
+               msg.len = 1;
+               msg.data[0] = 23;
+
+               /* transmit */
+               f_can_send(0, &msg);
+       }
+       else
+       {
+               msg.cob_id.w = 0x07E4 /* 2020 */;
+
+               msg.data[0] = 23;
+               /* msg.data[1] = error code; */
+               /* msg.data[2] = spec err */
+               
+               /* transmit */
+               f_can_send(0, &msg);
+       }
+}
+
+
+void lss_InquireLSSAddress_master(int flag)
+/*
+       this service allows to determine the LSS-address parameters of a LSS-slave in
+       configuration mode
+
+       request 1 single item of the LSS address
+       0 = request vendor-id
+       1 = request product-id
+       2 = request revision
+       3 = request serial
+*/
+{
+       Message msg;
+       lss_init_msg(&msg);
+
+       if (i_am_the_master == 1)
+       {
+               msg.cob_id.w = 0x07E5 /* 2021 */;
+
+               msg.len = 1;
+               msg.data[0] = 90 + flag;
+       
+               /* transmit */
+               f_can_send(0, &msg);
+       }
+}
+
+
+int lss_InquireLSSAddress_slave(int cs)
+{
+       Message msg;
+       lss_init_msg(&msg);
+
+       if (i_am_the_master == 1) /* not a slave */
+               return -1;
+
+       unsigned long value = 0;
+
+       switch(cs)
+       {
+               case 90:
+                       value = 0; /* = vendor id */
+                       break;
+               case 91:
+                       value = 0; /* = product code */
+                       break;
+               case 92:
+                       value = 0; /* = revision */
+                       break;
+               case 93:
+                       value = 0; /* = serial */
+                       break;
+       }
+
+       if (value > 0)
+       {
+               msg.cob_id.w = 0x07E4 /* 2020 */;
+       
+               msg.len=5;
+               msg.data[0] = cs;
+               lss_copy(msg.data+1, value);
+               
+               /* transmit */
+               f_can_send(0, &msg);
+
+               return 0;
+       }
+
+       return -1;
+}
+
+
+void lss_IdentifyRemoteSlaves(unsigned long vendor_id,
+                              unsigned long product_code,
+                              unsigned long rev_low,
+                              unsigned long rev_high,
+                              unsigned long serial_low,
+                              unsigned long serial_high)
+/*
+       throught this service, the LSS Master requests all LSS slave whose LSS address
+       meets the LSSaddr_sel to idenfity themselves through LSS Identify Slave
+*/
+{
+       Message msg;
+       lss_init_msg(&msg);
+
+       if (i_am_the_master == 1)
+       {
+               /*
+                       request answers from all slaves corresponding
+                       to the revision and serial range of values
+               */
+
+               msg.cob_id.w = 0x07E5 /* 2021 */;
+               msg.len=5;
+
+               msg.data[0] = 70;
+               lss_copy(msg.data+1, vendor_id);
+               /* transmit */
+               f_can_send(0, &msg);
+
+               msg.data[0] = 71;
+               lss_copy(msg.data+1, product_code); 
+               /* transmit */
+               f_can_send(0, &msg);
+       
+               msg.data[0] = 72; /* revision number low */
+               lss_copy(msg.data+1, rev_low);
+               /* transmit */
+               f_can_send(0, &msg);
+
+               msg.data[0] = 73; /* revision number high */
+               lss_copy(msg.data+1, rev_high);
+               /* transmit */
+               f_can_send(0, &msg);
+       
+               msg.data[0] = 74; /* serial number low */
+               lss_copy(msg.data+1, serial_low);
+               /* transmit */
+               f_can_send(0, &msg);
+
+               msg.data[0] = 75; /* serial number high */
+               lss_copy(msg.data+1, serial_high);
+               /* transmit */
+               f_can_send(0, &msg);
+       }
+}
+
+
+int lss_validate_range_addr(void)
+{
+       extern s_identity obj1018;
+
+       /*
+               if 
+
+               lss_buffer[4] == vendor_id
+               lss_buffer[5] == product code
+               lss_buffer[6] <= revision <= lss_buffer[7]
+               lss_buffer[8] <= serial <= lss_buffer[9]
+
+               then return 1
+               else return 0
+       */
+
+       if (lss_buffer[4] == obj1018.vendor_id  &&
+           lss_buffer[5] == obj1018.product_code &&
+           lss_buffer[6] <= obj1018.revision_number &&
+           obj1018.revision_number <= lss_buffer[7] &&
+           lss_buffer[8] <= obj1018.serial_number &&
+           obj1018.serial_number <= lss_buffer[9])
+       {
+               return 1;
+       }
+
+       return 0;
+}
+
+
+void lss_IdentifySlave()
+/*
+       through this service, an LSS slave indicates that it is a slave
+       with LSS address within the LSSaddr_sel
+*/
+{
+       Message msg;
+       lss_init_msg(&msg);
+
+       if (lss_validate_range_addr())
+       {
+               msg.cob_id.w = 0x07E4 /* 2020 */;
+
+               msg.len = 1;
+               msg.data[0] = 79;
+
+               /* transmit */
+               f_can_send(0, &msg);
+       }
+
+       /* reset */
+       lss_buffer[4] = 0;
+       lss_buffer[5] = 0;
+       lss_buffer[6] = 0;
+       lss_buffer[7] = 0;
+       lss_buffer[8] = 0;
+       lss_buffer[9] = 0;
+}
+
+
+int lss_process_msg(Message *msg)
+{
+       /* process the incoming message */
+       if (msg->cob_id.w == 0x07E4 /* 2020 */)
+       {
+               // should be the master
+               // a slave just answered
+               switch(msg->data[0])
+               {
+                       /* slave acknowledging the SwitchModeSelective call */
+                       case 68: 
+                               /* msg->data[1] contains the 'mode global' value from the slave*/
+                               break;
+
+                       /* a slave had acknowledged the call from LSS Identify Remote Slave */
+                       case 79:
+                               break;
+
+                       /* the slave acknowledged and sent the requested data */
+                       case 90:
+                               lss_buffer[0] = lss_get_value(msg->data+1);
+                               /* action ? */
+                               break;
+                       case 91:
+                               lss_buffer[1] = lss_get_value(msg->data+1);
+                               /* action ? */
+                               break;
+                       case 92:
+                               lss_buffer[2] = lss_get_value(msg->data+1);
+                               /* action ? */
+                               break;
+                       case 93:
+                               lss_buffer[3] = lss_get_value(msg->data+1);
+                               /* action ? */
+                               break;
+               }
+       }
+
+       else if (msg->cob_id.w == 0x07E5 /* 2021 */)
+       {
+               // should be a slave
+               // the master sent a request
+               switch(msg->data[0])
+               {
+                       case 4:
+                               lss_SwitchModeGlobal(msg->data[1]);
+                               break;
+
+                       case 17:
+                               lss_ConfigureNode_ID(msg->data[1]);
+                               break;
+
+                       case 19:
+                               lss_ConfigureBitTimingParameters(msg->data[1], msg->data[2]);
+                               break;
+                       case 21:
+                               lss_ActivateBitTimingParameters_slave(msg->data[1], msg->data[2]);
+                               break;
+
+                       /* Switch Mode Selective */
+                       case 64:
+                               lss_buffer[0] = lss_get_value(msg->data+1);
+                               break;
+                       case 65:
+                               lss_buffer[1] = lss_get_value(msg->data+1);
+                               break;
+                       case 66:
+                               lss_buffer[2] = lss_get_value(msg->data+1);
+                               break;
+                       case 67:
+                               lss_buffer[3] = lss_get_value(msg->data+1);
+                               lss_SwitchModeSelective_slave();
+                               break;
+
+                       /* Identify Remote Slave */
+                       case 70:
+                               lss_buffer[4] = lss_get_value(msg->data+1);
+                               break;
+                       case 71:
+                               lss_buffer[5] = lss_get_value(msg->data+1);
+                               break;
+                       case 72:
+                               lss_buffer[6] = lss_get_value(msg->data+1);
+                               break;
+                       case 73:
+                               lss_buffer[7] = lss_get_value(msg->data+1);
+                               break;
+                       case 74:
+                               lss_buffer[8] = lss_get_value(msg->data+1);
+                               break;
+                       case 75:
+                               lss_buffer[9] = lss_get_value(msg->data+1);
+                               lss_IdentifySlave();
+                               break;
+
+                       /* Inquire Identify of Slave */
+                       case 90:
+                       case 91:
+                       case 92:
+                       case 93:
+                               lss_InquireLSSAddress_slave(msg->data[0]);
+                               break;
+               }
+       }
+
+       return 0;
+}
diff --git a/app/cantest/canfestival/src/nmtMaster.c b/app/cantest/canfestival/src/nmtMaster.c
new file mode 100644 (file)
index 0000000..ccc2930
--- /dev/null
@@ -0,0 +1,83 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+#include "nmtMaster.h"
+
+/******************************************************************************/
+UNS8 masterSendNMTstateChange(CO_Data* d, UNS8 Node_ID, UNS8 cs)
+{
+  Message m;
+
+  MSG_WAR(0x3501, "Send_NMT cs : ", cs);
+  MSG_WAR(0x3502, "    to node : ", Node_ID);
+  /* message configuration */
+  m.cob_id.w = 0x0000; /*(NMT) << 7*/
+  m.rtr = NOT_A_REQUEST;
+  m.len = 2;
+  m.data[0] = cs;
+  m.data[1] = Node_ID;
+  
+  return (*d->canSend)(&m);
+}
+
+
+/****************************************************************************/
+UNS8 masterSendNMTnodeguard(CO_Data* d, UNS8 nodeId)
+{
+  Message m;
+  
+  MSG_WAR(0x3503, "Send_NODE_GUARD to node : ", nodeId);
+       
+  /* message configuration */
+  m.cob_id.w = nodeId | (NODE_GUARD << 7);
+  m.rtr = REQUEST;
+  m.len = 1;
+  
+  return (*d->canSend)(&m);
+}
+
+/******************************************************************************/
+void masterRequestNodeState(CO_Data* d, UNS8 nodeId)
+{
+  // FIXME: should warn for bad toggle bit.
+
+  /* NMTable configuration to indicate that the master is waiting
+   * for a Node_Guard frame from the slave whose node_id is ID */
+  d->NMTable[nodeId] = Unknown_state; // A state that does not exist
+
+  if (nodeId == 0) { // NMT broadcast
+    UNS8 i = 0;
+    for (i = 0 ; i < NMT_MAX_NODE_ID ; i++) {
+      d->NMTable[i] = Unknown_state;
+    }
+  }
+  masterSendNMTnodeguard(d,nodeId);
+}
+
+
+
+
+
+
+
+
+
diff --git a/app/cantest/canfestival/src/nmtSlave.c b/app/cantest/canfestival/src/nmtSlave.c
new file mode 100644 (file)
index 0000000..b090902
--- /dev/null
@@ -0,0 +1,89 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+#include "nmtSlave.h"
+#include "states.h"
+
+/*******************************************************************)*********/
+/* put the slave in the state wanted by the master */  
+void proceedNMTstateChange(CO_Data* d, Message *m)
+{
+  if( d->nodeState == Pre_operational ||
+      d->nodeState == Operational ||
+      d->nodeState == Stopped ) {
+    
+    MSG_WAR(0x3400, "NMT received. for node :  ", (*m).data[1]);
+    
+    // Check if this NMT-message is for this node
+    // byte 1 = 0 : all the nodes are concerned (broadcast)
+       
+    if( ( (*m).data[1] == 0 ) || ( (*m).data[1] == *d->bDeviceNodeId ) ){
+      
+      switch( (*m).data[0]){ // command specifier (cs)                 
+      case NMT_Start_Node:
+        if ( (d->nodeState == Pre_operational) || (d->nodeState == Stopped) )
+          setState(d,Operational);
+        break; 
+        
+      case NMT_Stop_Node:
+        if ( d->nodeState == Pre_operational ||
+            d->nodeState == Operational )
+          setState(d,Stopped);
+        break;
+        
+      case NMT_Enter_PreOperational:
+        if ( d->nodeState == Operational || 
+            d->nodeState == Stopped )
+         setState(d,Pre_operational);
+        break;
+        
+      case NMT_Reset_Node:
+          setState(d,Initialisation);
+        break;
+        
+      case NMT_Reset_Comunication:
+          setState(d,Initialisation);
+        break;
+        
+      }// end switch
+      
+    }// end if( ( (*m).data[1] == 0 ) || ( (*m).data[1] == bDeviceNodeId ) )
+  }
+}
+
+
+/*****************************************************************************/
+UNS8 slaveSendBootUp(CO_Data* d)
+{
+  Message m;
+       
+  MSG_WAR(0x3407, "Send a Boot-Up msg ", 0);
+       
+  /* message configuration */
+  m.cob_id.w = NODE_GUARD << 7 | *d->bDeviceNodeId;
+  m.rtr = NOT_A_REQUEST;
+  m.len = 1;
+  m.data[0] = 0x00;
+    
+  return (*d->canSend)(&m);
+}
+
diff --git a/app/cantest/canfestival/src/objacces.c b/app/cantest/canfestival/src/objacces.c
new file mode 100644 (file)
index 0000000..135e079
--- /dev/null
@@ -0,0 +1,186 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+#include "objacces.h"
+
+UNS8 accessDictionaryError(UNS16 index, UNS8 subIndex, 
+                            UNS8 sizeDataDict, UNS8 sizeDataGiven, UNS32 code)
+{
+  MSG_WAR(0x2B09,"Dictionary index : ", index);
+  MSG_WAR(0X2B10,"           subindex : ", subIndex);
+  switch (code) {
+    case  OD_NO_SUCH_OBJECT: 
+      MSG_WAR(0x2B11,"Index not found ", index);
+      break;
+    case OD_NO_SUCH_SUBINDEX :
+      MSG_WAR(0x2B12,"SubIndex not found ", subIndex);
+      break;   
+    case OD_WRITE_NOT_ALLOWED :
+      MSG_WAR(0x2B13,"Write not allowed, data is read only ", index);
+      break;         
+    case OD_LENGTH_DATA_INVALID :    
+      MSG_WAR(0x2B14,"Conflict size data. Should be (bytes)  : ", sizeDataDict);
+      MSG_WAR(0x2B15,"But you have given the size  : ", sizeDataGiven);
+      break;
+    case OD_NOT_MAPPABLE :
+      MSG_WAR(0x2B16,"Not mappable data in a PDO at index    : ", index);
+      break;
+    case OD_VALUE_TOO_LOW :
+      MSG_WAR(0x2B17,"Value range error : value too low. SDOabort : ", code);
+      break;
+    case OD_VALUE_TOO_HIGH :
+      MSG_WAR(0x2B18,"Value range error : value too high. SDOabort : ", code);
+      break;
+  default :
+    MSG_WAR(0x2B20, "Unknown error code : ", code);
+  }
+  return 0; 
+}      
+
+
+UNS32 getODentry( CO_Data* d, 
+                  UNS16 wIndex,
+                 UNS8 bSubindex,
+                 void * * ppbData,
+                 UNS8 * pdwSize,
+                 UNS8 * pDataType,
+                 UNS8 checkAccess)
+{ // DO NOT USE MSG_ERR because the macro may send a PDO -> infinite loop if it fails.
+  UNS32 errorCode;
+  const indextable *ptrTable;
+  //MSG_WAR(0x3B40, "Read dico at index : ", wIndex);
+  //MSG_WAR(0x3B41, "           subIndex : ", bSubindex);
+  ptrTable = scanIndexOD(d, wIndex, &errorCode);
+  if (errorCode != OD_SUCCESSFUL)
+    return errorCode;
+  if( ptrTable->bSubCount <= bSubindex ) {
+    // Subindex not found
+    accessDictionaryError(wIndex, bSubindex, 0, 0, OD_NO_SUCH_SUBINDEX);
+    return OD_NO_SUCH_SUBINDEX;
+  }
+  
+  if (checkAccess && (ptrTable->pSubindex[bSubindex].bAccessType == WO)) {
+    accessDictionaryError(wIndex, bSubindex, 0, 0, OD_WRITE_NOT_ALLOWED);
+    return OD_READ_NOT_ALLOWED;
+  }
+
+  *ppbData = ptrTable->pSubindex[bSubindex].pObject;
+  *pdwSize = ptrTable->pSubindex[bSubindex].size;
+  *pDataType = ptrTable->pSubindex[bSubindex].bDataType;
+
+  return OD_SUCCESSFUL;
+}
+
+UNS32 setODentry( CO_Data* d, 
+                  UNS16 wIndex,
+                 UNS8 bSubindex, 
+                 void * pbData, 
+                 UNS8 dwSize, 
+                 UNS8 checkAccess)
+{
+  UNS8 szData;
+  UNS8 dataType;
+  UNS32 errorCode;
+  const indextable *ptrTable;
+
+  //MSG_WAR(0x3B30, "Write dico at index : ", wIndex);
+  //MSG_WAR(0x3B31, "           subIndex : ", bSubindex);
+
+  ptrTable = scanIndexOD(d, wIndex, &errorCode);
+  if (errorCode != OD_SUCCESSFUL)
+    return errorCode;
+
+  if( ptrTable->bSubCount <= bSubindex ) {
+    // Subindex not found
+    accessDictionaryError(wIndex, bSubindex, 0, dwSize, OD_NO_SUCH_SUBINDEX);
+    return OD_NO_SUCH_SUBINDEX;
+  }
+  szData = ptrTable->pSubindex[bSubindex].size;
+  dataType = ptrTable->pSubindex[bSubindex].bDataType;
+  if (szData != dwSize) {
+    if (! ((dataType == visible_string) && (dwSize < szData))) {// We allow to store a shorter string
+      accessDictionaryError(wIndex, bSubindex, szData, dwSize, OD_LENGTH_DATA_INVALID);
+      return OD_LENGTH_DATA_INVALID;
+    }
+  }
+  if (checkAccess && (ptrTable->pSubindex[bSubindex].bAccessType == RO)) {
+    accessDictionaryError(wIndex, bSubindex, 0, dwSize, OD_WRITE_NOT_ALLOWED);
+    return OD_WRITE_NOT_ALLOWED;
+  }
+  // Value range test
+  {
+    UNS32 tmpUNS32 = 0;
+    REAL32 tmpREAL32 = 0;
+    if (dwSize < 5) { // Value Range not tested for variables of more than 32 bits
+      memcpy(&tmpUNS32,pbData, dwSize );
+      memcpy(&tmpREAL32,pbData, dwSize );
+      errorCode = (*d->valueRangeTest)(dataType, tmpUNS32, tmpREAL32);
+      if (errorCode) {
+       accessDictionaryError(wIndex, bSubindex, szData, dwSize, errorCode);
+       return errorCode;
+      }
+    }
+  }
+
+  memcpy(
+        ptrTable->pSubindex[bSubindex].pObject,
+        pbData, dwSize );
+
+  return OD_SUCCESSFUL;
+}
+
+
+const indextable * scanIndexOD (CO_Data* d, UNS16 wIndex, UNS32 * errorCode)
+{ // DO NOT USE MSG_ERR because the macro may send a PDO -> infinite loop if it fails.
+  UNS16 min;
+  UNS16 max;
+  UNS16 current;
+  // Dichotomic search
+  min = 0;
+  max =  *d->ObjdictSize - 1;
+  current = *d->ObjdictSize >> 1;
+  *errorCode = OD_SUCCESSFUL; // Default value.
+  do {
+    if (wIndex < d->objdict[current].index ) {
+      max = current;
+      current = min + ((max - min) >> 1);
+      continue;
+    }
+    if (wIndex > d->objdict[current].index) {
+      min = current;
+      current = min + ((max - min) >> 1);
+      continue;
+    }
+    return &d->objdict[current];
+  } while ( (max - min) > 1);
+  
+  if (d->objdict[min].index == wIndex) {
+    return &d->objdict[min];
+  }
+  if (d->objdict[max].index == wIndex) {
+    return &d->objdict[max];
+  }
+  MSG_WAR(0x2B50, "Objdict Index not found : ", wIndex); 
+  *errorCode = OD_NO_SUCH_OBJECT;
+  return NULL; // index not found;
+}
+
diff --git a/app/cantest/canfestival/src/pdo.c b/app/cantest/canfestival/src/pdo.c
new file mode 100644 (file)
index 0000000..a0540b6
--- /dev/null
@@ -0,0 +1,537 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+#include "pdo.h"
+#include "objacces.h"
+
+
+#ifdef CANOPEN_BIG_ENDIAN
+#warning "pdo.c Compiling for big endian architecture"
+#else
+#warning "pdo.c Compiling for little endian architecture"
+#endif
+
+
+/****************************************************************************/
+UNS8 sendPDO(CO_Data* d, s_PDO pdo, UNS8 req)
+{
+  UNS8 i;
+  if( d->nodeState == Operational ) {
+    Message m;
+
+    /* Message copy for sending */
+    m.cob_id.w = pdo.cobId & 0x7FF; // Because the cobId is 11 bytes length
+    if ( req == NOT_A_REQUEST ) {
+      UNS8 i;
+      m.rtr = NOT_A_REQUEST;
+      m.len = pdo.len;
+      //memcpy(&m.data, &pdo.data, m.len);
+      // This Memcpy depends on packing structure. Avoid
+      for (i = 0 ; i < pdo.len ; i++)
+       m.data[i] = pdo.data[i];
+    }
+    else {
+      m.rtr = REQUEST;
+      m.len = 0;
+    }
+
+    MSG_WAR(0x3901, "sendPDO cobId :", m.cob_id.w);
+    MSG_WAR(0x3902,  "     Nb octets  : ",  m.len);
+    for (i = 0 ; i < m.len ; i++) {
+      MSG_WAR(0x3903,"           data : ", m.data[i]);
+    }
+                 
+    return (*d->canSend)(&m);
+  } // end if 
+  return 0xFF;
+}
+
+/***************************************************************************/
+UNS8 PDOmGR(CO_Data* d, UNS32 cobId) //PDO Manager
+{
+  UNS8 res;
+  UNS8 i;
+  s_PDO pdo;
+
+  MSG_WAR(0x3905, "PDOmGR",0);
+       
+  /* if PDO is waiting for transmission,
+     preparation of the message to send */
+    pdo.cobId = cobId;
+    pdo.len =  d->process_var.count;
+    //memcpy(&(pdo.data), &(process_var.data), pdo.len);
+    // Ce memcpy devrait Ãªtre portable
+    for ( i = 0 ; i < pdo.len ; i++) 
+      pdo.data[i] = d->process_var.data[i];
+
+    res = sendPDO(d, pdo, NOT_A_REQUEST);
+
+    return res;
+}
+
+/**************************************************************************/
+UNS8 buildPDO(CO_Data* d, UNS16 index)
+{ // DO NOT USE MSG_ERR because the macro may send a PDO -> infinite loop if it fails. 
+  UNS16 ind;
+  UNS8      subInd;
+
+  UNS8 *     pMappingCount = NULL;      // count of mapped objects...
+  // pointer to the var which is mapped to a pdo
+  void *     pMappedAppObject = NULL; 
+  // pointer fo the var which holds the mapping parameter of an mapping entry  
+  UNS32 *    pMappingParameter = NULL;  
+
+  UNS8 *    pSize;
+  UNS8      size;
+  UNS8      dataType;
+  UNS8      offset;
+  UNS16     offsetObjdict;
+  UNS16     offsetObjdictPrm;
+  UNS32     objDict;
+
+  pSize = &size;       
+  subInd=(UNS8)0x00;
+  offset = 0x00;
+  ind = index - 0x1800;
+  
+  MSG_WAR(0x3910,"Prepare PDO to send index :", index);
+
+  /* only operational state allows PDO transmission */
+  if( d->nodeState != Operational ) {
+    MSG_WAR(0x2911, "Unable to send the PDO (node not in OPERATIONAL mode). Node : ", index);
+    return 0xFF;
+  }
+  offsetObjdictPrm = d->firstIndex->PDO_TRS;
+  offsetObjdict = d->firstIndex->PDO_TRS_MAP;
+  
+  if (offsetObjdictPrm && offsetObjdict)
+  {
+         /* get mapped objects number to transmit with this PDO */
+         pMappingCount = (d->objdict + offsetObjdict + ind)->pSubindex[0].pObject;
+         MSG_WAR(0x3912, "Nb maped objects : ",* pMappingCount);
+         MSG_WAR(0x3913, "        at index : ", 0x1A00 + ind);
+         while (subInd < *pMappingCount) { // Loop on mapped variables
+           /* get mapping parameters */
+           pMappingParameter = (d->objdict + offsetObjdict + ind)->pSubindex[subInd + 1].pObject;
+           MSG_WAR(0x3914, "Get the mapping      at index : ", (UNS16)0x1A00 + ind);
+           MSG_WAR(0x3915, "                     subIndex : ", subInd + 1);
+           MSG_WAR(0x3916, "                     value    : ", *(UNS32 *)pMappingParameter);
+           // Get the mapped variable
+           objDict = getODentry(d, (UNS16)((*pMappingParameter) >> 16),
+                                   (UNS8)(((*pMappingParameter) >> 8 ) & 0x000000FF),
+                                   (void * *)&pMappedAppObject, pSize, &dataType, 0 ); 
+           MSG_WAR(0x3917, "Write in PDO the variable : ",
+                   ((*pMappingParameter) >> 16));
+           MSG_WAR(0x3918, "                 subIndex : ",
+                   (UNS8)(((*pMappingParameter) >> 8 ) & 0x000000FF));
+            if ((objDict != OD_SUCCESSFUL) || 
+                       (((UNS8)(((*pMappingParameter) & 0xFF) >> 3)) != *pSize )) {
+               MSG_WAR(0x2919, "error accessing to the mapped var : ", subInd + 1);  
+               MSG_WAR(0x2920, "         Mapped at index : ", (*pMappingParameter) >> 16);
+               MSG_WAR(0x2921, "                subindex : ", ((*pMappingParameter) >> 8 ) & 0xFF);
+               return 0xFF;
+            } 
+            else {
+             MSG_WAR(0x3922, "                 value    : ", *(UNS32*)pMappedAppObject);
+             memcpy(  &d->process_var.data[offset], pMappedAppObject,
+                      (*pMappingParameter & (UNS32)0x000000FF) >> 3 );
+       #     ifdef CANOPEN_BIG_ENDIAN
+             {
+               // data must be transmited with low byte first
+               UNS8 pivot, i;
+               UNS8 sizeData = (*pMappingParameter & (UNS32)0x000000FF) >> 3 ; // in bytes
+               for ( i = 0 ; i < ( sizeData >> 1)  ; i++) {
+                 pivot = d->process_var.data[offset + (sizeData - 1) - i];
+                 d->process_var.data[offset + (sizeData - 1) - i] = d->process_var.data[offset + i];
+                 d->process_var.data[offset + i] = pivot ;
+               }
+             }
+       #     endif
+             offset += (UNS8) ((*pMappingParameter & (UNS32)0x000000FF) >> 3) ;
+             d->process_var.count = offset;
+             subInd++;                                 
+           }
+           }// end Loop on mapped variables 
+  }
+  return 0;
+}
+
+/**************************************************************************/
+UNS8 sendPDOrequest( CO_Data* d, UNS32 cobId )
+{              
+  UNS32 *       pwCobId;       
+  UNS16          offset;
+  UNS16          lastIndex;
+  UNS8           err;
+
+  MSG_WAR(0x3930, "sendPDOrequest ",0);  
+  // Sending the request only if the cobid have been found on the PDO receive
+  // part dictionary
+  offset = d->firstIndex->PDO_RCV;
+  lastIndex = d->lastIndex->PDO_RCV;
+  if (offset)
+         while (offset <= lastIndex) {
+           /*get the CobId*/
+           pwCobId = d->objdict[offset].pSubindex[1].pObject;
+             
+           if ( *pwCobId  == cobId ) {
+             s_PDO pdo;
+             pdo.cobId = *pwCobId;
+             pdo.len = 0;
+             err  = sendPDO(d, pdo, REQUEST);  
+             return err;
+           }
+           offset++;
+         }
+  MSG_WAR(0x1931, "sendPDOrequest : COBID not found : ", cobId); 
+  return 0xFF;
+}
+
+
+
+/***********************************************************************/
+UNS8 proceedPDO(CO_Data* d, Message *m)
+{              
+  UNS8   numPdo;
+  UNS8   numMap;  // Number of the mapped varable                           
+  UNS8 i;
+  UNS8 *     pMappingCount = NULL;    // count of mapped objects...
+  // pointer to the var which is mapped to a pdo...
+  void *     pMappedAppObject = NULL;  
+  // pointer fo the var which holds the mapping parameter of an mapping entry
+  UNS32 *    pMappingParameter = NULL;  
+  UNS8  *    pTransmissionType = NULL; // pointer to the transmission type
+  UNS32 *    pwCobId = NULL;
+  UNS8  *    pSize;
+  UNS8       size;
+  UNS8       dataType;
+  UNS8       offset;
+  UNS8       status;
+  UNS32      objDict;
+  UNS16      offsetObjdict;
+  UNS16      lastIndex;
+  pSize = &size;
+  status = state1;
+
+  MSG_WAR(0x3935, "proceedPDO, cobID : ", ((*m).cob_id.w & 0x7ff)); 
+  offset = 0x00;
+  numPdo = 0;
+  numMap = 0;
+  if((*m).rtr == NOT_A_REQUEST ) { // The PDO received is not a request.
+    offsetObjdict = d->firstIndex->PDO_RCV;
+    lastIndex = d->lastIndex->PDO_RCV;
+
+    /* study of all the PDO stored in the dictionary */   
+    if(offsetObjdict)
+           while (offsetObjdict <= lastIndex) {
+                                       
+             switch( status ) {
+                                               
+               case state1:    /* data are stored in process_var array */
+                 //memcpy(&(process_var.data), &m->data, (*m).len);
+                 // Ce memcpy devrait Ãªtre portable.
+                 for ( i = 0 ; i < m->len ; i++) 
+                   d->process_var.data[i] = m->data[i];
+                 d->process_var.count = (*m).len;
+       
+                 status = state2; 
+                 break;
+       
+               case state2:
+                 /* get CobId of the dictionary correspondant to the received PDO */
+                 pwCobId = d->objdict[offsetObjdict].pSubindex[1].pObject;
+                 /* check the CobId coherance */
+                 //*pwCobId is the cobId read in the dictionary at the state 3
+                 if ( *pwCobId == (*m).cob_id.w ){
+                   // The cobId is recognized
+                   status = state4;
+                   MSG_WAR(0x3936, "cobId found at index ", 0x1400 + numPdo);
+                   break;
+                 }
+                 else {
+                   // cobId received does not match with those write in the dictionnary
+                   numPdo++;
+                   offsetObjdict++;
+                   status = state2;
+                   break;
+                 }
+       
+               case state4:    /* get mapped objects number */
+                 // The cobId of the message received has been found in the dictionnary.
+                 offsetObjdict = d->firstIndex->PDO_RCV_MAP;
+                 lastIndex = d->lastIndex->PDO_RCV_MAP;
+                 pMappingCount = (d->objdict + offsetObjdict + numPdo)->pSubindex[0].pObject;    
+                 numMap = 0;
+                 while (numMap < *pMappingCount) {
+                   pMappingParameter = (d->objdict + offsetObjdict + numPdo)->pSubindex[numMap + 1].pObject;
+                   if (pMappingParameter == NULL) {
+                     MSG_ERR(0x1937, "Couldn't get mapping parameter : ", numMap + 1); 
+                     return 0xFF;
+                   }
+                   // Get the addresse of the mapped variable.
+                   // detail of *pMappingParameter :
+                   // The 16 hight bits contains the index, the medium 8 bits contains the subindex, 
+                   // and the lower 8 bits contains the size of the mapped variable.
+       
+                   objDict = getODentry(d, (UNS16)((*pMappingParameter) >> 16),
+                                           (UNS8)(((*pMappingParameter) >> 8 ) & 0xFF),
+                                           (void * *)&pMappedAppObject, pSize, &dataType, 0 );
+                   if(objDict != OD_SUCCESSFUL) {
+                     MSG_ERR(0x1938, "error accessing to the mapped var : ", numMap + 1);  
+                     MSG_WAR(0x2939, "         Mapped at index : ", (*pMappingParameter) >> 16);
+                     MSG_WAR(0x2940, "                subindex : ", ((*pMappingParameter) >> 8 ) & 0xFF);
+                     return 0xFF;
+                   }
+                   if ((UNS8)(((*pMappingParameter) & 0xFF) >> 3) != *pSize) {
+                     MSG_ERR(0x1941, "error mapping : size does not match. var : ", numMap + 1); 
+                     return 0xFF;
+                   }
+                   
+                   // Update the variable
+       #           ifdef CANOPEN_BIG_ENDIAN
+                   {
+                     UNS8 pivot, i;
+                     UNS8 sizeData = (*pMappingParameter & 0xFF) >> 3 ; // in bytes
+                     for ( i = 0 ; i < ( sizeData >> 1)  ; i++) {
+                       pivot = d->process_var.data[offset + (sizeData - 1) - i];
+                       d->process_var.data[offset + (sizeData - 1) - i] = d->process_var.data[offset + i];
+                       d->process_var.data[offset + i] = pivot ;
+                     }
+                   }
+       #       endif
+       
+       
+       
+                   /*memcpy( pMappedAppObject, &process_var.data[offset],(((*pMappingParameter) & 0xFF ) >> 3));
+                   */
+                   // A bit more complicated than a memcpy if we wants to test the valueRange...
+                   {
+                     UNS32 tmpUNS32 = 0;
+                     REAL32 tmpREAL32 = 0;
+                     UNS32 errorCode;
+                     UNS8 sizeData = (*pMappingParameter & 0xFF) >> 3 ; // in bytes
+                     if (sizeData < 5) { // Value Range not tested for variables of more than 32 bits
+                       memcpy(&tmpUNS32, &d->process_var.data[offset],(((*pMappingParameter) & 0xFF ) >> 3));
+                       memcpy(&tmpREAL32, &d->process_var.data[offset],(((*pMappingParameter) & 0xFF ) >> 3));
+                       errorCode = (*d->valueRangeTest)(dataType, tmpUNS32, tmpREAL32);
+                       if (errorCode) {
+                         accessDictionaryError((*pMappingParameter) >> 16, 
+                                               ((*pMappingParameter) >> 8 ) & 0xFF, 0, 0, errorCode);
+                         return errorCode;
+                       }
+                     }       
+                   }
+       
+       
+                   memcpy( pMappedAppObject, &d->process_var.data[offset],(((*pMappingParameter) & 0xFF ) >> 3));
+                   MSG_WAR(0x3942, "Variable updated with value received by PDO cobid : ", m->cob_id.w);  
+                   MSG_WAR(0x3943, "         Mapped at index : ", (*pMappingParameter) >> 16);
+                   MSG_WAR(0x3944, "                subindex : ", ((*pMappingParameter) >> 8 ) & 0xFF);
+                   MSG_WAR(0x3945, "                data : ",*((UNS32 *)pMappedAppObject));
+                   offset += (UNS8) (((*pMappingParameter) & 0xFF) >> 3) ;
+                   numMap++;
+                 } // end loop while on mapped variables
+                 
+                 offset=0x00;          
+                 numMap = 0;
+                 return 0;
+                 
+             }// end switch status              
+           }// end while       
+  }// end if Donnees 
+
+
+  else if ((*m).rtr == REQUEST ){  
+      MSG_WAR(0x3946, "Receive a PDO request cobId : ", m->cob_id.w);
+      status = state1;
+      offsetObjdict = d->firstIndex->PDO_TRS;
+      lastIndex = d->lastIndex->PDO_TRS;
+      if(offsetObjdict) while( offsetObjdict  <= lastIndex ){ 
+       /* study of all PDO stored in the objects dictionary */
+
+       switch( status ){
+
+       case state1:    /* check the CobId */
+                       /* get CobId of the dictionary which match to the received PDO */
+         pwCobId = (d->objdict + offsetObjdict)->pSubindex[1].pObject;   
+         if ( *pwCobId == (*m).cob_id.w ) {
+           status = state4;
+           break;
+         }
+         else {
+           numPdo++;
+           offsetObjdict++;
+         }
+         status = state1;
+         break;
+
+
+       case state4:    /* check transmission type (after request?) */
+         pTransmissionType = d->objdict[offsetObjdict].pSubindex[2].pObject;
+         if ( (*pTransmissionType == TRANS_RTR) || (*pTransmissionType == TRANS_RTR_SYNC ) || (*pTransmissionType == TRANS_EVENT) ) {
+           status = state5;
+           break;
+         }
+         else {
+           // The requested PDO is not to send on request. So, does nothing.
+           MSG_WAR(0x2947, "PDO is not to send on request : ", m->cob_id.w);
+           return 0xFF;
+         }
+
+       case state5:    /* get mapped objects number */
+         offsetObjdict = d->firstIndex->PDO_TRS_MAP;
+         lastIndex = d->lastIndex->PDO_TRS_MAP;
+         pMappingCount = (d->objdict + offsetObjdict + numPdo)->pSubindex[0].pObject;
+         numMap = 0;
+         while (numMap < *pMappingCount) {
+           pMappingParameter = (d->objdict + offsetObjdict + numPdo)->pSubindex[numMap + 1].pObject;
+           // Get the mapped variable
+           objDict = getODentry( d, (UNS16)((*pMappingParameter) >> (UNS8)16), 
+                                    (UNS8)(( (*pMappingParameter) >> (UNS8)8 ) & 0xFF),
+                                    (void * *)&pMappedAppObject, pSize, &dataType, 0 );
+           if ((objDict != OD_SUCCESSFUL) || 
+               (((UNS8)(((*pMappingParameter) & 0xFF) >> 3)) != *pSize )) {
+             MSG_ERR(0x1948, "error accessing to the mapped var : ", numMap + 1);  
+             MSG_WAR(0x2949, "         Mapped at index : ", (*pMappingParameter) >> 16);
+             MSG_WAR(0x2950, "                subindex : ", ((*pMappingParameter) >> 8 ) & 0xFF);
+             return 0xFF;
+           }
+           memcpy(&d->process_var.data[offset], pMappedAppObject,
+                    ((*pMappingParameter) & 0xFF) >> 3 ); 
+#           ifdef CANOPEN_BIG_ENDIAN
+           {
+             UNS8 pivot, i;
+             UNS8 sizeData = (*pMappingParameter & (UNS32)0x000000FF) >> 3 ; // in bytes
+             for ( i = 0 ; i < ( sizeData >> 1)  ; i++) {
+               pivot = d->process_var.data[offset + (sizeData - 1) - i];
+               d->process_var.data[offset + (sizeData - 1) - i] = d->process_var.data[offset + i];
+               d->process_var.data[offset + i] = pivot;
+             }
+           }
+#           endif
+           offset += (UNS8) (((*pMappingParameter) & 0xFF) >> 3);
+           d->process_var.count = offset;
+           numMap++;
+
+         } // end while
+         PDOmGR( d, *pwCobId ); // Transmit the PDO
+         return 0;
+
+       }// end switch status
+      }// end while                            
+    }// end if Requete
+               
+  return 0;
+}
+
+
+
+
+/*********************************************************************/
+UNS8 sendPDOevent( CO_Data* d, void * variable )
+{ // DO NOT USE MSG_ERR because the macro may send a PDO -> infinite loop if it fails. 
+  UNS32           objDict = 0;
+  UNS8            ind, sub_ind;
+  UNS8            status; 
+  UNS8            offset;
+  UNS8 *     pMappingCount = NULL;
+  UNS32 *    pMappingParameter = NULL;
+  void *     pMappedAppObject = NULL;
+  UNS8 *     pTransmissionType = NULL; // pointer to the transmission type
+  UNS32 *    pwCobId = NULL;
+  UNS8 *     pSize;
+  UNS8       size;
+  UNS8       dataType;
+  UNS16      offsetObjdict;
+  UNS16      offsetObjdictPrm;
+  UNS16      lastIndex;
+  UNS8       numMap;
+  ind     = 0x00;
+  sub_ind = 1; 
+  offset  = 0x00;
+  pSize   = &size;
+  status  = state1;
+
+  // look for the index and subindex where the variable is mapped
+  // Then, send the pdo which contains the variable.
+
+  MSG_WAR (0x3960, "sendPDOevent", 0);
+  offsetObjdictPrm = d->firstIndex->PDO_TRS;
+  
+  offsetObjdict = d->firstIndex->PDO_TRS_MAP;
+  lastIndex = d->lastIndex->PDO_TRS_MAP;
+
+  if (offsetObjdictPrm && offsetObjdict) 
+         // Loop on PDO Transmit
+         while(offsetObjdict <= lastIndex){
+           // Check the transmission mode
+            MSG_WAR (0xf0f0, "offsetObjdict* <= lastIndex", offsetObjdict);
+          MSG_WAR (0xf0f0, "offsetObjdict <= lastIndex*", lastIndex); 
+           pTransmissionType = d->objdict[offsetObjdictPrm].pSubindex[2].pObject;
+           if (*pTransmissionType != TRANS_EVENT) {
+             ind++;
+             offsetObjdict++;  
+             offsetObjdictPrm++;
+             continue;
+           }
+           pMappingCount = d->objdict[offsetObjdict].pSubindex[0].pObject;
+           MSG_WAR (0xf0f0, "*pMappingCount", *pMappingCount);
+           numMap = 1; // mapped variable
+           while (numMap <= *pMappingCount) {
+              MSG_WAR (0xf0f1, "numMap <= *pMappingCount", 0);
+             pMappingParameter = d->objdict[offsetObjdict].pSubindex[numMap].pObject;
+             MSG_WAR (0xf0f0, "*pMappingParameter", *pMappingParameter);
+             // Get the variable
+             objDict = getODentry( d,
+                                   (UNS16)((*pMappingParameter) >> 16), 
+                                   (UNS8)(( (*pMappingParameter) >> (UNS8)8 ) & (UNS32)0x000000FF),
+                                   (void * *)&pMappedAppObject, pSize, &dataType, 0 );
+             if( objDict != OD_SUCCESSFUL ) {  
+               MSG_WAR(0x2961, "Error in dict. at index : ", 
+                       (*pMappingParameter) >> (UNS8)16);
+             
+               MSG_WAR(0x2962, "               subindex : ", 
+                       ((*pMappingParameter) >> (UNS8)8 ) & (UNS32)0x000000FF);
+               return 0xFF;
+             }
+             if (pMappedAppObject == variable) { // Variable found !
+               MSG_WAR(0x3963, "Variable to send found at index : ", 
+                       (*pMappingParameter) >> 16);
+               MSG_WAR(0x3964, "                       subIndex : ", 
+                       ((*pMappingParameter) >> 8 ) & 0x000000FF);
+               buildPDO(d, 0x1800 + ind);
+               // Get the cobId
+               pwCobId = d->objdict[offsetObjdictPrm].pSubindex[1].pObject;
+               PDOmGR( d, *pwCobId ); // Send the PDO
+               return 0;           
+             }
+             numMap++;
+           } // End loop on mapped variable
+           ind++;      
+           offsetObjdict++;  
+           offsetObjdictPrm++;
+         } // End loop while on PDO
+
+  MSG_WAR(0x2965, "Variable not found in a PDO to send on event", 0);
+  return 0xFF;
+
+}
+
diff --git a/app/cantest/canfestival/src/sdo.c b/app/cantest/canfestival/src/sdo.c
new file mode 100644 (file)
index 0000000..524ba56
--- /dev/null
@@ -0,0 +1,1323 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+//#define DEBUG_WAR_CONSOLE_ON
+//#define DEBUG_ERR_CONSOLE_ON
+
+#include "objacces.h"
+#include "sdo.h"
+
+#ifdef CANOPEN_BIG_ENDIAN
+#warning "sdo.c Compiling for big endian architecture"
+#else
+#warning "sdo.c Compiling for little endian architecture"
+#endif
+
+/***************************************************************************/
+// SDO (un)packing macros
+
+/** Returns the command specifier (cs, ccs, scs) from the first byte of the SDO   
+ */
+#define getSDOcs(byte) (byte >> 5)
+
+/** Returns the number of bytes without data from the first byte of the SDO. Coded in 2 bits   
+ */
+#define getSDOn2(byte) ((byte >> 2) & 3)
+
+/** Returns the number of bytes without data from the first byte of the SDO. Coded in 3 bits   
+ */
+#define getSDOn3(byte) ((byte >> 1) & 7)
+
+/** Returns the transfer type from the first byte of the SDO   
+ */
+#define getSDOe(byte) ((byte >> 1) & 1)
+
+/** Returns the size indicator from the first byte of the SDO   
+ */
+#define getSDOs(byte) (byte & 1)
+
+/** Returns the indicator of end transmission from the first byte of the SDO   
+ */
+#define getSDOc(byte) (byte & 1)
+
+/** Returns the toggle from the first byte of the SDO   
+ */
+#define getSDOt(byte) ((byte >> 4) & 1)
+
+/** Returns the index from the bytes 1 and 2 of the SDO   
+ */
+#define getSDOindex(byte1, byte2) ((byte2 << 8) | (byte1))
+
+/** Returns the subIndex from the byte 3 of the SDO   
+ */
+#define getSDOsubIndex(byte3) (byte3)
+
+/***************************************************************************
+**
+*/
+void SDOTimeoutAlarm(CO_Data* d, UNS32 id)
+{  /* !!! Caled in interrup routine !!! */
+    //MSG_ERR(0x1A01, "SDO timeout. SDO response not received.", 0);
+    //MSG_WAR(0x2A02, "server node : ", d->transfers[id].nodeId);
+    //MSG_WAR(0x2A02, "      index : ", d->transfers[id].index);
+    //MSG_WAR(0x2A02, "   subIndex : ", d->transfers[id].subIndex); 
+    // Reset timer handler
+    d->transfers[id].timer = TIMER_NONE;
+    // Call the user function to inform of the problem.
+    (*d->SDOtimeoutError)(id);
+    // Sending a SDO abort
+    sendSDOabort(d, d->transfers[id].whoami, 
+                d->transfers[id].index, d->transfers[id].subIndex, SDOABT_TIMED_OUT);
+    // Reset the line
+    resetSDOline(d, id);
+}
+
+#define StopSDO_TIMER(id) \
+MSG_WAR(0x3A05, "StopSDO_TIMER for line : ", line);\
+d->transfers[id].timer = DelAlarm(d->transfers[id].timer);
+
+#define StartSDO_TIMER(id) \
+MSG_WAR(0x3A06, "StartSDO_TIMER for line : ", line);\
+d->transfers[id].timer = SetAlarm(d,id,&SDOTimeoutAlarm,MS_TO_TIMEVAL(SDO_TIMEOUT_MS),0);
+
+#define RestartSDO_TIMER(id) \
+MSG_WAR(0x3A07, "restartSDO_TIMER for line : ", line);\
+if(d->transfers[id].timer != TIMER_NONE) { StopSDO_TIMER(id) StartSDO_TIMER(id) }
+
+/***************************************************************************/
+/** Reset all sdo buffers
+ */
+void resetSDO (CO_Data* d)
+{
+  UNS8 j;
+
+  /* transfer structure initialization */
+    for (j = 0 ; j < SDO_MAX_SIMULTANEOUS_TRANSFERTS ; j++) 
+      resetSDOline(d, j);
+}
+
+/***************************************************************************/
+UNS32 SDOlineToObjdict (CO_Data* d, UNS8 line)
+{
+  const indextable *ptrTable;
+  UNS8 i;
+  UNS8  data[SDO_MAX_LENGTH_TRANSFERT];
+  //UNS8 *    pSize;
+  UNS8      size;
+  UNS32 errorCode;
+  UNS8 dataType;
+
+  // Checking the type of data
+  ptrTable = scanIndexOD(d, d->transfers[line].index, &errorCode);
+  if (errorCode != OD_SUCCESSFUL)
+    return errorCode;
+  dataType = ptrTable->pSubindex[d->transfers[line].subIndex].bDataType;
+
+  // Put the value in the object dictionary.
+  size = d->transfers[line].count;
+  for  ( i = 0 ; i < size ; i++) {
+# ifdef CANOPEN_BIG_ENDIAN
+    if (dataType != visible_string)
+      data[size - 1 - i] = d->transfers[line].data[i];
+    else // String of bytes.
+      data[i] = d->transfers[line].data[i];
+# else 
+    data[i] = d->transfers[line].data[i];
+# endif
+  } 
+  
+  errorCode = setODentry(d, d->transfers[line].index, d->transfers[line].subIndex, 
+                        (void *) &data[0], size, 1);
+  if (errorCode != OD_SUCCESSFUL)
+    return errorCode;
+
+  return 0;
+
+}
+
+/***************************************************************************/
+UNS32 objdictToSDOline (CO_Data* d, UNS8 line)
+{
+  UNS8  j;
+  UNS8  *data;
+  UNS8  size;
+  UNS8  dataType;
+  UNS32 errorCode;
+
+  MSG_WAR(0x3A05, "Reading at index : ", d->transfers[line].index);
+  MSG_WAR(0x3A06, "Reading at subIndex : ", d->transfers[line].subIndex);
+  
+  errorCode = getODentry(d, d->transfers[line].index, d->transfers[line].subIndex, (void * *)&data, &size, & dataType, 0);
+  
+  if (errorCode != OD_SUCCESSFUL)
+    return errorCode;
+
+  MSG_WAR(0x3A07, "Found data type (see objdictdef.h) : ", dataType);
+  MSG_WAR(0x3A08, "Size of data (bytes) : ", size);
+
+  if (size > SDO_MAX_LENGTH_TRANSFERT) {
+    MSG_ERR(0x1A09,"SDO Size of data too large. Exceed SDO_MAX_LENGTH_TRANSFERT", size);
+    return SDOABT_OUT_OF_MEMORY;
+  }
+
+  // Copy data to transfers structure.
+  for (j = 0 ; j < size ; j++) {
+# ifdef CANOPEN_BIG_ENDIAN
+    if (dataType != visible_string)
+      d->transfers[line].data[size - 1 - j] = * (data + j);
+    else // String of bytes.
+      d->transfers[line].data[j] = * (data + j);
+#  else 
+    d->transfers[line].data[j] = * (data + j);
+#  endif
+  }
+  d->transfers[line].count = size;
+  d->transfers[line].offset = 0;
+  return 0;
+}
+
+/***************************************************************************/
+UNS8 lineToSDO (CO_Data* d, UNS8 line, UNS8 nbBytes, UNS8* data) {
+  UNS8 i;
+  UNS8 offset;
+
+  if ((d->transfers[line].offset + nbBytes) > SDO_MAX_LENGTH_TRANSFERT) {
+    MSG_ERR(0x1A10,"SDO Size of data too large. Exceed SDO_MAX_LENGTH_TRANSFERT", nbBytes);
+    return 0xFF;
+  }
+    if ((d->transfers[line].offset + nbBytes) > d->transfers[line].count) {
+    MSG_ERR(0x1A11,"SDO Size of data too large. Exceed count", nbBytes);
+    return 0xFF;
+  }
+  offset = d->transfers[line].offset;
+  for (i = 0 ; i < nbBytes ; i++) 
+    * (data + i) = d->transfers[line].data[offset + i];
+  d->transfers[line].offset = d->transfers[line].offset + nbBytes;
+  return 0;
+}
+
+
+/***************************************************************************/
+UNS8 SDOtoLine (CO_Data* d, UNS8 line, UNS8 nbBytes, UNS8* data)
+{
+  UNS8 i;
+  UNS8 offset;
+  
+  if ((d->transfers[line].offset + nbBytes) > SDO_MAX_LENGTH_TRANSFERT) {
+    MSG_ERR(0x1A15,"SDO Size of data too large. Exceed SDO_MAX_LENGTH_TRANSFERT", nbBytes);
+    return 0xFF;
+  }
+  offset = d->transfers[line].offset;
+  for (i = 0 ; i < nbBytes ; i++) 
+    d->transfers[line].data[offset + i] = * (data + i);
+  d->transfers[line].offset = d->transfers[line].offset + nbBytes;
+  return 0;
+}
+
+/***************************************************************************/
+UNS8 failedSDO (CO_Data* d, UNS8 nodeId, UNS8 whoami, UNS16 index, 
+               UNS8 subIndex, UNS32 abortCode)
+{
+  UNS8 err;
+  UNS8 line;
+
+  err = getSDOlineOnUse( d, nodeId, whoami, &line );
+  if (!err)
+    MSG_WAR(0x3A20, "FailedSDO : line found : ", line);
+  if ((! err) && (whoami == SDO_SERVER)) {
+    resetSDOline( d, line );
+    MSG_WAR(0x3A21, "FailedSDO : line released : ", line);
+  }
+  if ((! err) && (whoami == SDO_CLIENT)) {
+    StopSDO_TIMER(line)
+    d->transfers[line].state = SDO_ABORTED_INTERNAL;
+  }
+  MSG_WAR(0x3A22, "Sending SDO abort ", 0);
+  err = sendSDOabort(d, whoami, index, subIndex, abortCode);
+  if (err) {
+    MSG_WAR(0x3A23, "Unable to send the SDO abort", 0);
+    return 0xFF;
+  }
+  return 0;
+}
+
+/***************************************************************************/
+void resetSDOline ( CO_Data* d, UNS8 line )
+{
+  UNS8 i; 
+
+  initSDOline(d, line, 0, 0, 0, SDO_RESET);
+  for (i = 0 ; i < SDO_MAX_LENGTH_TRANSFERT ; i++)
+    d->transfers[line].data[i] = 0;
+}
+
+/***************************************************************************/
+UNS8 initSDOline (CO_Data* d, UNS8 line, UNS8 nodeId, UNS16 index, UNS8 subIndex, UNS8 state)
+{
+  if (state == SDO_DOWNLOAD_IN_PROGRESS || state == SDO_UPLOAD_IN_PROGRESS){
+       StartSDO_TIMER(line)
+  }else{
+       StopSDO_TIMER(line)
+  }
+  d->transfers[line].nodeId = nodeId; 
+  d->transfers[line].index = index;
+  d->transfers[line].subIndex = subIndex;
+  d->transfers[line].state = state;
+  d->transfers[line].toggle = 0;
+  d->transfers[line].count = 0;
+  d->transfers[line].offset = 0;
+  d->transfers[line].dataType = 0;
+  return 0;
+}
+
+/***************************************************************************/
+UNS8 getSDOfreeLine ( CO_Data* d, UNS8 whoami, UNS8 *line )
+{
+       
+  UNS8 i;
+    
+  for (i = 0 ; i < SDO_MAX_SIMULTANEOUS_TRANSFERTS ; i++){
+    if ( d->transfers[i].state == SDO_RESET ) {
+      *line = i;
+      d->transfers[i].whoami = whoami;
+      return 0;
+    } // end if
+  } // end for
+  MSG_ERR(0x1A25, "Too many SDO in progress. Aborted.", i);
+  return 0xFF;
+}
+
+/***************************************************************************/
+UNS8 getSDOlineOnUse (CO_Data* d, UNS8 nodeId, UNS8 whoami, UNS8 *line)
+{
+       
+  UNS8 i;
+    
+  for (i = 0 ; i < SDO_MAX_SIMULTANEOUS_TRANSFERTS ; i++){
+    if ( (d->transfers[i].state != SDO_RESET) &&
+        (d->transfers[i].nodeId == nodeId) && 
+        (d->transfers[i].whoami == whoami) ) {
+      *line = i;
+      return 0;
+    }
+  } 
+  return 0xFF;
+}
+
+/***************************************************************************/
+UNS8 closeSDOtransfer (CO_Data* d, UNS8 nodeId, UNS8 whoami)
+{
+  UNS8 err;
+  UNS8 line;
+  err = getSDOlineOnUse(d, nodeId, whoami, &line);
+  if (err) {
+    MSG_WAR(0x2A30, "No SDO communication to close for node : ", nodeId); 
+    return 0xFF;
+  }
+  resetSDOline(d, line);  
+  return 0;
+}
+
+/***************************************************************************/
+UNS8 getSDOlineRestBytes (CO_Data* d, UNS8 line, UNS8 * nbBytes)
+{
+  if (d->transfers[line].count == 0) // if received initiate SDO protocol with e=0 and s=0
+    * nbBytes = 0;
+  else
+    * nbBytes = d->transfers[line].count - d->transfers[line].offset;
+  return 0;
+}
+
+/***************************************************************************/
+UNS8 setSDOlineRestBytes (CO_Data* d, UNS8 line, UNS8 nbBytes)
+{
+  if (nbBytes > SDO_MAX_LENGTH_TRANSFERT) {
+    MSG_ERR(0x1A35,"SDO Size of data too large. Exceed SDO_MAX_LENGTH_TRANSFERT", nbBytes);
+    return 0xFF;
+  }
+  d->transfers[line].count = nbBytes;
+  return 0;
+}
+
+
+/***************************************************************************/
+UNS8 sendSDO (CO_Data* d, UNS8 whoami, s_SDO sdo)
+{      
+  UNS16 offset;
+  UNS16 lastIndex;
+  UNS8 found = 0;
+  Message m;
+  UNS8 i;
+  UNS32 * pwCobId = NULL;
+  UNS8 * pwNodeId = NULL;
+  UNS8 *    pSize;
+  UNS8      size;
+  pSize = &size;
+
+  MSG_WAR(0x3A38, "sendSDO",0);
+  if( !((d->nodeState == Operational) ||  (d->nodeState == Pre_operational ))) {
+    MSG_WAR(0x2A39, "unable to send the SDO (not in op or pre-op mode", d->nodeState);
+    return 0xFF;
+  }                            
+
+  /*get the server->client cobid*/
+  if ( whoami == SDO_SERVER )  {/*case server. Easy because today only one server SDO is authorized in CanFestival*/
+    offset = d->firstIndex->SDO_SVR;
+    if (offset == 0) {
+      MSG_ERR(0x1A42, "SendSDO : No SDO server found", 0); 
+      return 0xFF;
+    }
+    pwCobId = d->objdict[offset].pSubindex[2].pObject;
+    MSG_WAR(0x3A41, "I am server. cobId : ", *pwCobId); 
+  }
+  else {                       /*case client*/
+    /* Get the client->server cobid.*/
+    UNS16 sdoNum = 0;
+    offset = d->firstIndex->SDO_CLT;
+    lastIndex = d->lastIndex->SDO_CLT;
+    if (offset == 0) {
+      MSG_ERR(0x1A42, "SendSDO : No SDO client index found", 0); 
+      return 0xFF;
+    }
+    /* First, have to find at the index where is defined the communication with the server node */
+    while (offset <= lastIndex){
+      MSG_WAR(0x3A43,"Reading index : ", 0x1280 + sdoNum);
+      if (d->objdict[offset].bSubCount <= 3) {
+       MSG_ERR(0x1A28, "Subindex 3  not found at index ", 0x1280 + sdoNum);
+       return 0xFF;
+      }
+      pwNodeId = d->objdict[offset].pSubindex[3].pObject;
+      MSG_WAR(0x3A44, "Found nodeId server = ", *pwNodeId);    
+      if(*pwNodeId == sdo.nodeId) {
+       found = 1;
+       break;          
+      }      
+      offset ++;
+      sdoNum ++;
+    }
+    if (! found){
+      MSG_WAR (0x2A45, "No SDO client corresponds to the mesage to send to node ", sdo.nodeId);
+      return 0xFF;
+    }
+    /* Second, read the cobid client->server */
+    pwCobId = d->objdict[offset].pSubindex[1].pObject;
+  }
+  /* message copy for sending */
+  m.cob_id.w = *pwCobId;
+  m.rtr = NOT_A_REQUEST; 
+  //the length of SDO must be 8
+  m.len = 8;
+  for (i = 0 ; i < 8 ; i++) {
+    m.data[i] =  sdo.body.data[i];
+  }
+  return (*d->canSend)(&m);
+}
+
+/***************************************************************************/
+UNS8 sendSDOabort (CO_Data* d, UNS8 whoami, UNS16 index, UNS8 subIndex, UNS32 abortCode)
+{
+  s_SDO sdo;
+  UNS8 ret;
+  MSG_WAR(0x2A50,"Sending SDO abort", abortCode);
+  sdo.nodeId = *d->bDeviceNodeId;
+  sdo.body.data[0] = 0x80;
+  // Index
+  sdo.body.data[1] = index & 0xFF; // LSB
+  sdo.body.data[2] = (index >> 8) & 0xFF; // MSB
+  // Subindex
+  sdo.body.data[3] = subIndex;
+  // Data
+  sdo.body.data[4] = (UNS8)(abortCode & 0xFF);
+  sdo.body.data[5] = (UNS8)((abortCode >> 8) & 0xFF);
+  sdo.body.data[6] = (UNS8)((abortCode >> 16) & 0xFF);
+  sdo.body.data[7] = (UNS8)((abortCode >> 24) & 0xFF);
+  ret = sendSDO(d, whoami, sdo);
+
+  return ret;
+}
+
+/***************************************************************************/
+UNS8 proceedSDO (CO_Data* d, Message *m)
+{
+  UNS8 err;
+  UNS8 line;
+  UNS8 nbBytes; // received or to be transmited.
+  UNS8 nodeId = 0;  // The node from which the SDO is received
+  UNS8 *pNodeId = NULL;
+  UNS8 whoami = SDO_UNKNOWN;  // SDO_SERVER or SDO_CLIENT.
+  UNS32 errorCode; // while reading or writing in the local object dictionary.
+  s_SDO sdo;    // SDO to transmit
+  UNS16 index;
+  UNS8 subIndex;
+  UNS32 abortCode;
+  UNS8 i,j;
+  UNS32 *     pCobId = NULL;
+  UNS8 *      pSize;
+  UNS8        size;
+  UNS16 offset;
+  UNS16 lastIndex;
+  
+  pSize = &size; 
+
+  MSG_WAR(0x3A60, "proceedSDO ", 0);
+  whoami = SDO_UNKNOWN;
+  // Looking for the cobId in the object dictionary.
+  // Am-I a server ?
+  offset = d->firstIndex->SDO_SVR;
+  lastIndex = d->lastIndex->SDO_SVR;
+  j = 0;
+  if(offset) while (offset <= lastIndex) {
+     if (d->objdict[offset].bSubCount <= 1) {
+         MSG_ERR(0x1A61, "Subindex 1  not found at index ", 0x1200 + j);
+         return 0xFF;
+       }
+      pCobId = d->objdict[offset].pSubindex[1].pObject;
+      if ( *pCobId == (*m).cob_id.w ) {
+       whoami = SDO_SERVER;
+       MSG_WAR(0x3A62, "proceedSDO. I am server. index : ", 0x1200 + j);
+       // In case of server, the node id of the client may be unknown. So we put the index minus offset
+       // 0x1200 where the cobid received is defined.
+       nodeId = j;
+       break;
+      }
+      j++;
+      offset++;
+  } // end while
+  if (whoami == SDO_UNKNOWN) {
+    // Am-I client ?
+    offset = d->firstIndex->SDO_CLT;
+    lastIndex = d->lastIndex->SDO_CLT;
+    j = 0;
+    if(offset) while (offset <= lastIndex) {
+       if (d->objdict[offset].bSubCount <= 3) {
+        MSG_ERR(0x1A63, "Subindex 3  not found at index ", 0x1280 + j);
+        return 0xFF;
+       }
+       // a) Looking for the cobid received.
+       pCobId = d->objdict[offset].pSubindex[2].pObject;
+       if (*pCobId == (*m).cob_id.w ) {
+        // b) cobid found, so reading the node id of the server.
+        pNodeId = d->objdict[offset].pSubindex[3].pObject;
+        whoami = SDO_CLIENT;
+        nodeId = *pNodeId;
+        MSG_WAR(0x3A64, "proceedSDO. I am server. index : ", 0x1280 + j);
+        MSG_WAR(0x3A65, "                 Server nodeId : ", nodeId);
+        break;
+       }
+       j++;
+       offset++;
+    } // end while
+  }
+  if (whoami == SDO_UNKNOWN) {
+    return 0xFF;// This SDO was not for us !
+  }
+
+  // Test if the size of the SDO is ok
+  if ( (*m).len != 8) {
+    MSG_ERR(0x1A67, "Error size SDO. CobId  : ", (*m).cob_id.w);
+    failedSDO(d, nodeId, whoami, 0, 0, SDOABT_GENERAL_ERROR);
+    return 0xFF;
+  }
+  
+  if (whoami == SDO_CLIENT) {
+    MSG_WAR(0x3A68, "I am CLIENT. Received SDO from nodeId : ", nodeId);
+  }
+  else {
+    MSG_WAR(0x3A69, "I am SERVER. Received SDO cobId : ", (*m).cob_id.w);
+  }
+    
+  // Testing the command specifier
+  // Allowed : cs = 0, 1, 2, 3, 4. (=  all except those for block tranfert).
+  // cs = other : Not allowed -> abort.
+  switch (getSDOcs(m->data[0])) {
+
+  case 0:
+    // I am SERVER
+    if (whoami == SDO_SERVER) {
+      // Receiving a download segment data.
+      // A SDO transfert should have been yet initiated.
+      err = getSDOlineOnUse( d, nodeId, whoami, &line ); 
+      if (!err)
+       err = d->transfers[line].state != SDO_DOWNLOAD_IN_PROGRESS;
+      if (err) {
+       MSG_ERR(0x1A70, "SDO error : Received download segment for unstarted trans. index 0x1200 + ", 
+               nodeId); 
+       failedSDO(d, nodeId, whoami, 0, 0, SDOABT_LOCAL_CTRL_ERROR);
+       return 0xFF;
+      }
+      // Reset the wathdog
+      RestartSDO_TIMER(line)
+      MSG_WAR(0x3A71, "Received SDO download segment defined at index 0x1200 + ", nodeId); 
+      index = d->transfers[line].index;
+      subIndex = d->transfers[line].subIndex;
+      // Toggle test.
+      if (d->transfers[line].toggle != getSDOt(m->data[0])) {
+       MSG_ERR(0x1A72, "SDO error : Toggle error : ", getSDOt(m->data[0])); 
+       failedSDO(d, nodeId, whoami, index, subIndex, SDOABT_TOGGLE_NOT_ALTERNED);
+       return 0xFF;
+      }
+      // Nb of data to be downloaded
+      nbBytes = 7 - getSDOn3(m->data[0]);
+      // Store the data in the transfert structure.
+      err = SDOtoLine(d, line, nbBytes, (*m).data + 1);
+      if (err) {
+       failedSDO(d, nodeId, whoami, index, subIndex, SDOABT_GENERAL_ERROR);
+       return 0xFF;
+      }
+      // Sending the SDO response, CS = 1
+      sdo.nodeId = *d->bDeviceNodeId; // The node id of the server, (here it is the sender).
+      sdo.body.data[0] = (1 << 5) | (d->transfers[line].toggle << 4);
+      for (i = 1 ; i < 8 ; i++)
+       sdo.body.data[i] = 0;
+      MSG_WAR(0x3A73, "SDO. Send response to download request defined at index 0x1200 + ", nodeId); 
+      sendSDO(d, whoami, sdo);
+      // Inverting the toggle for the next segment.
+      d->transfers[line].toggle = ! d->transfers[line].toggle & 1;
+      // If it was the last segment,
+      if (getSDOc(m->data[0])) {
+       // Transfering line data to object dictionary.
+       // The code does not use the "d" of initiate frame. So it is safe if e=s=0
+       errorCode = SDOlineToObjdict(d, line);
+       if (errorCode) {
+         MSG_ERR(0x1A54, "SDO error : Unable to copy the data in the object dictionary", 0); 
+         failedSDO(d, nodeId, whoami, index, subIndex, errorCode);
+         return 0xFF;    
+       }
+       // Release of the line
+       resetSDOline(d, line);
+       MSG_WAR(0x3A74, "SDO. End of download defined at index 0x1200 + ", nodeId); 
+      }
+    } // end if SERVER
+    else { // if CLIENT
+      // I am CLIENT
+      // It is a request for a previous upload segment. We should find a line opened for this.
+      err = getSDOlineOnUse( d, nodeId, whoami, &line);
+      if (!err)
+       err = d->transfers[line].state != SDO_UPLOAD_IN_PROGRESS;
+      if (err) {
+       MSG_ERR(0x1A75, "SDO error : Received segment response for unknown trans. from nodeId", nodeId); 
+       failedSDO(d, nodeId, whoami, 0, 0, SDOABT_LOCAL_CTRL_ERROR);
+       return 0xFF;
+      }
+      // Reset the wathdog
+      RestartSDO_TIMER(line)
+      index = d->transfers[line].index;
+      subIndex = d->transfers[line].subIndex;
+      // test of the toggle;
+      if (d->transfers[line].toggle != getSDOt(m->data[0])) {
+       MSG_ERR(0x1A76, "SDO error : Received segment response Toggle error. from nodeId", nodeId); 
+       failedSDO(d, nodeId, whoami, index, subIndex, SDOABT_TOGGLE_NOT_ALTERNED);
+       return 0xFF;
+      }
+      // nb of data to be uploaded
+      nbBytes = 7 - getSDOn3(m->data[0]);
+      // Storing the data in the line structure.
+      err = SDOtoLine(d, line, nbBytes, (*m).data + 1);
+      if (err) {
+       failedSDO(d, nodeId, whoami, index, subIndex, SDOABT_GENERAL_ERROR);
+       return 0xFF;
+      }
+      // Inverting the toggle for the next segment.
+      d->transfers[line].toggle = ! d->transfers[line].toggle & 1;
+      // If it was the last segment,
+      if ( getSDOc(m->data[0])) {
+       // Put in state finished
+       // The code is safe for the case e=s=0 in initiate frame.
+       StopSDO_TIMER(line)
+       d->transfers[line].state = SDO_FINISHED;
+       MSG_WAR(0x3A77, "SDO. End of upload from node : ", nodeId);
+      }
+      else { // more segments to receive
+            // Sending the request for the next segment.
+       sdo.nodeId = nodeId;
+       sdo.body.data[0] = (3 << 5) | (d->transfers[line].toggle << 4);
+       for (i = 1 ; i < 8 ; i++)
+         sdo.body.data[i] = 0;
+       sendSDO(d, whoami, sdo);
+       MSG_WAR(0x3A78, "SDO send upload segment request to nodeId", nodeId);
+      }            
+    } // End if CLIENT
+    break;
+
+  case 1:
+    // I am SERVER
+    // Receive of an initiate download
+    if (whoami == SDO_SERVER) {
+      index = getSDOindex(m->data[1],m->data[2]);
+      subIndex = getSDOsubIndex(m->data[3]);
+      MSG_WAR(0x3A79, "Received SDO Initiate Download (to store data) defined at index 0x1200 + ", 
+             nodeId); 
+      MSG_WAR(0x3A80, "Writing at index : ", index);
+      MSG_WAR(0x3A80, "Writing at subIndex : ", subIndex);
+      
+      // Search if a SDO transfert have been yet initiated
+      err = getSDOlineOnUse( d, nodeId, whoami, &line );
+      if (! err) {
+       MSG_ERR(0x1A81, "SDO error : Transmission yet started.", 0); 
+       failedSDO(d, nodeId, whoami, index, subIndex, SDOABT_LOCAL_CTRL_ERROR);
+       return 0xFF;
+      }
+      // No line on use. Great !
+      // Try to open a new line.
+      err = getSDOfreeLine( d, whoami, &line );
+      if (err) {
+       MSG_ERR(0x1A82, "SDO error : No line free, too many SDO in progress. Aborted.", 0);
+       failedSDO(d, nodeId, whoami, index, subIndex, SDOABT_LOCAL_CTRL_ERROR);
+       return 0xFF;
+      }
+      initSDOline(d, line, nodeId, index, subIndex, SDO_DOWNLOAD_IN_PROGRESS);      
+
+      if (getSDOe(m->data[0])) { // If SDO expedited
+       // nb of data to be downloaded
+       nbBytes = 4 - getSDOn2(m->data[0]);
+       // Storing the data in the line structure.
+       d->transfers[line].count = nbBytes;
+       err = SDOtoLine(d, line, nbBytes, (*m).data + 4);
+       
+       if (err) {
+         failedSDO(d, nodeId, whoami, index, subIndex, SDOABT_GENERAL_ERROR);
+         return 0xFF;
+       }         
+
+       // SDO expedited -> transfert finished. Data can be stored in the dictionary.
+       // The line will be reseted when it is downloading in the dictionary.
+       MSG_WAR(0x3A83, "SDO Initiate Download is an expedited transfert. Finished.: ", nodeId);
+       // Transfering line data to object dictionary.
+       errorCode = SDOlineToObjdict(d, line);
+       if (errorCode) {
+         MSG_ERR(0x1A84, "SDO error : Unable to copy the data in the object dictionary", 0); 
+         failedSDO(d, nodeId, whoami, index, subIndex, errorCode);
+         return 0xFF;
+       }
+       // Release of the line.
+       resetSDOline(d, line);
+      }
+      else {// So, if it is not an expedited transfert
+       if (getSDOs(m->data[0])) {
+         // TODO : if e and s = 0, not reading m->data[4] but put nbBytes = 0
+         nbBytes = m->data[4]; // Transfert limited to 255 bytes.
+         err = setSDOlineRestBytes(d, nodeId, nbBytes);
+         if (err) {
+           failedSDO(d, nodeId, whoami, index, subIndex, SDOABT_GENERAL_ERROR);
+           return 0xFF;
+         }     
+       }
+      }
+      //Sending a SDO, cs=3
+      sdo.nodeId = *d->bDeviceNodeId; // The node id of the server, (here it is the sender).
+      sdo.body.data[0] = 3 << 5;
+      sdo.body.data[1] = index & 0xFF;        // LSB
+      sdo.body.data[2] = (index >> 8) & 0xFF; // MSB 
+      sdo.body.data[3] = subIndex;
+      for (i = 4 ; i < 8 ; i++)
+               sdo.body.data[i] = 0;
+      sendSDO(d, whoami, sdo);
+    } // end if I am SERVER
+    else {
+      // I am CLIENT
+      // It is a response for a previous download segment. We should find a line opened for this.
+      err = getSDOlineOnUse( d, nodeId, whoami, &line);
+      if (!err)
+       err = d->transfers[line].state != SDO_DOWNLOAD_IN_PROGRESS;
+      if (err) {
+       MSG_ERR(0x1A85, "SDO error : Received segment response for unknown trans. from nodeId", nodeId); 
+       failedSDO(d, nodeId, whoami, 0, 0, SDOABT_LOCAL_CTRL_ERROR);
+       return 0xFF;
+      }
+      // Reset the wathdog
+      RestartSDO_TIMER(line)
+      index = d->transfers[line].index;
+      subIndex = d->transfers[line].subIndex;
+      // test of the toggle;
+      if (d->transfers[line].toggle != getSDOt(m->data[0])) {
+       MSG_ERR(0x1A86, "SDO error : Received segment response Toggle error. from nodeId", nodeId); 
+       failedSDO(d, nodeId, whoami, index, subIndex, SDOABT_TOGGLE_NOT_ALTERNED);
+       return 0xFF;
+      }
+
+      // End transmission or downloading next segment. We need to know if it will be the last one.
+      getSDOlineRestBytes(d, line, &nbBytes);
+      if (nbBytes == 0) {
+       MSG_WAR(0x3A87, "SDO End download. segment response received. OK. from nodeId", nodeId); 
+       StopSDO_TIMER(line)
+       d->transfers[line].state = SDO_FINISHED;
+       return 0x00;
+      }
+      // At least one transfer to send.          
+      if (nbBytes > 7) {
+       // several segments to download.
+       // code to send the next segment. (cs = 0; c = 0)
+       d->transfers[line].toggle = ! d->transfers[line].toggle & 1;
+       sdo.nodeId = nodeId; // The server node Id;
+       sdo.body.data[0] = (d->transfers[line].toggle << 4);
+       err = lineToSDO(d, line, 7, sdo.body.data + 1);  
+       if (err) {
+         failedSDO(d, nodeId, whoami, index, subIndex, SDOABT_GENERAL_ERROR);
+         return 0xFF;
+       }
+      } 
+      else {
+       // Last segment.
+       // code to send the last segment. (cs = 0; c = 1)
+       d->transfers[line].toggle = ! d->transfers[line].toggle & 1;
+       sdo.nodeId = nodeId; // The server node Id;
+       sdo.body.data[0] = (d->transfers[line].toggle << 4) | ((7 - nbBytes) << 1) | 1;
+       err = lineToSDO(d, line, nbBytes, sdo.body.data + 1);    
+       if (err) {
+         failedSDO(d, nodeId, whoami, index, subIndex, SDOABT_GENERAL_ERROR);
+         return 0xFF;
+       }
+       for (i = nbBytes + 1 ; i < 8 ; i++)
+         sdo.body.data[i] = 0;
+      }
+      MSG_WAR(0x3A88, "SDO sending download segment to nodeId", nodeId); 
+      sendSDO(d, whoami, sdo); 
+    } // end if I am a CLIENT                    
+    break;
+
+  case 2:
+    // I am SERVER
+    // Receive of an initiate upload.
+    if (whoami == SDO_SERVER) {
+      index = getSDOindex(m->data[1],m->data[2]);
+      subIndex = getSDOsubIndex(m->data[3]);
+      MSG_WAR(0x3A89, "Received SDO Initiate upload (to send data) defined at index 0x1200 + ", 
+             nodeId); 
+      MSG_WAR(0x3A90, "Reading at index : ", index);
+      MSG_WAR(0x3A91, "Reading at subIndex : ", subIndex);
+      // Search if a SDO transfert have been yet initiated
+      err = getSDOlineOnUse( d, nodeId, whoami, &line );
+      if (! err) {
+       MSG_ERR(0x1A92, "SDO error : Transmission yet started at line : ", line); 
+        MSG_WAR(0x3A93, "nodeId = ", nodeId); 
+       failedSDO(d, nodeId, whoami, index, subIndex, SDOABT_LOCAL_CTRL_ERROR);
+       return 0xFF;
+      }
+      // No line on use. Great !
+      // Try to open a new line.
+      err = getSDOfreeLine( d, whoami, &line );
+      if (err) {
+       MSG_ERR(0x1A71, "SDO error : No line free, too many SDO in progress. Aborted.", 0);
+       failedSDO(d, nodeId, whoami, index, subIndex, SDOABT_LOCAL_CTRL_ERROR);
+       return 0xFF;
+      }
+      initSDOline(d, line, nodeId, index, subIndex, SDO_UPLOAD_IN_PROGRESS);
+      // Transfer data from dictionary to the line structure.
+      errorCode = objdictToSDOline(d, line);
+     
+      if (errorCode) {
+       MSG_ERR(0x1A94, "SDO error : Unable to copy the data from object dictionary. Err code : ", 
+               errorCode); 
+       failedSDO(d, nodeId, whoami, index, subIndex, errorCode);
+       return 0xFF;
+       }
+      // Preparing the response.
+      getSDOlineRestBytes(d, line, &nbBytes);  // Nb bytes to transfer ?
+      sdo.nodeId = nodeId; // The server node Id;
+      if (nbBytes > 4) {
+       // normal transfert. (segmented).
+       // code to send the initiate upload response. (cs = 2)
+       sdo.body.data[0] = (2 << 5) | 1;
+       sdo.body.data[1] = index & 0xFF;        // LSB
+       sdo.body.data[2] = (index >> 8) & 0xFF; // MSB 
+       sdo.body.data[3] = subIndex;
+        sdo.body.data[4] = nbBytes; // Limitation of canfestival2 : Max tranfert is 256 bytes.
+       // It takes too much memory to upgrate to 2^32 because the size of data is also coded
+       // in the object dictionary, at every index and subindex.
+       for (i = 5 ; i < 8 ; i++)
+         sdo.body.data[i] = 0;
+       MSG_WAR(0x3A95, "SDO. Sending normal upload initiate response defined at index 0x1200 + ", nodeId); 
+       sendSDO(d, whoami, sdo); 
+      }
+      else {
+       // Expedited upload. (cs = 2 ; e = 1) 
+       sdo.body.data[0] = (2 << 5) | ((4 - nbBytes) << 2) | 3;  
+       sdo.body.data[1] = index & 0xFF;        // LSB
+       sdo.body.data[2] = (index >> 8) & 0xFF; // MSB 
+       sdo.body.data[3] = subIndex;
+       err = lineToSDO(d, line, nbBytes, sdo.body.data + 4);    
+       if (err) {
+         failedSDO(d, nodeId, whoami, index, subIndex, SDOABT_GENERAL_ERROR);
+         return 0xFF;
+       }
+       for (i = 4 + nbBytes ; i < 8 ; i++)
+         sdo.body.data[i] = 0;
+       MSG_WAR(0x3A96, "SDO. Sending expedited upload initiate response defined at index 0x1200 + ", 
+               nodeId); 
+       sendSDO(d, whoami, sdo); 
+       // Release the line.
+       resetSDOline(d, line);
+      }
+    } // end if I am SERVER
+    else {
+      // I am CLIENT
+      // It is the response for the previous initiate upload request. 
+      // We should find a line opened for this.
+      err = getSDOlineOnUse( d, nodeId, whoami, &line);
+      if (!err)
+       err = d->transfers[line].state != SDO_UPLOAD_IN_PROGRESS;
+      if (err) {
+       MSG_ERR(0x1A97, "SDO error : Received response for unknown upload request from nodeId", nodeId); 
+       failedSDO(d, nodeId, whoami, 0, 0, SDOABT_LOCAL_CTRL_ERROR);
+       return 0xFF;
+      }
+      // Reset the wathdog
+      RestartSDO_TIMER(line)
+      index = d->transfers[line].index;
+      subIndex = d->transfers[line].subIndex;
+      
+      if (getSDOe(m->data[0])) { // If SDO expedited
+       // nb of data to be uploaded
+         nbBytes = 4 - getSDOn2(m->data[0]);
+       // Storing the data in the line structure.
+       err = SDOtoLine(d, line, nbBytes, (*m).data + 4);
+       if (err) {
+         failedSDO(d, nodeId, whoami, index, subIndex, SDOABT_GENERAL_ERROR);
+         return 0xFF;
+       }
+       // SDO expedited -> transfert finished. data are available via  getReadResultNetworkDict().
+       MSG_WAR(0x3A98, "SDO expedited upload finished. Response received from node : ", nodeId);
+       StopSDO_TIMER(line)
+       d->transfers[line].count = nbBytes;
+       d->transfers[line].state = SDO_FINISHED;
+       return 0;
+      }
+      else { // So, if it is not an expedited transfert
+       // Storing the nb of data to receive.
+       if (getSDOs(m->data[0])) {
+         nbBytes = m->data[4]; // Remember the limitation to 255 bytes to transfert
+         err = setSDOlineRestBytes(d, line, nbBytes);
+         if (err) {
+           failedSDO(d, nodeId, whoami, index, subIndex, SDOABT_GENERAL_ERROR);
+           return 0xFF;
+         }     
+       }
+       // Requesting next segment. (cs = 3)
+       sdo.nodeId = nodeId;
+       sdo.body.data[0] = 3 << 5;
+       for (i = 1 ; i < 8 ; i++)
+         sdo.body.data[i] = 0;
+       MSG_WAR(0x3A99, "SDO. Sending upload segment request to node : ", nodeId); 
+       sendSDO(d, whoami, sdo);  
+      }
+    } // End if CLIENT
+    break;
+
+  case 3:
+    // I am SERVER
+    if (whoami == SDO_SERVER) {
+      // Receiving a upload segment.
+      // A SDO transfert should have been yet initiated.
+      err = getSDOlineOnUse( d, nodeId, whoami, &line ); 
+      if (!err)
+       err = d->transfers[line].state != SDO_UPLOAD_IN_PROGRESS;
+      if (err) {
+       MSG_ERR(0x1AA0, "SDO error : Received upload segment for unstarted trans. index 0x1200 + ", 
+               nodeId); 
+       failedSDO(d, nodeId, whoami, 0, 0, SDOABT_LOCAL_CTRL_ERROR);
+       return 0xFF;
+      }
+      // Reset the wathdog
+      RestartSDO_TIMER(line)
+      MSG_WAR(0x3AA1, "Received SDO upload segment defined at index 0x1200 + ", nodeId); 
+      index = d->transfers[line].index;
+      subIndex = d->transfers[line].subIndex;
+      // Toggle test.
+      if (d->transfers[line].toggle != getSDOt(m->data[0])) {
+       MSG_ERR(0x1AA2, "SDO error : Toggle error : ", getSDOt(m->data[0])); 
+       failedSDO(d, nodeId, whoami, index, subIndex, SDOABT_TOGGLE_NOT_ALTERNED);
+       return 0xFF;
+      }
+      // Uploading next segment. We need to know if it will be the last one.
+      getSDOlineRestBytes(d, line, &nbBytes);            
+      if (nbBytes > 7) {
+       // The segment to transfer is not the last one.
+       // code to send the next segment. (cs = 0; c = 0)
+       sdo.nodeId = nodeId; // The server node Id;
+       sdo.body.data[0] = (d->transfers[line].toggle << 4);
+       err = lineToSDO(d, line, 7, sdo.body.data + 1);  
+       if (err) {
+         failedSDO(d, nodeId, whoami, index, subIndex, SDOABT_GENERAL_ERROR);
+         return 0xFF;
+       }
+       // Inverting the toggle for the next tranfert.
+       d->transfers[line].toggle = ! d->transfers[line].toggle & 1;
+       MSG_WAR(0x3AA3, "SDO. Sending upload segment defined at index 0x1200 + ", nodeId); 
+       sendSDO(d, whoami, sdo); 
+      } 
+      else {
+       // Last segment.
+       // code to send the last segment. (cs = 0; c = 1)           
+       sdo.nodeId = nodeId; // The server node Id;
+       sdo.body.data[0] = (d->transfers[line].toggle << 4) | ((7 - nbBytes) << 1) | 1;
+       err = lineToSDO(d, line, nbBytes, sdo.body.data + 1);    
+       if (err) {
+         failedSDO(d, nodeId, whoami, index, subIndex, SDOABT_GENERAL_ERROR);
+         return 0xFF;
+       }
+       for (i = nbBytes + 1 ; i < 8 ; i++)
+         sdo.body.data[i] = 0;
+       MSG_WAR(0x3AA4, "SDO. Sending last upload segment defined at index 0x1200 + ", nodeId);      
+       sendSDO(d, whoami, sdo);
+       // Release the line
+       resetSDOline(d, line);
+      }
+    } // end if SERVER 
+    else {
+      // I am CLIENT
+      // It is the response for the previous initiate download request. 
+      // We should find a line opened for this.
+      err = getSDOlineOnUse( d, nodeId, whoami, &line);
+      if (!err)
+       err = d->transfers[line].state != SDO_DOWNLOAD_IN_PROGRESS;
+      if (err) {
+       MSG_ERR(0x1AA5, "SDO error : Received response for unknown download request from nodeId", nodeId); 
+       failedSDO(d, nodeId, whoami, 0, 0, SDOABT_LOCAL_CTRL_ERROR);
+       return 0xFF;
+      }
+      // Reset the wathdog
+      RestartSDO_TIMER(line)
+      index = d->transfers[line].index;
+      subIndex = d->transfers[line].subIndex;
+      // End transmission or requesting  next segment. 
+      getSDOlineRestBytes(d, line, &nbBytes);
+      if (nbBytes == 0) {
+       MSG_WAR(0x3AA6, "SDO End download expedited. Response received. from nodeId", nodeId); 
+       StopSDO_TIMER(line)
+       d->transfers[line].state = SDO_FINISHED;
+       return 0x00;
+      }          
+      if (nbBytes > 7) {
+       // more than one request to send
+       // code to send the next segment. (cs = 0; c = 0)           
+       sdo.nodeId = nodeId; // The server node Id;
+       sdo.body.data[0] = (d->transfers[line].toggle << 4);
+       err = lineToSDO(d, line, 7, sdo.body.data + 1);  
+       if (err) {
+         failedSDO(d, nodeId, whoami, index, subIndex, SDOABT_GENERAL_ERROR);
+         return 0xFF;
+       }
+      } 
+      else {
+       // Last segment.
+       // code to send the last segment. (cs = 0; c = 1)          
+       sdo.nodeId = nodeId; // The server node Id;
+       sdo.body.data[0] = (d->transfers[line].toggle << 4) | ((7 - nbBytes) << 1) | 1;
+       err = lineToSDO(d, line, nbBytes, sdo.body.data + 1);    
+       if (err) {
+         failedSDO(d, nodeId, whoami, index, subIndex, SDOABT_GENERAL_ERROR);
+         return 0xFF;
+       }
+       for (i = nbBytes + 1 ; i < 8 ; i++)
+         sdo.body.data[i] = 0;
+      }
+      MSG_WAR(0x3AA7, "SDO sending download segment to nodeId", nodeId); 
+      sendSDO(d, whoami, sdo); 
+
+    } // end if I am a CLIENT                    
+    break;  
+
+  case 4:
+    abortCode = (*m).data[3] | 
+      (m->data[5] << 8) |
+      (m->data[6] << 16) |
+      (m->data[7] << 24);
+    // Received SDO abort.
+    // Looking for the line concerned.
+    if (whoami == SDO_SERVER) {
+      err = getSDOlineOnUse( d, nodeId, whoami, &line );
+      if (!err) {
+       resetSDOline( d, line );
+       MSG_WAR(0x3AA8, "SD0. Received SDO abort. Line released. Code : ", abortCode);
+      }
+      else
+       MSG_WAR(0x3AA9, "SD0. Received SDO abort. No line found. Code : ", abortCode);
+      // Tips : The end user has no way to know that the server node has received an abort SDO. 
+      // Its is ok, I think.
+    }
+    else { // If I am CLIENT
+      err = getSDOlineOnUse( d, nodeId, whoami, &line );
+      if (!err) {
+       // The line *must* be released by the core program.
+       StopSDO_TIMER(line)
+       d->transfers[line].state = SDO_ABORTED_RCV;
+       MSG_WAR(0x3AB0, "SD0. Received SDO abort. Line state ABORTED. Code : ", abortCode);
+      }
+      else
+       MSG_WAR(0x3AB1, "SD0. Received SDO abort. No line found. Code : ", abortCode);
+    } 
+    break;
+  default:
+    // Error : Unknown cs
+    MSG_ERR(0x1AB2, "SDO. Received unknown command specifier : ", getSDOcs(m->data[0]));
+    return 0xFF;
+
+  } // End switch
+  return 0;     
+}
+
+/*******************************************************************)******/
+UNS8 writeNetworkDict (CO_Data* d, UNS8 nodeId, UNS16 index, 
+                      UNS8 subIndex, UNS8 count, UNS8 dataType, void *data)
+{
+  UNS8 err;
+  UNS8 SDOfound = 0;
+  UNS8 line;
+  s_SDO sdo;    // SDO to transmit
+  UNS8 i, j;
+  UNS8 *    pSize;
+  UNS8      size;
+  UNS16     lastIndex;
+  UNS16     offset;
+  UNS8      *pNodeIdServer;
+  UNS8      nodeIdServer;
+  pSize = &size;
+
+  MSG_WAR(0x3AC0, "Send SDO to write in the dictionary of node : ", nodeId);
+  MSG_WAR(0x3AC1, "                                   At index : ", index);
+  MSG_WAR(0x3AC2, "                                   subIndex : ", subIndex);
+  MSG_WAR(0x3AC3, "                                   nb bytes : ", count);
+
+  // Verify that there is no SDO communication yet.
+  err = getSDOlineOnUse(d, nodeId, SDO_CLIENT, &line);
+  if (!err) {
+    MSG_ERR(0x1AC4, "SDO error : Communication yet established. with node : ", nodeId); 
+    return 0xFF;
+  }
+  // Taking the line ...
+  err = getSDOfreeLine( d, SDO_CLIENT, &line );
+  if (err) {
+    MSG_ERR(0x1AC5, "SDO error : No line free, too many SDO in progress. Aborted for node : ", nodeId); 
+    return (0xFF);
+  }
+  // Check which SDO to use to communicate with the node
+  offset = d->firstIndex->SDO_CLT;
+  lastIndex = d->lastIndex->SDO_CLT;
+  if (offset == 0) {
+    MSG_ERR(0x1AC6, "writeNetworkDict : No SDO client index found", 0); 
+    return 0xFF;
+  }
+  i = 0;
+   while (offset <= lastIndex) {
+     if (d->objdict[offset].bSubCount <= 3) {
+        MSG_ERR(0x1AC8, "Subindex 3  not found at index ", 0x1280 + i);
+        return 0xFF;
+     }
+     // looking for the nodeId server
+     pNodeIdServer = d->objdict[offset].pSubindex[3].pObject;
+     nodeIdServer = *pNodeIdServer;
+     MSG_WAR(0x1AD2, "index : ", 0x1280 + i);
+     MSG_WAR(0x1AD3, "nodeIdServer : ", nodeIdServer);
+   
+    if(nodeIdServer == nodeId) {
+      SDOfound = 1;
+      break;
+    }
+    offset++;
+    i++;
+  } // end while
+  if (!SDOfound) {
+    MSG_ERR(0x1AC9, "SDO. Error. No client found to communicate with node : ", nodeId);
+    return 0xFF;
+  }
+  MSG_WAR(0x3AD0,"        SDO client defined at index  : ", 0x1280 + i);
+  initSDOline(d, line, nodeId, index, subIndex, SDO_DOWNLOAD_IN_PROGRESS);
+  d->transfers[line].count = count;
+  d->transfers[line].dataType = dataType;
+  
+  // Copy data to transfers structure.
+  for (j = 0 ; j < count ; j++) {
+# ifdef CANOPEN_BIG_ENDIAN
+    if (dataType == 0)
+      d->transfers[line].data[count - 1 - j] = ((char *)data)[j];
+    else // String of bytes.
+      d->transfers[line].data[j] = ((char *)data)[j];
+#  else 
+    d->transfers[line].data[j] = ((char *)data)[j];
+#  endif
+  }
+  // Send the SDO to the server. Initiate download, cs=1.
+  sdo.nodeId = nodeId;
+  if (count <= 4) { // Expedited transfert
+    sdo.body.data[0] = (1 << 5) | ((4 - count) << 2) | 3;
+    for (i = 4 ; i < 8 ; i++)
+      sdo.body.data[i] = d->transfers[line].data[i - 4];
+    d->transfers[line].offset = count;
+  }    
+  else { // Normal transfert
+    sdo.body.data[0] = (1 << 5) | 1;
+    sdo.body.data[4] = count; // nb of byte to transmit. Max = 255. (canfestival2 limitation).
+    for (i = 5 ; i < 8 ; i++)
+      sdo.body.data[i] = 0;
+  }
+  sdo.body.data[1] = index & 0xFF;        // LSB
+  sdo.body.data[2] = (index >> 8) & 0xFF; // MSB 
+  sdo.body.data[3] = subIndex;
+  
+  err = sendSDO(d, SDO_CLIENT, sdo);
+  if (err) {
+    MSG_ERR(0x1AD1, "SDO. Error while sending SDO to node : ", nodeId);
+    // release the line
+    resetSDOline(d, line);
+    return 0xFF;
+  }            
+  return 0;
+}
+
+
+
+/***************************************************************************/
+UNS8 readNetworkDict (CO_Data* d, UNS8 nodeId, UNS16 index, UNS8 subIndex, UNS8 dataType)
+{
+  UNS8 err;
+  UNS8 SDOfound = 0;
+  UNS8 i;
+  UNS8 line;
+  UNS8 *    pSize;
+  UNS8      size;
+  s_SDO sdo;    // SDO to transmit
+  UNS8      *pNodeIdServer;
+  UNS8      nodeIdServer;
+  UNS16     offset;
+  UNS16     lastIndex;
+  pSize = &size;
+  MSG_WAR(0x3AD5, "Send SDO to read in the dictionary of node : ", nodeId);
+  MSG_WAR(0x3AD6, "                                  At index : ", index);
+  MSG_WAR(0x3AD7, "                                  subIndex : ", subIndex);
+
+
+  // Verify that there is no SDO communication yet.
+  err = getSDOlineOnUse(d, nodeId, SDO_CLIENT, &line);
+  if (!err) {
+    MSG_ERR(0x1AD8, "SDO error : Communication yet established. with node : ", nodeId); 
+    return 0xFF;
+  }
+  // Taking the line ...
+  err = getSDOfreeLine( d, SDO_CLIENT, &line );
+  if (err) {
+    MSG_ERR(0x1AD9, "SDO error : No line free, too many SDO in progress. Aborted for node : ", nodeId); 
+    return (0xFF);
+  }
+  else
+    MSG_WAR(0x3AE0, "Transmission on line : ", line);
+
+  // Check which SDO to use to communicate with the node
+  offset = d->firstIndex->SDO_CLT;
+  lastIndex = d->lastIndex->SDO_CLT;
+  if (offset == 0) {
+    MSG_ERR(0x1AE1, "writeNetworkDict : No SDO client index found", 0); 
+    return 0xFF;
+  }
+  i = 0;
+  while (offset <= lastIndex) {
+     if (d->objdict[offset].bSubCount <= 3) {
+        MSG_ERR(0x1AE2, "Subindex 3  not found at index ", 0x1280 + i);
+        return 0xFF;
+     }
+     // looking for the nodeId server
+     pNodeIdServer = d->objdict[offset].pSubindex[3].pObject;
+     nodeIdServer = *pNodeIdServer;
+   
+    if(nodeIdServer == nodeId) {
+      SDOfound = 1;
+      break;
+    }
+    offset++;
+    i++;
+  } // end while
+  if (!SDOfound) {
+    MSG_ERR(0x1AE3, "SDO. Error. No client found to communicate with node : ", nodeId);
+    return 0xFF;
+  }
+  MSG_WAR(0x3AE4,"        SDO client defined at index  : ", 0x1280 + i);
+  initSDOline(d, line, nodeId, index, subIndex, SDO_UPLOAD_IN_PROGRESS);
+  getSDOlineOnUse(d, nodeId, SDO_CLIENT, &line);
+  sdo.nodeId = nodeId;
+  // Send the SDO to the server. Initiate upload, cs=2.
+  d->transfers[line].dataType = dataType;                              
+  sdo.body.data[0] = (2 << 5); 
+  sdo.body.data[1] = index & 0xFF;        // LSB
+  sdo.body.data[2] = (index >> 8) & 0xFF; // MSB 
+  sdo.body.data[3] = subIndex;
+  for (i = 4 ; i < 8 ; i++)
+    sdo.body.data[i] = 0;
+  err = sendSDO(d, SDO_CLIENT, sdo);
+  if (err) {
+    MSG_ERR(0x1AE5, "SDO. Error while sending SDO to node : ", nodeId);
+    // release the line
+    resetSDOline(d, line);
+    return 0xFF;
+  }            
+  return 0;
+}
+
+/***************************************************************************/
+
+UNS8 getReadResultNetworkDict (CO_Data* d, UNS8 nodeId, void* data, UNS8 *size, 
+                              UNS32 * abortCode)
+{
+  UNS8 i;
+  UNS8 err;
+  UNS8 line;
+  * size = 0;
+
+  // Looking for the line tranfert.
+  err = getSDOlineOnUse(d, nodeId, SDO_CLIENT, &line);
+  if (err) {
+    MSG_ERR(0x1AF0, "SDO error : No line found for communication with node : ", nodeId); 
+    return SDO_ABORTED_INTERNAL;
+  }
+  if (d->transfers[line].state != SDO_FINISHED)
+    return d->transfers[line].state;
+
+  // Transfert is finished. Put the value in the data.
+  * size = d->transfers[line].count;
+  for  ( i = 0 ; i < *size ; i++) {
+# ifdef CANOPEN_BIG_ENDIAN
+    if (d->transfers[line].dataType != visible_string)
+      ( (char *) data)[*size - 1 - i] = d->transfers[line].data[i];
+    else // String of bytes.
+      ( (char *) data)[i] = d->transfers[line].data[i];
+# else 
+    ( (char *) data)[i] = d->transfers[line].data[i];
+# endif
+  } 
+  return SDO_FINISHED;
+}
+
+/***************************************************************************/
+
+UNS8 getWriteResultNetworkDict (CO_Data* d, UNS8 nodeId, UNS32 * abortCode)
+{
+  UNS8 line = 0;
+  UNS8 err;
+
+  * abortCode = 0;
+  // Looking for the line tranfert.
+  err = getSDOlineOnUse(d, nodeId, SDO_CLIENT, &line);
+  if (err) {
+    MSG_ERR(0x1AF1, "SDO error : No line found for communication with node : ", nodeId); 
+    return SDO_ABORTED_INTERNAL;
+  }
+  * abortCode = d->transfers[line].abortCode;
+  return d->transfers[line].state;
+}
diff --git a/app/cantest/canfestival/src/states.c b/app/cantest/canfestival/src/states.c
new file mode 100644 (file)
index 0000000..7adfa61
--- /dev/null
@@ -0,0 +1,276 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+#include "states.h"
+#include "def.h"
+
+#include "nmtSlave.h"
+
+#ifdef LED_ENABLE
+//#include "led.h"
+#endif
+
+
+e_nodeState getState(CO_Data* d)
+{
+  return d->nodeState;
+}
+
+void canDispatch(CO_Data* d, Message *m)
+{
+
+#ifdef CANOPEN_LSS_ENABLE
+       /*      OREMEQ 2006-04-08 */
+       if (m->cob_id.w == 0x7E4 || m->cob_id.w == 0x705)
+       {
+               proceedLSS();
+       }
+       else 
+#endif
+
+        switch(m->cob_id.w >> 7)
+       {
+               case SYNC:
+                       if(d->CurrentCommunicationState.csSYNC)
+                               proceedSYNC(d,m);
+                       break;
+               //case TIME_STAMP:
+               case PDO1tx:
+               case PDO1rx:
+               case PDO2tx:
+               case PDO2rx:
+               case PDO3tx:
+               case PDO3rx:
+               case PDO4tx:
+               case PDO4rx:
+                       if (d->CurrentCommunicationState.csPDO)
+                               proceedPDO(d,m);
+                       break;
+               case SDOtx:
+               case SDOrx:
+                       if (d->CurrentCommunicationState.csSDO)
+                               proceedSDO(d,m);
+                       break;
+               case NODE_GUARD:
+                       if (d->CurrentCommunicationState.csHeartbeat)
+                               proceedNODE_GUARD(d,m);
+                       break;
+               case NMT:
+                       if (d->iam_a_slave)
+                       {
+                               proceedNMTstateChange(d,m);
+                       }
+       }
+}
+
+#define StartOrStop(CommType, FuncStart, FuncStop) \
+       if(newCommunicationState->CommType && !d->CurrentCommunicationState.CommType){\
+               MSG_ERR(0x9999,#FuncStart, 9999);\
+               d->CurrentCommunicationState.CommType = 1;\
+               FuncStart;\
+       }else if(!newCommunicationState->CommType && d->CurrentCommunicationState.CommType){\
+               MSG_ERR(0x9999,#FuncStop, 9999);\
+               d->CurrentCommunicationState.CommType = 0;\
+               FuncStop;\
+       }
+#define None
+
+void switchCommunicationState(CO_Data* d, s_state_communication *newCommunicationState)
+{
+       StartOrStop(csBoot_Up,  None,   slaveSendBootUp(d))
+       StartOrStop(csSDO,      None,           resetSDO(d))
+//     StartOrStop(csSYNC,     startSYNC(d),           stopSYNC(d))
+       StartOrStop(csHeartbeat,        heartbeatInit(d),       heartbeatStop(d))
+//     StartOrStop(Emergency,,)
+       StartOrStop(csPDO,      None,   None)
+}
+
+UNS8 setState(CO_Data* d, e_nodeState newState)
+{
+       while(newState != d->nodeState){
+               switch( newState ){
+                       case Initialisation:
+                       {
+                               s_state_communication newCommunicationState = {
+                                       csBoot_Up: 1,
+                                       csSDO: 0,
+                                       csEmergency: 0,
+                                       csSYNC: 0,
+                                       csHeartbeat: 0,
+                                       csPDO: 0};
+                               // This will force a second loop for the state switch
+                               d->nodeState = Initialisation;
+                               newState = Pre_operational;
+                               switchCommunicationState(d, &newCommunicationState);
+                               // call user app related state func.
+                               (*d->initialisation)();
+#ifdef LED_ENABLE
+                               led_init();             
+#endif
+                       }
+                       break;
+                                                               
+                       case Pre_operational:
+                       {
+                               s_state_communication newCommunicationState = {
+                                       csBoot_Up: 0,
+                                       csSDO: 1,
+                                       csEmergency: 1,
+                                       csSYNC: 1,
+                                       csHeartbeat: 1,
+                                       csPDO: 0};
+                               d->nodeState = Pre_operational;
+                               newState = Pre_operational;
+                               switchCommunicationState(d, &newCommunicationState);
+                               (*d->preOperational)();
+#ifdef LED_ENABLE
+                               led_set_state(LED_PRE_OPS);             
+#endif
+                       }
+                       break;
+                                                               
+                       case Operational:
+                       if(d->nodeState == Initialisation) return 0xFF;
+                       {
+                               s_state_communication newCommunicationState = {
+                                       csBoot_Up: 0,
+                                       csSDO: 1,
+                                       csEmergency: 1,
+                                       csSYNC: 1,
+                                       csHeartbeat: 1,
+                                       csPDO: 1};
+                               d->nodeState = Operational;
+                               newState = Operational;
+                               switchCommunicationState(d, &newCommunicationState);
+                               (*d->operational)();
+#ifdef LED_ENABLE
+                               led_set_state(LED_OPS);         
+#endif
+                       }
+                       break;
+                                               
+                       case Stopped:
+                       if(d->nodeState == Initialisation) return 0xFF;
+                       {
+                               s_state_communication newCommunicationState = {
+                                       csBoot_Up: 0,
+                                       csSDO: 0,
+                                       csEmergency: 0,
+                                       csSYNC: 0,
+                                       csHeartbeat: 1,
+                                       csPDO: 0};
+                               d->nodeState = Stopped;
+                               newState = Stopped;
+                               switchCommunicationState(d, &newCommunicationState);
+                               (*d->stopped)();
+#ifdef LED_ENABLE
+                               led_set_state(LED_STOP);
+#endif                 
+                       }
+                       break;
+                       
+                       default:
+                               return 0xFF;
+               }//end switch case
+       }
+       return 0;
+}
+
+UNS8 getNodeId(CO_Data* d)
+{
+  return *d->bDeviceNodeId;
+}
+
+void setNodeId(CO_Data* d, UNS8 nodeId)
+{
+  UNS16 offset = d->firstIndex->SDO_SVR;
+  if(offset){
+      //cob_id_client = 0x600 + nodeId;
+      *(UNS32*)d->objdict[offset].pSubindex[1].pObject = 0x600 + nodeId;
+      //cob_id_server = 0x580 + nodeId;
+      *(UNS32*)d->objdict[offset].pSubindex[2].pObject = 0x580 + nodeId;
+      // node Id client. As we do not know the value, we put the node Id Server
+      *(UNS8*)d->objdict[offset].pSubindex[3].pObject = nodeId;
+  }
+
+  // ** Initialize the server(s) SDO parameters
+  // Remember that only one SDO server is allowed, defined at index 0x1200
+  // ** Initialize the client(s) SDO parameters  
+  // Nothing to initialize (no default values required by the DS 401)
+  // ** Initialize the receive PDO communication parameters. Only for 0x1400 to 0x1403
+  {
+    UNS8 i = 0;
+    //UNS32 pbData32;
+    UNS16 offset = d->firstIndex->PDO_RCV;
+    UNS16 lastIndex = d->lastIndex->PDO_RCV;
+    UNS32 cobID[] = {0x200, 0x300, 0x400, 0x500};
+    // TODO : Verify the index number (in case of hole in PDO index)
+    if( offset ) while( (offset <= lastIndex) && (i < 4)) {
+      if(*(UNS32*)d->objdict[offset].pSubindex[1].pObject == cobID[i] + *d->bDeviceNodeId)
+             *(UNS32*)d->objdict[offset].pSubindex[1].pObject = cobID[i] + nodeId;
+      //ret = setODentry(0x1400 + i, 1, &pbData32, 4, 0); // Subindex 1
+      i ++;
+      offset ++;
+    }
+  }
+  // ** Initialize the transmit PDO communication parameters. Only for 0x1800 to 0x1803
+  {
+    UNS8 i = 0;
+    //UNS32 pbData32;
+    UNS16 offset = d->firstIndex->PDO_TRS;
+    UNS16 lastIndex = d->lastIndex->PDO_TRS;
+    UNS32 cobID[] = {0x180, 0x280, 0x380, 0x480};
+    i = 0;
+    if( offset ) while ((offset <= lastIndex) && (i < 4)) {
+      //pbData32 = cobID[i] + nodeId;
+      // TODO : Verify the index number (in case of hole in PDO index)
+      if(*(UNS32*)d->objdict[offset].pSubindex[1].pObject == cobID[i] + *d->bDeviceNodeId)
+             *(UNS32*)d->objdict[offset].pSubindex[1].pObject = cobID[i] + nodeId;
+      //ret = setODentry(0x1800 + i, 1, &pbData32, 4, 0); // Subindex 1
+      i ++;
+      offset ++;
+    }
+  }
+  // bDeviceNodeId is defined in the object dictionary.
+  *d->bDeviceNodeId = nodeId;
+}
+/*
+void initResetMode(CO_Data* d)
+{
+  // Some stuff to do when the node enter in reset mode
+  *d->COB_ID_Sync &= ~0x40000000; 
+//  *d->Sync_Cycle_Period = 0; 
+//  *d->Sync_window_length = 0;
+  *d->ProducerHeartBeatTime = 0;
+  // Init the nodeguard toggle
+  d->toggle = 0;
+}
+*/
+void initPreOperationalMode(CO_Data* d)
+{
+  // Some stuff to do when the node enter in pre-operational mode
+  // Init the nodeguard toggle
+  d->toggle = 0;
+}
+
diff --git a/app/cantest/canfestival/src/sync.c b/app/cantest/canfestival/src/sync.c
new file mode 100644 (file)
index 0000000..f1de454
--- /dev/null
@@ -0,0 +1,259 @@
+/*\r
+This file is part of CanFestival, a library implementing CanOpen Stack. \r
+\r
+Copyright (C): Edouard TISSERANT and Francis DUPIN\r
+\r
+See COPYING file for copyrights details.\r
+\r
+This library is free software; you can redistribute it and/or\r
+modify it under the terms of the GNU Lesser General Public\r
+License as published by the Free Software Foundation; either\r
+version 2.1 of the License, or (at your option) any later version.\r
+\r
+This library is distributed in the hope that it will be useful,\r
+but WITHOUT ANY WARRANTY; without even the implied warranty of\r
+MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU\r
+Lesser General Public License for more details.\r
+\r
+You should have received a copy of the GNU Lesser General Public\r
+License along with this library; if not, write to the Free Software\r
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA\r
+*/\r
+\r
+#include "data.h"\r
+#include "sync.h"\r
+\r
+#ifdef CANOPEN_BIG_ENDIAN\r
+#warning "sync.c Compiling for big endian architecture"\r
+#else\r
+#warning "sync.c Compiling for little endian architecture"\r
+#endif\r
+\r
+void SyncAlarm(CO_Data* d, UNS32 id)\r
+{\r
+       sendSYNC(d, *d->COB_ID_Sync & 0x1FFFFFFF) ;\r
+}\r
+\r
+void startSYNC(CO_Data* d)\r
+{\r
+       if(*d->COB_ID_Sync & 0x40000000 && *d->Sync_Cycle_Period)\r
+       {\r
+               d->syncTimer = SetAlarm(\r
+                               d,\r
+                               0/*No id needed*/,\r
+                               &SyncAlarm,\r
+                               US_TO_TIMEVAL(*d->Sync_Cycle_Period), \r
+                               US_TO_TIMEVAL(*d->Sync_Cycle_Period));\r
+       }\r
+}\r
+\r
+void stopSYNC(CO_Data* d)\r
+{\r
+       d->syncTimer = DelAlarm(d->syncTimer);\r
+}\r
+\r
+/*********************************************************************/\r
+UNS8 sendSYNC(CO_Data* d, UNS32 cob_id)\r
+{\r
+  Message m;\r
+  UNS8 resultat ;\r
+  \r
+  MSG_WAR(0x3001, "sendSYNC ", 0);\r
+  \r
+  m.cob_id.w = cob_id ;\r
+  m.rtr = NOT_A_REQUEST;\r
+  m.len = 0;\r
+  resultat = (*d->canSend)(&m) ;\r
+  proceedSYNC(d, &m) ; \r
+  return resultat ;\r
+}\r
+\r
+/*****************************************************************************/\r
+UNS8 proceedSYNC(CO_Data* d, Message *m)\r
+{\r
+\r
+  MSG_WAR(0x3002, "SYNC received. Proceed. ", 0);\r
+\r
+  UNS8         pdoNum,       // number of the actual processed pdo-nr.\r
+    prp_j;\r
+\r
+  const UNS8 *     pMappingCount = NULL;      // count of mapped objects...\r
+  // pointer to the var which is mapped to a pdo\r
+  void *     pMappedAppObject = NULL; \r
+  // pointer fo the var which holds the mapping parameter of an mapping entry  \r
+  UNS32 *    pMappingParameter = NULL;  \r
+  // pointer to the transmissiontype...\r
+  UNS8 *     pTransmissionType = NULL;  \r
+  UNS32 *    pwCobId = NULL;   \r
+\r
+  UNS8 *    pSize;\r
+  UNS8      size;\r
+  UNS8      dataType;\r
+  UNS16 index;\r
+  UNS8 subIndex;\r
+  UNS8 offset;\r
+  UNS8 status;\r
+  UNS8 sizeData;\r
+  pSize = &size;\r
+  UNS32   objDict;     \r
+  status = state3;\r
+  pdoNum=0x00;\r
+  prp_j=0x00;\r
+  offset = 0x00;\r
+  UNS16 offsetObjdict;\r
+  UNS16 offsetObjdictMap;\r
+  UNS16 lastIndex;\r
+\r
+  /* only operational state allows PDO transmission */\r
+  if( d->nodeState != Operational ) \r
+    return 0;\r
+\r
+   (*d->post_sync)();\r
+  \r
+  /* So, the node is in operational state */\r
+  /* study all PDO stored in the objects dictionary */ \r
\r
+  offsetObjdict = d->firstIndex->PDO_TRS;\r
+  lastIndex = d->lastIndex->PDO_TRS;\r
+  offsetObjdictMap = d->firstIndex->PDO_TRS_MAP;\r
+  \r
+  if(offsetObjdict) while( offsetObjdict <= lastIndex) {  \r
+    switch( status ) {\r
+                    \r
+    case state3:    /* get the PDO transmission type */\r
+      if (d->objdict[offsetObjdict].bSubCount <= 2) {\r
+         MSG_ERR(0x1004, "Subindex 2  not found at index ", 0x1800 + pdoNum);\r
+         return 0xFF;\r
+       }\r
+      pTransmissionType = d->objdict[offsetObjdict].pSubindex[2].pObject;    \r
+      MSG_WAR(0x3005, "Reading PDO at index : ", 0x1800 + pdoNum);\r
+      status = state4; \r
+      break;     \r
+    case state4:       /* check if transmission type is after (this) SYNC */\r
+                        /* The message may not be transmited every SYNC but every n SYNC */      \r
+      if( (*pTransmissionType >= TRANS_SYNC_MIN) && (*pTransmissionType <= TRANS_SYNC_MAX) &&\r
+          (++d->count_sync[pdoNum] == *pTransmissionType) ) {  \r
+       d->count_sync[pdoNum] = 0;\r
+       MSG_WAR(0x3007, "  PDO is on SYNCHRO. Trans type : ", *pTransmissionType);\r
+       status = state5;\r
+       break;\r
+      }\r
+      else {\r
+       MSG_WAR(0x3008, "  Not on synchro or not at this SYNC. Trans type : ", \r
+               *pTransmissionType);\r
+       pdoNum++;\r
+       offsetObjdict++;\r
+       offsetObjdictMap++;\r
+       status = state11;\r
+       break;\r
+      }      \r
+    case state5:       /* get PDO CobId */\r
+        pwCobId = d->objdict[offsetObjdict].pSubindex[1].pObject;     \r
+       MSG_WAR(0x3009, "  PDO CobId is : ", *pwCobId);\r
+       status = state7;\r
+       break;     \r
+    case state7:  /* get mapped objects number to transmit with this PDO */\r
+      pMappingCount = d->objdict[offsetObjdictMap].pSubindex[0].pObject;\r
+      /*objDict = getODentry(d, 0x1A00 + pdoNum, 0,\r
+                           (void * *)&pMappingCount, pSize, &dataType, 0 );\r
+      if( objDict == OD_SUCCESSFUL ){*/\r
+       MSG_WAR(0x300D, "  Number of objects mapped : ",*pMappingCount );\r
+       status = state8;\r
+       /*break;\r
+      }\r
+      else {\r
+       MSG_ERR(0x100E, "  Failure while trying to get map count : 0X1A00 + ", pdoNum);\r
+       return 0xFF;\r
+      }*/     \r
+    case state8:       /* get mapping parameters */\r
+      pMappingParameter = d->objdict[offsetObjdictMap].pSubindex[prp_j + 1].pObject;\r
+      /*objDict = getODentry(d, 0x1A00 + pdoNum, prp_j + 1,\r
+                           (void * *)&pMappingParameter, pSize, &dataType, 0 );\r
+      if( objDict == OD_SUCCESSFUL ){*/\r
+       MSG_WAR(0x300F, "  got mapping parameter : ", *pMappingParameter);\r
+       MSG_WAR(0x3050, "    at index : ", 0x1A00 + pdoNum);\r
+       MSG_WAR(0x3051, "    sub-index : ", prp_j + 1);\r
+       status = state9;\r
+       /*break;\r
+      }\r
+      else {\r
+       MSG_ERR(0x1010, "  Couldn't get mapping parameter for subindex : ", prp_j + (UNS8)1);\r
+       return 0xFF;\r
+      }*/\r
+      \r
+    case state9:       /* get data to transmit */ \r
+      index = (UNS16)((*pMappingParameter) >> 16);\r
+      subIndex = (UNS8)(( (*pMappingParameter) >> (UNS8)8 ) & (UNS32)0x000000FF);\r
+      // <<3 because in *pMappingParameter the size is in bits\r
+      sizeData = (UNS8) ((*pMappingParameter & (UNS32)0x000000FF) >> 3) ;\r
+      objDict = getODentry(d, index, subIndex, (void * *)&pMappedAppObject, pSize, &dataType, 0 ); \r
+      if( objDict == OD_SUCCESSFUL ){\r
+       MSG_WAR(0x3011, "  Mapped data found size bytes : ", *pSize);\r
+       MSG_WAR(0x3012, "    at index : ", index);\r
+       MSG_WAR(0x3013, "    sub-index : ", subIndex);\r
+       if (sizeData != *pSize) {\r
+         MSG_WAR(0x2052, "  Size of data different than (size in mapping / 8) : ", sizeData);\r
+       }\r
+       memcpy(&d->process_var.data[offset], pMappedAppObject, sizeData);\r
+                \r
+       \r
+#       ifdef CANOPEN_BIG_ENDIAN\r
+       {\r
+         // data must be transmited with low byte first\r
+         UNS8 pivot, i;\r
+         for ( i = 0 ; i < ( sizeData >> 1)  ; i++) {\r
+           pivot = d->process_var.data[offset + (sizeData - 1) - i];\r
+           d->process_var.data[offset + (sizeData - 1) - i] = d->process_var.data[offset + i];\r
+           d->process_var.data[offset + i] = pivot ;\r
+         } // end for\r
+       }\r
+#       endif\r
+       \r
+       offset += sizeData ;\r
+       d->process_var.count = offset;\r
+       prp_j++;\r
+       status = state10;        \r
+       break;                                  \r
+      } // end if\r
+      else {\r
+       MSG_ERR(0x1013, " Couldn't find mapped variable at index-subindex-size : ", (UNS16)(*pMappingParameter));\r
+       return 0xFF;\r
+      }\r
+      \r
+    case state10:      /* loop to get all the data to transmit */\r
+      if( prp_j < *pMappingCount ){\r
+       MSG_WAR(0x3014, "  next variable mapped : ", prp_j);\r
+       status = state8;\r
+       break;\r
+      }\r
+      else {\r
+       MSG_WAR(0x3015, "  End scan mapped variable", 0);\r
+       PDOmGR( d, *pwCobId );  \r
+       MSG_WAR(0x3016, "  End of this pdo. Should have been sent", 0);\r
+       pdoNum++;\r
+       offsetObjdict++;\r
+       offsetObjdictMap++;\r
+       offset = 0x00;\r
+       prp_j = 0x00;\r
+       status = state11;\r
+       break;\r
+      }\r
+      \r
+    case state11:     \r
+      MSG_WAR(0x3017, "next pdo index : ", pdoNum);\r
+      status = state3;\r
+      break;\r
+      \r
+    default:\r
+      MSG_ERR(0x1019,"Unknown state has been reached : %d",status);\r
+      return 0xFF;\r
+    }// end switch case\r
+    \r
+  }// end while( prp_i<dict_cstes.max_count_of_PDO_transmit )\r
+   \r
+  (*d->post_TPDO)();\r
+\r
+  return 0;\r
+}\r
+\r
+\r
diff --git a/app/cantest/canfestival/src/timer.c b/app/cantest/canfestival/src/timer.c
new file mode 100644 (file)
index 0000000..1c55bc6
--- /dev/null
@@ -0,0 +1,164 @@
+/*\r
+This file is part of CanFestival, a library implementing CanOpen Stack. \r
+\r
+Copyright (C): Edouard TISSERANT and Francis DUPIN\r
+\r
+See COPYING file for copyrights details.\r
+\r
+This library is free software; you can redistribute it and/or\r
+modify it under the terms of the GNU Lesser General Public\r
+License as published by the Free Software Foundation; either\r
+version 2.1 of the License, or (at your option) any later version.\r
+\r
+This library is distributed in the hope that it will be useful,\r
+but WITHOUT ANY WARRANTY; without even the implied warranty of\r
+MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU\r
+Lesser General Public License for more details.\r
+\r
+You should have received a copy of the GNU Lesser General Public\r
+License along with this library; if not, write to the Free Software\r
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA\r
+*/\r
+\r
+//#define DEBUG_WAR_CONSOLE_ON\r
+//#define DEBUG_ERR_CONSOLE_ON\r
+\r
+#include <applicfg.h>\r
+#include "timer.h"\r
+\r
+// ---------  The timer table ---------\r
+s_timer_entry timers[MAX_NB_TIMER] = {{TIMER_FREE, NULL, NULL, 0, 0, 0},};\r
+//\r
+TIMEVAL total_sleep_time = TIMEVAL_MAX;\r
+TIMER_HANDLE last_timer_raw = -1;\r
+\r
+#define max(a,b) a>b?a:b\r
+#define min(a,b) a<b?a:b\r
+\r
+// ---------  Use this to declare a new alarm ---------\r
+TIMER_HANDLE SetAlarm(CO_Data* d, UNS32 id, TimerCallback_t callback, TIMEVAL value, TIMEVAL period)\r
+{\r
+       //printf("SetAlarm(UNS32 id=%d, TimerCallback_t callback=%x, TIMEVAL value=%d, TIMEVAL period=%d)\n", id, callback, value, period);\r
+       TIMER_HANDLE i;\r
+       TIMER_HANDLE row_number = TIMER_NONE;\r
+\r
+       // in order to decide new timer setting we have to run over all timer rows\r
+       for(i=0; i <= last_timer_raw + 1 && i < MAX_NB_TIMER; i++)\r
+       {\r
+               s_timer_entry *row = (timers+i);\r
+\r
+               if (callback &&         // if something to store\r
+                  row->state == TIMER_FREE) // and empty row\r
+               {       // just store\r
+                       row->callback = callback;\r
+                       row->d = d;\r
+                       row->id = id;\r
+                       row->val = value;\r
+                       row->interval = period;\r
+                       row->state = TIMER_ARMED;\r
+                       row_number = i;\r
+                       break;\r
+               }\r
+       }\r
+       \r
+       if (row_number != TIMER_NONE) // if successfull\r
+       {\r
+               if (row_number == last_timer_raw + 1) last_timer_raw++;\r
+               \r
+               // set next wakeup alarm if new entry is sooner than others, or if it is alone\r
+               TIMEVAL real_timer_value = min(value, TIMEVAL_MAX);\r
+               TIMEVAL elapsed_time = getElapsedTime();\r
+\r
+               //printf("elapsed_time=%d real_timer_value=%d total_sleep_time=%d\n", elapsed_time, real_timer_value, total_sleep_time);\r
+               if (total_sleep_time > elapsed_time && total_sleep_time - elapsed_time > real_timer_value)\r
+               {\r
+                       total_sleep_time = elapsed_time + real_timer_value;\r
+                       setTimer(real_timer_value);\r
+               }\r
+               //printf("SetAlarm() return %d\n", row_number);\r
+               return row_number;\r
+       }\r
+       return TIMER_NONE;\r
+}\r
+\r
+// ---------  Use this to remove an alarm ---------\r
+TIMER_HANDLE DelAlarm(TIMER_HANDLE handle)\r
+{\r
+       // Quick and dirty. system timer will continue to be trigged, but no action will be preformed.\r
+       MSG_WAR(0x3320, "DelAlarm. handle = ", handle);\r
+       if(handle != TIMER_NONE)\r
+       {\r
+               if(handle == last_timer_raw) \r
+                       last_timer_raw--;\r
+               timers[handle].state = TIMER_FREE;              \r
+       }\r
+       else {\r
+       }\r
+       return TIMER_NONE;\r
+}\r
+\r
+\r
+// ---------  TimeDispatch is called on each timer expiration ---------\r
+void TimeDispatch()\r
+{\r
+       TIMER_HANDLE i;\r
+       TIMEVAL next_wakeup = TIMEVAL_MAX; // used to compute when should normaly occur next wakeup\r
+       // First run : change timer state depending on time\r
+       // Get time since timer signal\r
+       TIMEVAL overrun = getElapsedTime();\r
+       \r
+       TIMEVAL real_total_sleep_time = total_sleep_time + overrun;\r
+       //printf("total_sleep_time %d + overrun %d\n", total_sleep_time , overrun);\r
+\r
+       for(i=0; i <= last_timer_raw; i++)\r
+       {\r
+               s_timer_entry *row = (timers+i);\r
+\r
+               if (row->state & TIMER_ARMED) // if row is active\r
+               {\r
+                       if (row->val <= real_total_sleep_time) // to be trigged\r
+                       {\r
+                               //printf("row->val(%d) <= (%d)real_total_sleep_time\n", row->val, real_total_sleep_time);\r
+                               if (!row->interval) // if simply outdated\r
+                               {\r
+                                       row->state = TIMER_TRIG; // ask for trig\r
+                               }\r
+                               else // or period have expired\r
+                               {\r
+                                       // set val as interval, with overrun correction\r
+                                       row->val = row->interval - (overrun % row->interval);\r
+                                       row->state = TIMER_TRIG_PERIOD; // ask for trig, periodic\r
+                                       // Check if this new timer value is the soonest\r
+                                       next_wakeup = min(row->val,next_wakeup);\r
+                               }\r
+                       }\r
+                       else\r
+                       {\r
+                               // Each armed timer value in decremented.\r
+                               row->val -= real_total_sleep_time;\r
+\r
+                               // Check if this new timer value is the soonest\r
+                               next_wakeup = min(row->val,next_wakeup);\r
+                       }\r
+               }\r
+       }\r
+       \r
+       // Remember how much time we should sleep.\r
+       total_sleep_time = next_wakeup;\r
+\r
+       // Set timer to soonest occurence\r
+       setTimer(next_wakeup);\r
+\r
+       // Then trig them or not.\r
+       for(i=0; i<=last_timer_raw; i++)\r
+       {\r
+               s_timer_entry *row = (timers+i);\r
+\r
+               if (row->state & TIMER_TRIG)\r
+               {\r
+                       row->state &= ~TIMER_TRIG; // reset trig state (will be free if not periodic)\r
+                       (*row->callback)(row->d, row->id); // trig !\r
+               }\r
+       }\r
+}\r
+\r
diff --git a/app/cantest/timer/Makefile b/app/cantest/timer/Makefile
new file mode 100644 (file)
index 0000000..f595272
--- /dev/null
@@ -0,0 +1,14 @@
+# Generic directory or leaf node makefile for OCERA make framework
+
+ifndef MAKERULES_DIR
+MAKERULES_DIR := $(shell ( old_pwd="" ;  while [ ! -e Makefile.rules ] ; do if [ "$$old_pwd" == `pwd`  ] ; then exit 1 ; else old_pwd=`pwd` ; cd -L .. 2>/dev/null ; fi ; done ; pwd ) )
+endif
+
+ifeq ($(MAKERULES_DIR),)
+all : default
+.DEFAULT::
+       @echo -e "\nThe Makefile.rules has not been found in this or partent directory\n"
+else   
+include $(MAKERULES_DIR)/Makefile.rules
+endif
+
diff --git a/app/cantest/timer/Makefile.omk b/app/cantest/timer/Makefile.omk
new file mode 100644 (file)
index 0000000..fca35b1
--- /dev/null
@@ -0,0 +1,10 @@
+# -*- makefile -*-
+
+bin_PROGRAMS  = timer_tst_cmd
+
+timer_tst_cmd_SOURCES = timer_tst_cmd.c timerhw.c
+
+timer_tst_cmd_LIBS = boot_fn arch_drivers sci_channels excptvec misc
+timer_tst_cmd_MOREOBJS = $(USER_LIB_DIR)/system_stub.o
+
+#SUBDIRS = ../../arch/h8300/generic/drivers ../../arch/h8300/mach-2638/drivers
diff --git a/app/cantest/timer/timer_tst_cmd.c b/app/cantest/timer/timer_tst_cmd.c
new file mode 100644 (file)
index 0000000..8852ea5
--- /dev/null
@@ -0,0 +1,202 @@
+/* procesor H8S/2638 ver 1.1  */
+#include <stdio.h>
+#include <types.h>
+#include <cpu_def.h>
+#include <h8s2638h.h>
+#include <system_def.h>
+#include <string.h>
+#include <periph/sci_rs232.h>
+#include <utils.h>
+//#include <boot_fn.h>
+#include <cmd_proc.h>
+#include "timerhw.h"
+
+ #ifndef DEB_LED_OUT
+  #define DEB_LED_OUT
+  static void deb_led_out(char val)
+  {
+    if (val&1)
+      DEB_LED_ON(0);
+    else
+      DEB_LED_OFF(0);
+    if (val&2)
+      DEB_LED_ON(1);
+    else
+      DEB_LED_OFF(1);
+    if (val&4)
+      DEB_LED_ON(2);
+    else
+      DEB_LED_OFF(2);
+    if (val&8)
+      DEB_LED_ON(3);
+    else
+      DEB_LED_OFF(3);
+   }
+ #endif
+
+/* ---- handling interupt vectors */
+void test_unhandled_isr(void) __attribute__ ((interrupt_handler));
+void test_unhandled_isr(void)
+{
+  #if DEBUG
+    deb_led_out(2);
+  #endif
+  while(1);
+}
+
+/* ---- global variables */
+
+
+/* ---- function on end of file declaration */
+int cmd_rs232_test(void);
+
+// ports initialization
+void init()
+{
+    DEB_LED_INIT();
+}
+
+
+
+/* ---- main function --- */
+int main()
+{
+  /* variables declaration and initialization */
+  int rs232_init_ok=0;
+
+  excptvec_initfill(test_unhandled_isr,1); /* catch all unhadled interrupts */
+  excptvec_set(40,timer1_p_int); /* Timer interrupt */
+  sti();
+  init(); /* Init for deb. LEDs */
+  /* set serial chanel */
+  if(sci_rs232_setmode(19200, 0, 0, sci_rs232_chan_default)>=0)  {
+    rs232_init_ok=1;
+    //FlWait(2*1000000);
+    deb_led_out(1);
+    printf("I am alive, you can ask for \"help\"\n ported version for EDK2638\n");
+  };
+  #if 1
+    // int info;
+    while(1){
+      if((!(ms%1000))&&(ms>1))
+        printf("cas:%ld ms, cas:%ld s, count:0x%x\n", ms, ms/1000, (int) stav_counteru);
+      cmd_rs232_test();
+    };
+  #endif
+
+  /* blink LEDs */
+   while(1)
+   {
+      deb_led_out(0);
+      FlWait(2*100000);
+      printf("End of execution \n EDK2638\n");
+      deb_led_out(3);
+      FlWait(2*100000);
+   };
+};
+/* ------------------------------------------------------------------------------------------------------------ */
+/* COMMAND */
+/* new command add -> add new function cmd_do_name, cmd_des_name update variable cmd_rs232_default */
+# if 1
+/* ---- prikaz: POKUS pridan pokus pro vyzkouseni command systemu */
+int cmd_do_pokus(cmd_io_t *cmd_io, const struct cmd_des *des, char *param[])
+{ 
+  printf("Test command POKUS \"help\"\n pokus uspesny\n");
+  return 0; 
+}
+
+cmd_des_t const cmd_des_pokus={0, CDESM_OPCHR,
+                       "POKUS","test command",
+                       cmd_do_pokus,{}};
+/* ---------------------------------  TIMER  -------------------------------- */
+int cmd_do_timer(cmd_io_t *cmd_io, const struct cmd_des *des, char *param[])
+{ 
+  printf("Command timer, CTS2=%d, ints:%d\n", *TPU_TSTR &=TSTR_CST2m, ints);
+  if(*TPU_TSTR &=TSTR_CST2m)
+    *TPU_TSTR &=~TSTR_CST2m;
+  else
+    *TPU_TSTR |=TSTR_CST2m;
+  printf("Command timer, CTS2=%d, ints:%d\n", *TPU_TSTR &=TSTR_CST2m, ints);
+  return 0;
+}
+
+cmd_des_t const cmd_des_timer={0, CDESM_OPCHR,
+                       "TIMER","test timer",
+                       cmd_do_timer,{}};
+
+/* ---------------------------------  TIMERINIT  -------------------------------- */
+int cmd_do_timerinit(cmd_io_t *cmd_io, const struct cmd_des *des, char *param[])
+{ 
+  printf("Command timer init, CTS1:%d\n", *TPU_TSTR &=TSTR_CST1m);
+  //init_timer1();
+  //initTimer1();
+  //init_timer1_p();
+  initTimerClk();
+  return 0;
+}
+
+cmd_des_t const cmd_des_timerinit={0, CDESM_OPCHR,
+                       "TIMERINIT","init timer",
+                       cmd_do_timerinit,{}};
+
+/* ---- prikaz: CAN */
+int cmd_do_can(cmd_io_t *cmd_io, const struct cmd_des *des, char *param[])
+{ 
+  /* printf("Test command POKUS \"help\"\n pokus uspesny\n");   */
+  printf("nic \n");
+  return 0; 
+}
+
+cmd_des_t const cmd_des_can={0, CDESM_OPCHR,
+                       "CAN","CAN 1-Setup,2-Read,3-Power Up",
+                       cmd_do_can,{}};
+
+/* ---- prikaz help, vytiskne detaily vsech prikazu z cmd_des_ */
+cmd_des_t const cmd_des_help={0, 0,"help","prints help for commands",
+                       cmd_do_help,{(char*)&cmd_rs232}};
+
+/* ---- Seznam prikazu. */
+extern cmd_des_t *cmd_iic_test[1];
+
+cmd_des_t const *cmd_rs232_default[]={
+  &cmd_des_help,
+  &cmd_des_pokus, /* pridano na zkousku */
+  &cmd_des_can, /* nastavovani can komunikace */
+  &cmd_des_timer,      /* Testing timer function */
+  &cmd_des_timerinit,  /* Initialize timer */
+  NULL
+};
+
+cmd_des_t const **cmd_rs232=cmd_rs232_default;
+/* ---- main command procedure */
+int cmd_rs232_test(void)
+{
+  int val;
+  cmd_io_t* cmd_io;
+
+  cmd_io=&cmd_io_rs232;
+  //printf("Enter cmd_rs232_test\n"); //kanal:%d \n", cmd_io_getc_rs232(cmd_io));
+  if(cmd_rs232_line_out(cmd_io))
+    return 1;
+  if(cmd_rs232_line_in(cmd_io)<=0)
+    return 0;
+  if(cmd_rs232){
+    val=proc_cmd_line(cmd_io, cmd_rs232, cmd_io->priv.ed_line.in->buf);
+  }else{
+    val=-CMDERR_BADCMD;
+  }
+  if(cmd_io->priv.ed_line.out->inbuf){
+    cmd_io_putc(cmd_io,'\r');
+    cmd_io_putc(cmd_io,'\n');
+  }else if(val<0){
+    char s[20];
+    cmd_io_write(&cmd_io_rs232,"ERROR ",6);
+    i2str(s,-val,0,0);
+    cmd_io_write(cmd_io,s,strlen(s));
+    cmd_io_putc(cmd_io,'\r');
+    cmd_io_putc(cmd_io,'\n');
+  }
+  return 1;
+}
+#endif
+
diff --git a/app/cantest/timer/timerhw.c b/app/cantest/timer/timerhw.c
new file mode 100644 (file)
index 0000000..56b079f
--- /dev/null
@@ -0,0 +1,269 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+//#include "applicfg.h"
+//#include "interrupt.h"
+#include "timerhw.h"
+//#include "../include/timer.h"
+#include <cpu_def.h>
+#include <h8s2638h.h>
+#include <system_def.h>
+#include <stdio.h>
+
+/* !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!! */
+//#define PORT_DIS_FUNC /* projekt nebude fungovat, ale lze kompilovat */
+
+
+
+ #ifndef DEB_LED_OUT
+  #define DEB_LED_OUT
+  static void deb_led_out(char val)
+  {
+    if (val&1)
+      DEB_LED_ON(0);
+    else
+      DEB_LED_OFF(0);
+    if (val&2)
+      DEB_LED_ON(1);
+    else
+      DEB_LED_OFF(1);
+    if (val&4)
+      DEB_LED_ON(2);
+    else
+      DEB_LED_OFF(2);
+    if (val&8)
+      DEB_LED_ON(3);
+    else
+      DEB_LED_OFF(3);
+   }
+ #endif
+
+/* Function called every 1 ms by the timer channel 4
+*  This function call timerInterrupt()
+*/
+/*
+void __attribute__((interrupt)) timer4Hdl (void);
+
+void resetTimer(void)
+{
+
+}
+*/
+void timer2Hdl (void) __attribute__ ((interrupt_handler));
+void timer2Hdl (void)
+{
+  //unsigned short saveif;     /* interrupt every 1s */
+
+  //save_and_cli(saveif);      /* interrupts save and disable */
+  *TPU_TSR2 &= ~TSR2_TGFAm;    /* clear compare match */
+  //incDate();
+   deb_led_out(i);
+         if(i<3) i++;
+         else i=0;
+  ints++;
+  //restore_flags(saveif);     /* interruptions restore end enable */
+}
+
+void initTimerClk(void)
+{
+  //unsigned short saveif;
+
+  //save_and_cli(saveif);      /* interrupts save and disable */
+  excptvec_set(44,timer2Hdl);  /* register interrup routine for this timer */
+  if(*SYS_MSTPCRA&MSTPCRA_TPUm)        /* when module is stoped do */
+    *SYS_MSTPCRA &= ~MSTPCRA_TPUm; // power TPU unit
+  *TPU_TSTR &=~TSTR_CST2m;     // stop timer in all case
+  *TPU_TCR2 =(TCR_TPSC2m|TCR_TPSC1m|TCR_TPSC0m)|(TCR1_CCLR0m); //rising edge, f divided by 1024, cleared by compare TGRA
+  *TPU_TMDR2 =0x00;    // normal mode
+  *TPU_TIOR2=0x00;     /* output compare is disabled */
+  *TPU_TSR2 &= ~TSR_TGFAm ;    //clear flag for TGRA compare
+  *TPU_TIER2 = TIER_TGIEAm;    //enable interrupt on compare with TGFA 
+  *TPU_TCNT2 = 0x00;
+  *TPU_TGR2A = 0x4650;         /* cout for 1 s, compare TGRA */
+  //TPU_TGR2B
+        printf("SYS_MSTPCRA:0x%x, TPU_TSTR:0x%x, TPU_TCR2:0x%x\n", *SYS_MSTPCRA, *TPU_TSTR, *TPU_TCR2);
+        printf("TPU_TMDR2:0x%x, TPU_TIOR2:0x%x, TPU_TSR2:0x%x\n", *TPU_TMDR2, *TPU_TIOR2, *TPU_TSR2);
+        printf("TPU_TIER2:0x%x, TPU_TCNT2:0x%x, TPU_TGRA2:0x%x\n", *TPU_TIER2, *TPU_TCNT2, *TPU_TGR2A);
+       FlWait(5*100000);
+  *TPU_TSTR |=TSTR_CST2m;      //start timer
+  //restore_flags(saveif);     /* interruptions restore end enable */
+}
+
+
+
+
+#if 1
+/* Using timer */
+//Interrupt routine
+void  LightOn(void) __attribute__ ((interrupt_handler));
+void LightOn(void)
+{
+       *TPU_TSR1 &= ~TSR1_TCFVm ; //reset overflow flag
+       *TPU_TCNT1 = 0xFFFF - 29*1000;
+       //i = (i + 1) & 7;
+       deb_led_out(i);
+       if(i<3) i++;
+       else i=0;
+       ints++;
+       //FlWait(1*200000);
+}
+
+void  timer1_int(void) __attribute__ ((interrupt_handler));
+void timer1_int(void)
+{
+       uint16_t timer_stav;
+       *TPU_TSR1 &= ~TSR1_TCFVm ; //reset overflow flag
+       *TPU_TCNT1 = (0xffff-0x481-0xa);        /* count for time 1 ms, set in initTimer also */
+                                               /* experimentaly measured time for handle interrupt */
+       if(ints==1000) {
+          ints=0;
+         deb_led_out(i);
+         if(i<3) i++;
+         else i=0;
+       };
+       ints++;
+        ms++;
+       //FlWait(1*200000);
+}
+
+void timer1_p_int(void) __attribute__ ((interrupt_handler));
+void timer1_p_int(void)
+{
+       uint16_t timer_stav;
+       *TPU_TSR1 &= ~TSR_TGFAm; //reset overflow flag
+       //*TPU_TCNT1 = (0xffff-0x481-0xa);      /* count for time 1 ms, set in initTimer also */
+                                               /* experimentaly measured time for handle interrupt */
+       if(ints==1000) {
+          ints=0;
+         deb_led_out(i);
+         if(i<3) i++;
+         else i=0;
+       };
+       ints++;
+        ms++;
+       //FlWait(1*200000);
+}
+
+//int auto_timer_settings();
+/* free running */
+void init_timer1(void) {
+       #if 1
+        if(*SYS_MSTPCRA&MSTPCRA_TPUm)  /* when module is stoped do */
+         *SYS_MSTPCRA &= ~MSTPCRA_TPUm; // power TPU unit
+        *TPU_TSTR &=~TSTR_CST1m;       // stop timer in all case
+       //*TPU_TCR1 =0x06; //rising edge, f divided by 256
+       *TPU_TCR1 =TCR_TPSC1m; //rising edge, f divided by 16
+       *TPU_TMDR1 =0x00;       // normal mode
+       //*TPU_TIOR1
+       *TPU_TSR1 &= ~TSR1_TCFVm ;      //reset overflow flag
+       *TPU_TIER1 |=TIER1_TCIEVm;      //enable overflow interrupt
+       //*TPU_TCNT
+       *TPU_TSTR |=TSTR_CST1m;         //start timer
+        ints=0;
+
+       #else
+       *SYS_MSTPCRA &= ~MSTPCRA_TPUm; // power TPU unit
+       *TPU_TCR1 =0x06; //rising edge, f divided by 256
+       *TPU_TMDR1 =0x00; // normal mode
+       *TPU_TSR1 &= ~TSR1_TCFVm ; //reset overflow flag
+       *TPU_TIER1 |=TIER1_TCIEVm; //enable overflow interrupt
+       *TPU_TSTR |=TSTR_CST1m; //start timer
+       #endif
+}
+
+void init_timer1_p(void) {
+       #if 1
+       if(*SYS_MSTPCRA&MSTPCRA_TPUm)   /* when module is stoped do */
+         *SYS_MSTPCRA &= ~MSTPCRA_TPUm; // power TPU unit
+        *TPU_TSTR &=~TSTR_CST1m;       // stop timer in all case
+       //*TPU_TCR1 =0x06; //rising edge, f divided by 256
+       *TPU_TCR1 =TCR_TPSC1m|(TCR1_CCLR0m); //rising edge, f divided by 16, cleared by compare TGRA
+       *TPU_TMDR1 =0x00;       // normal mode
+       *TPU_TIOR1=0x00;        /* output compare is disabled */
+       *TPU_TSR1 &= ~TSR_TGFAm ;       //clear flag for TGRA compare
+       *TPU_TIER1 = TIER_TGIEAm;       //enable interrupt on compare with TGFA 
+       *TPU_TCNT1 = 0x00;
+        *TPU_TGR1A = 0x0480;           /* cout for 1 ms compare TGRA */
+       //TPU_TGR1B
+        printf("SYS_MSTPCRA:0x%x, TPU_TSTR:0x%x, TPU_TCR1:0x%x\n", *SYS_MSTPCRA, *TPU_TSTR, *TPU_TCR1);
+        printf("TPU_TMDR1:0x%x, TPU_TIOR1:0x%x, TPU_TSR1:0x%x\n", *TPU_TMDR1, *TPU_TIOR1, *TPU_TSR1);
+        printf("TPU_TIER:0x%x, TPU_TCNT1:0x%x, TPU_TGR1A:0x%x\n", *TPU_TIER1, *TPU_TCNT1, *TPU_TGR1A);
+        FlWait(5*100000);
+       *TPU_TSTR |=TSTR_CST1m;         //start timer
+        ints=0;
+
+       #else
+       *SYS_MSTPCRA &= ~MSTPCRA_TPUm; // power TPU unit
+       *TPU_TCR1 =0x06; //rising edge, f divided by 256
+       *TPU_TMDR1 =0x00; // normal mode
+       *TPU_TSR1 &= ~TSR1_TCFVm ; //reset overflow flag
+       *TPU_TIER1 |=TIER1_TCIEVm; //enable overflow interrupt
+       *TPU_TSTR |=TSTR_CST1m; //start timer
+       #endif
+}
+
+void stop_timer1(void)
+{
+       *TPU_TSTR &=~TSTR_CST1m;        //stop timer
+};
+
+void start_timer1(void)
+{
+       if(*SYS_MSTPCRA &= MSTPCRA_TPUm) // power TPU unit, 1 = nopower
+         init_timer1();
+       *TPU_TSTR &=~TSTR_CST1m;        //start timer
+};
+#endif /* veci navic */
+
+//timer initialisation
+/*free running counter*/
+void initTimer(void)
+{
+  unsigned short saveif;
+
+  save_and_cli(saveif);        /* interrupts save and disable */
+  *SYS_MSTPCRA &= ~MSTPCRA_TPUm; // power TPU unit
+  *TPU_TSTR &=~TSTR_CST1m;     // stop timer in all case
+  *TPU_TCR1 =TCR_TPSC1m; //rising edge, f divided by 16
+  *TPU_TMDR1 =(0x0f&0x00);     // TGRA normal, normal operation  //TMDR_BFAm|TMDR_BFBm|
+  //*TPU_TIOR1
+  *TPU_TSR1 &= ~TSR1_TCFVm ;   //reset overflow flag
+  *TPU_TIER1 |=TIER1_TCIEVm;   //enable overflow interrupt
+  *TPU_TCNT1 = 0xffff-0x481;   /* count for time 1 ms, set in TPU1_test also */ 
+  *TPU_TSTR |=TSTR_CST1m;      //start timer
+  restore_flags(saveif);       /* interruptions restore end enable */
+}
+
+
+
+void timer4Hdl (void)
+{
+  unsigned short saveif;
+
+  save_and_cli(saveif);        /* interrupts save and disable */
+  *TPU_TSR1 &= ~TSR1_TCFVm ;   /* reset overflow flag */
+  *TPU_TCNT1 = (0xffff-0x481); /* count for time 1 ms, set in initTimer also */
+  restore_flags(saveif);       /* interruptions restore end enable */
+  //timerInterrupt(0);
+}
+
+
diff --git a/app/cantest/timer/timerhw.h b/app/cantest/timer/timerhw.h
new file mode 100644 (file)
index 0000000..89b9edb
--- /dev/null
@@ -0,0 +1,58 @@
+/*
+This file is part of CanFestival, a library implementing CanOpen Stack. 
+
+Copyright (C): Edouard TISSERANT and Francis DUPIN
+
+See COPYING file for copyrights details.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library 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
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+*/
+
+#ifndef  __TIMER_HW__
+#define  __TIMER_HW__
+
+/** Initiates the timer. Normally the timer should create an overflow every 1ms.
+ *  but on linux it is a bit complicated to do this. Thats the reason why
+ *  it only generates an overflow every 100ms at the moment
+ */
+void initTimer (void);
+
+
+/** Resets the timer. This is mainly needed for microcontrollers where interrupt
+ *  flags have to be set back and initial values for the timer registers have
+ *  to be set.
+ */
+void resetTimer (void);
+
+void LightOn(void);
+void timer1_int(void);
+void init_timer1(void);
+void stop_timer1(void);
+void start_timer1(void);
+void timer1_p_int(void);
+void init_timer1_p(void);
+void initTimerClk(void);
+
+int i,ints;
+long ms;
+unsigned int stav_counteru;
+
+
+#endif
+
+
+
+
+
diff --git a/build/h8canusb/Makefile b/build/h8canusb/Makefile
new file mode 120000 (symlink)
index 0000000..34ef4a2
--- /dev/null
@@ -0,0 +1 @@
+../_infrastructure/h8300-boot/Makefile
\ No newline at end of file
diff --git a/build/h8canusb/Makefile.omk b/build/h8canusb/Makefile.omk
new file mode 120000 (symlink)
index 0000000..9606c8d
--- /dev/null
@@ -0,0 +1 @@
+../_infrastructure/h8300-boot/Makefile.omk
\ No newline at end of file
diff --git a/build/h8canusb/Makefile.rules b/build/h8canusb/Makefile.rules
new file mode 120000 (symlink)
index 0000000..bec717d
--- /dev/null
@@ -0,0 +1 @@
+../_infrastructure/h8300-boot/Makefile.rules
\ No newline at end of file
diff --git a/build/h8canusb/README.makerules b/build/h8canusb/README.makerules
new file mode 120000 (symlink)
index 0000000..69fb737
--- /dev/null
@@ -0,0 +1 @@
+../_infrastructure/h8300-boot/README.makerules
\ No newline at end of file
diff --git a/build/h8canusb/app b/build/h8canusb/app
new file mode 120000 (symlink)
index 0000000..dd10d89
--- /dev/null
@@ -0,0 +1 @@
+../_infrastructure/h8300-boot/app
\ No newline at end of file
diff --git a/build/h8canusb/arch b/build/h8canusb/arch
new file mode 120000 (symlink)
index 0000000..17b6e20
--- /dev/null
@@ -0,0 +1 @@
+../_infrastructure/h8300-boot/arch
\ No newline at end of file
diff --git a/build/h8canusb/board b/build/h8canusb/board
new file mode 120000 (symlink)
index 0000000..3ed46c3
--- /dev/null
@@ -0,0 +1 @@
+../_infrastructure/h8300-boot/board
\ No newline at end of file
diff --git a/build/h8canusb/cantest b/build/h8canusb/cantest
new file mode 120000 (symlink)
index 0000000..186f288
--- /dev/null
@@ -0,0 +1 @@
+../../app/cantest/
\ No newline at end of file
diff --git a/build/h8canusb/common b/build/h8canusb/common
new file mode 120000 (symlink)
index 0000000..c774f2e
--- /dev/null
@@ -0,0 +1 @@
+../../app/common
\ No newline at end of file
diff --git a/build/h8canusb/config.omk b/build/h8canusb/config.omk
new file mode 120000 (symlink)
index 0000000..2eaa1b6
--- /dev/null
@@ -0,0 +1 @@
+board/h8canusb/config.h8canusb
\ No newline at end of file
diff --git a/build/h8canusb/hello b/build/h8canusb/hello
new file mode 120000 (symlink)
index 0000000..605a3c2
--- /dev/null
@@ -0,0 +1 @@
+../../app/hello
\ No newline at end of file
diff --git a/build/h8canusb/libcan b/build/h8canusb/libcan
new file mode 120000 (symlink)
index 0000000..ffe5073
--- /dev/null
@@ -0,0 +1 @@
+../../app/libcan
\ No newline at end of file
diff --git a/build/h8canusb/libs4c b/build/h8canusb/libs4c
new file mode 120000 (symlink)
index 0000000..2cef71f
--- /dev/null
@@ -0,0 +1 @@
+../_infrastructure/h8300-boot/libs4c
\ No newline at end of file
index a1fab2a16d31730e0fb16b205d068c6b20b94540..1ce38c8c7dfed458acc46ac167d79238596406ba 100755 (executable)
@@ -4,7 +4,7 @@ if [ ! -d _infrastructure/h8300-boot/_darcs ]; then
     [ -x "`which darcs`" ] && darcs get rtime.felk.cvut.cz:/var/repos/h8300-boot --repo-name=_infrastructure/h8300-boot || exit 1
 fi
 
-for i in h8eurobot/ h8mirosot/ linux/ ppc/; do
+for i in h8eurobot/ h8mirosot/ h8canusb/ linux/ ppc/; do
        make -C $i default-config
 done