diff --git a/Makefile b/Makefile
index a114da239b4073b6e28c21912f0e2168804977de..eeb471a7684a62268bfbd0597f4fd42a3fba967b 100755
--- a/Makefile
+++ b/Makefile
@@ -7,14 +7,13 @@ STM32_LIBRARIES_PATH=$(HOME)/humanoids/stm32_libraries
 PROJECT_NAME=darwin_firmware
 #TARGET_FILES=$(wildcard src/*.c)
 TARGET_FILES=src/cm730_fw.c
-#TARGET_FILES+=src/test_charger.c
+TARGET_FILES+=src/eeprom.c
 TARGET_FILES+=src/system_stm32f1xx.c
 TARGET_FILES+=src/gpio.c
-#TARGET_FILES+=src/darwin_time.c
-TARGET_FILES+=src/eeprom.c
+TARGET_FILES+=src/darwin_time.c
 TARGET_FILES+=src/adc_dma.c
 TARGET_FILES+=src/imu.c
-#TARGET_FILES+=src/darwin_dyn_slave.c
+TARGET_FILES+=src/darwin_dyn_slave.c
 #TARGET_FILES+=src/darwin_dyn_master.c
 #TARGET_FILES+=src/darwin_dyn_master_v2.c
 TARGET_FILES+=src/stm32f1xx_hal_msp.c
diff --git a/include/darwin_conf.h b/include/darwin_conf.h
index 97ee25acf58ba5d7c20cfad94ef02b2d9a344569..577308c12f14edc0828bdca1a295743d07161015 100644
--- a/include/darwin_conf.h
+++ b/include/darwin_conf.h
@@ -4,6 +4,21 @@
 #define           RAM_SIZE               1024
 #define           EEPROM_SIZE            256
 
+/* Dynamixel slave configuration */
+#define EEPROM_DYN_SLAVE_BASE_ADDRESS1        ((unsigned short int)0x0000)
+#define EEPROM_DYN_SLAVE_BASE_ADDRESS2        ((unsigned short int)0x0010)
+
+#define DEFAULT_DEVICE_MODEL                  0x7300
+#define DEFAULT_FIRMWARE_VERSION              0x0001
+#define DEFAULT_DEVICE_ID                     0x0001
+#define DEFAULT_BAUDRATE                      0x0010
+#define DEFAULT_RETURN_DELAY                  0x0000
+#define DEFAULT_RETURN_LEVEL                  0x0002
+
+#define MAX_DYN_SLAVE_TX_BUFFER_LEN           1024
+#define MAX_DYN_SLAVE_RX_BUFFER_LEN           1024
+#define MAX_DYN_SLAVE_REG_BUFFER_LEN          1024
+
 /* GPIO configuration */
 #define RAM_GPIO_BASE_ADDRESS                 ((unsigned short int)0x0100)
 
diff --git a/include/darwin_dyn_slave.h b/include/darwin_dyn_slave.h
index b3a38c9467c69f2be448e3c19c64fa92437468e4..49437d6860ecfdfe7e5548e671d0b517c9adf31d 100644
--- a/include/darwin_dyn_slave.h
+++ b/include/darwin_dyn_slave.h
@@ -7,8 +7,10 @@ extern "C" {
 
 #include "stm32f1xx.h"
 #include "dynamixel_slave.h"
+#include "dynamixel_slave_registers.h"
+#include "memory.h"
 
-void darwin_dyn_slave_init(void);
+uint8_t darwin_dyn_slave_init(TMemory *memory);
 void darwin_dyn_slave_start(void);
 void darwin_dyn_slave_stop(void);
 
diff --git a/include/darwin_registers.h b/include/darwin_registers.h
index 59ae35e783a50db52191099b27c1a841efa4ef59..c431cb92c468e9ad855da073dda74233f2d061ec 100644
--- a/include/darwin_registers.h
+++ b/include/darwin_registers.h
@@ -7,17 +7,11 @@
 extern "C" {
 #endif
 
-#define DEVICE_MODEL_OFFSET             ((unsigned short int)0x0000)
-#define FIRMWARE_VERSION_OFFSET         ((unsigned short int)0x0002)
-#define DEVICE_ID_OFFSET                ((unsigned short int)0x0003)
-#define BAUDRATE_OFFSET                 ((unsigned short int)0x0004)
-#define RETURN_DELAY_OFFSET             ((unsigned short int)0x0005)
 #define MM_PERIOD_OFFSET                ((unsigned short int)0x0006)
 #define MM_BAL_KNEE_GAIN_OFFSET         ((unsigned short int)0x0008)
 #define MM_BAL_ANKLE_ROLL_GAIN_OFFSET   ((unsigned short int)0x000A)
 #define MM_BAL_ANKLE_PITCH_GAIN_OFFSET  ((unsigned short int)0x000C)
 #define MM_BAL_HIP_ROLL_GAIN_OFFSET     ((unsigned short int)0x000E)
-#define RETURN_LEVEL_OFFSET             ((unsigned short int)0x0010)
 #define MM_SERVO0_OFFSET                ((unsigned short int)0x0011)
 #define MM_SERVO1_OFFSET                ((unsigned short int)0x0012)
 #define MM_SERVO2_OFFSET                ((unsigned short int)0x0013)
@@ -115,12 +109,6 @@ extern "C" {
 #define LAST_EEPROM_OFFSET              ((unsigned short int)0x00FF)
 
 typedef enum {
-  DARWIN_MODEL_NUMBER_L                = DEVICE_MODEL_OFFSET,
-  DARWIN_MODEL_NUMBER_H                = DEVICE_MODEL_OFFSET+1,
-  DARWIN_VERSION                       = FIRMWARE_VERSION_OFFSET,
-  DARWIN_ID                            = DEVICE_ID_OFFSET,
-  DARWIN_BAUD_RATE                     = BAUDRATE_OFFSET,
-  DARWIN_RETURN_DELAY_TIME             = RETURN_DELAY_OFFSET,
   DARWIN_MM_PERIOD_L                   = MM_PERIOD_OFFSET,
   DARWIN_MM_PERIOD_H                   = MM_PERIOD_OFFSET+1,
   DARWIN_MM_BAL_KNEE_GAIN_L            = MM_BAL_KNEE_GAIN_OFFSET,// fixed point format 0|16
@@ -131,7 +119,6 @@ typedef enum {
   DARWIN_MM_BAL_ANKLE_PITCH_GAIN_H     = MM_BAL_ANKLE_PITCH_GAIN_OFFSET+1,
   DARWIN_MM_BAL_HIP_ROLL_GAIN_L        = MM_BAL_HIP_ROLL_GAIN_OFFSET,// fixed point format 0|16
   DARWIN_MM_BAL_HIP_ROLL_GAIN_H        = MM_BAL_HIP_ROLL_GAIN_OFFSET+1,
-  DARWIN_RETURN_LEVEL                  = RETURN_LEVEL_OFFSET,
   DARWIN_MM_SERVO0_OFFSET              = MM_SERVO0_OFFSET, // angle offset in fixed point format 1-3|4
   DARWIN_MM_SERVO1_OFFSET              = MM_SERVO1_OFFSET, // angle offset in fixed point format 1-3|4
   DARWIN_MM_SERVO2_OFFSET              = MM_SERVO2_OFFSET, // angle offset in fixed point format 1-3|4
diff --git a/src/darwin_dyn_slave.c b/src/darwin_dyn_slave.c
index b287d062003f5a8011ae145d60137559255b6382..eb680dbfe896a92a801e7f72a136ed8a4553b8d0 100755
--- a/src/darwin_dyn_slave.c
+++ b/src/darwin_dyn_slave.c
@@ -2,18 +2,6 @@
 #include "darwin_time.h"
 #include "usart3.h"
 #include "ram.h"
-#include "eeprom.h"
-#include "gpio.h"
-#include "adc_dma.h"
-#include "imu.h"
-#include "motion_manager.h"
-#include "action.h"
-#include "walking.h"
-#include "joint_motion.h"
-#include "head_tracking.h"
-#include "grippers.h"
-#include "smart_charger.h"
-#include "stairs.h"
 
 /* timer for the execution of the dynamixel slave loop */
 #define     DYN_SLAVE_TIMER                   TIM7
@@ -28,80 +16,20 @@ TComm darwin_dyn_slave_comm;
 UART_InitTypeDef darwin_comm_init;
 TIM_HandleTypeDef darwin_dyn_slave_tim_handle;
 
+/* memory module */
+TMemory *darwin_dyn_slave_memory;
+
 // private functions
 unsigned char darwin_on_read(unsigned short int address,unsigned short int length,unsigned char *data)
 {
-  unsigned char error;
- 
-  if(ram_in_window(GPIO_BASE_ADDRESS,GPIO_MEM_LENGTH,address,length))
-    gpio_process_read_cmd(address,length,data);
-  /* dynamixel slave internal operation registers */
-  error=ram_read_table(address,length,data);
-
-  return error;
+  mem_do_read(darwin_dyn_slave_memory,address,length,data);
+
+  return 0x00;
 }
 
 unsigned char darwin_on_write(unsigned short int address,unsigned short int length,unsigned char *data)
 {
-  unsigned short int i,j;
-
-  /* dynamixel slave internal operation registers */
-  if(ram_in_range(DARWIN_ID,address,length))
-  {
-    dyn_slave_set_address(&darwin_dyn_slave,data[DARWIN_ID-address]);
-    ram_data[DARWIN_ID]=data[DARWIN_ID-address];
-  }
-  if(ram_in_range(DARWIN_BAUD_RATE,address,length))
-  {
-    darwin_comm_init.BaudRate=2000000/(data[DARWIN_BAUD_RATE-address]+1);
-    usart3_config(&darwin_dyn_slave_comm,&darwin_comm_init);
-    ram_data[DARWIN_BAUD_RATE]=data[DARWIN_BAUD_RATE-address];
-  }
-  if(ram_in_range(DARWIN_RETURN_DELAY_TIME,address,length))
-  {
-    dyn_slave_set_return_delay(&darwin_dyn_slave,data[DARWIN_RETURN_DELAY_TIME-address]);
-    ram_data[DARWIN_RETURN_DELAY_TIME]=data[DARWIN_RETURN_DELAY_TIME-address];
-  }
-  if(ram_in_range(DARWIN_RETURN_LEVEL,address,length))
-  {
-    dyn_slave_set_return_level(&darwin_dyn_slave,data[DARWIN_RETURN_LEVEL-address]);
-    ram_data[DARWIN_RETURN_LEVEL]=data[DARWIN_RETURN_LEVEL-address];
-  }
-  // GPIO commands
-  if(gpio_in_range(address,length))
-    gpio_process_write_cmd(address,length,data);
-  // ADC commands
-  if(adc_in_range(address,length))
-    adc_process_write_cmd(address,length,data);
-  // IMU commands
-  if(imu_in_range(address,length))
-    imu_process_write_cmd(address,length,data);
-  // Manager commands
-  if(manager_in_range(address,length))
-    manager_process_write_cmd(address,length,data);
-  // action commands
-  if(action_in_range(address,length))
-    action_process_write_cmd(address,length,data);
-  // walk commands
-  if(walking_in_range(address,length))
-    walking_process_write_cmd(address,length,data);
-  // joint motion commands
-  if(joint_motion_in_range(address,length))
-    joint_motion_process_write_cmd(address,length,data);
-  // head_tracking commands
-  if(head_tracking_in_range(address,length))
-    head_tracking_process_write_cmd(address,length,data);
-  // gripper commands
-  if(grippers_in_range(address,length))
-    grippers_process_write_cmd(address,length,data);
-  // smart charger commands
-  if(smart_charger_in_range(address,length))
-    smart_charger_process_write_cmd(address,length,data);
-  if(stairs_in_range(address,length))
-    stairs_process_write_cmd(address,length,data);
-  // write eeprom
-  for(i=address,j=0;i<LAST_EEPROM_OFFSET && i<(address+length);i++,j++)
-    EE_WriteVariable(i,data[j]);
+  mem_do_write(darwin_dyn_slave_memory,address,length,data);
 
   return 0x00;
 }
@@ -124,16 +52,17 @@ void DYN_SLAVE_TIMER_IRQHandler(void)
 }
 
 // public functions
-void darwin_dyn_slave_init(void)
+uint8_t darwin_dyn_slave_init(TMemory *memory)
 {
   TUSART_IRQ_Priorities priorities;
+  uint8_t status;
 
   // initialize timer structure
   time_init(&darwin_dyn_slave_timer,darwin_time_get_counts_per_us(),darwin_time_get_counts);
 
   /* initialize the comm object */
   comm_init(&darwin_dyn_slave_comm,0x01,&darwin_dyn_slave_timer);
-  darwin_comm_init.BaudRate     = 2000000/(ram_data[BAUDRATE_OFFSET]+1);
+  darwin_comm_init.BaudRate     = 2000000/(ram_data[BAUDRATE]+1);
   darwin_comm_init.WordLength   = UART_WORDLENGTH_8B;
   darwin_comm_init.StopBits     = UART_STOPBITS_1;
   darwin_comm_init.Parity       = UART_PARITY_NONE;
@@ -149,12 +78,13 @@ void darwin_dyn_slave_init(void)
   priorities.dma_tx_subpriority=0;
 
   usart3_init(&darwin_dyn_slave_comm,&darwin_comm_init,&priorities);
-  dyn_slave_init(&darwin_dyn_slave,&darwin_dyn_slave_comm,ram_data[DEVICE_ID_OFFSET],DYN_VER2);
+  status=dyn_slave_init(&darwin_dyn_slave,memory,&darwin_dyn_slave_comm,ram_data[DEVICE_ID],DYN_VER2);
+  darwin_dyn_slave_memory=memory;
   darwin_dyn_slave.on_read=darwin_on_read;
   darwin_dyn_slave.on_write=darwin_on_write;
   darwin_dyn_slave.on_ping=darwin_on_ping;
-  dyn_slave_set_return_delay(&darwin_dyn_slave,ram_data[DARWIN_RETURN_DELAY_TIME]);
-  dyn_slave_set_return_level(&darwin_dyn_slave,ram_data[DARWIN_RETURN_LEVEL]);
+  dyn_slave_set_return_delay(&darwin_dyn_slave,ram_data[RETURN_DELAY]);
+  dyn_slave_set_return_level(&darwin_dyn_slave,ram_data[RETURN_LEVEL]);
 
   /* initialize timer for the execution of the dynamixel slave loop */
   DYN_SLAVE_TIMER_ENABLE_CLK;
@@ -168,6 +98,7 @@ void darwin_dyn_slave_init(void)
   HAL_NVIC_SetPriority(DYN_SLAVE_TIMER_IRQn, 2, 2);
   HAL_NVIC_EnableIRQ(DYN_SLAVE_TIMER_IRQn);
 
+  return status;
 }
 
 void darwin_dyn_slave_start(void)
diff --git a/src/eeprom.c b/src/eeprom.c
index fd7d1f016d4c07e2bef8678d444a430c3e54311f..ca45c913d0c898359c8f5dca5611b6f01aacf936 100755
--- a/src/eeprom.c
+++ b/src/eeprom.c
@@ -53,145 +53,7 @@
 uint16_t DataVar = 0;
 
 /* Virtual address defined by the user: 0xFFFF value is prohibited */
-uint16_t eeprom_data[] __attribute__ ((section (".eeprom")))={VALID_PAGE,                                0xFFFF,
-                                                              DEFAULT_DEVICE_MODEL&0xFF,                 DEVICE_MODEL_OFFSET,// model number LSB
-                                                              DEFAULT_DEVICE_MODEL>>8,                   DEVICE_MODEL_OFFSET+1,// model number MSB
-                                                              DEFAULT_FIRMWARE_VERSION,                  FIRMWARE_VERSION_OFFSET,// firmware version
-                                                              DEFAULT_DEVICE_ID,                         DEVICE_ID_OFFSET,// default device id
-                                                              DEFAULT_BAUDRATE,                          BAUDRATE_OFFSET,// default baudrate 
-                                                              DEFAULT_RETURN_DELAY,                      RETURN_DELAY_OFFSET,// return delay time
-                                                              DEFAULT_MM_PERIOD&0xFF,                    MM_PERIOD_OFFSET,
-                                                              DEFAULT_MM_PERIOD>>8,                      MM_PERIOD_OFFSET+1,
-                                                              DEFAULT_BAL_KNEE_GAIN&0xFF,                MM_BAL_KNEE_GAIN_OFFSET,
-                                                              DEFAULT_BAL_KNEE_GAIN>>8,                  MM_BAL_KNEE_GAIN_OFFSET+1,
-                                                              DEFAULT_BAL_ANKLE_ROLL_GAIN&0xFF,          MM_BAL_ANKLE_ROLL_GAIN_OFFSET,
-                                                              DEFAULT_BAL_ANKLE_ROLL_GAIN>>8,            MM_BAL_ANKLE_ROLL_GAIN_OFFSET+1,
-                                                              DEFAULT_BAL_ANKLE_PITCH_GAIN&0xFF,         MM_BAL_ANKLE_PITCH_GAIN_OFFSET,
-                                                              DEFAULT_BAL_ANKLE_PITCH_GAIN>>8,           MM_BAL_ANKLE_PITCH_GAIN_OFFSET+1,
-                                                              DEFAULT_BAL_HIP_ROLL_GAIN&0xFF,            MM_BAL_HIP_ROLL_GAIN_OFFSET,
-                                                              DEFAULT_BAL_HIP_ROLL_GAIN>>8,              MM_BAL_HIP_ROLL_GAIN_OFFSET+1,
-                                                              DEFAULT_RETURN_LEVEL,                      RETURN_LEVEL_OFFSET,// return level
-                                                              DEFAULT_SERVO0_OFFSET,                     MM_SERVO0_OFFSET,
-                                                              DEFAULT_SERVO1_OFFSET,                     MM_SERVO1_OFFSET,
-                                                              DEFAULT_SERVO2_OFFSET,                     MM_SERVO2_OFFSET,
-                                                              DEFAULT_SERVO3_OFFSET,                     MM_SERVO3_OFFSET,
-                                                              DEFAULT_SERVO4_OFFSET,                     MM_SERVO4_OFFSET,
-                                                              DEFAULT_SERVO5_OFFSET,                     MM_SERVO5_OFFSET,
-                                                              DEFAULT_SERVO6_OFFSET,                     MM_SERVO6_OFFSET,
-                                                              DEFAULT_SERVO7_OFFSET,                     MM_SERVO7_OFFSET,
-                                                              DEFAULT_SERVO8_OFFSET,                     MM_SERVO8_OFFSET,
-                                                              DEFAULT_SERVO9_OFFSET,                     MM_SERVO9_OFFSET,
-                                                              DEFAULT_SERVO10_OFFSET,                    MM_SERVO10_OFFSET,
-                                                              DEFAULT_SERVO11_OFFSET,                    MM_SERVO11_OFFSET,
-                                                              DEFAULT_SERVO12_OFFSET,                    MM_SERVO12_OFFSET,
-                                                              DEFAULT_SERVO13_OFFSET,                    MM_SERVO13_OFFSET,
-                                                              DEFAULT_SERVO14_OFFSET,                    MM_SERVO14_OFFSET,
-                                                              DEFAULT_SERVO15_OFFSET,                    MM_SERVO15_OFFSET,
-                                                              DEFAULT_SERVO16_OFFSET,                    MM_SERVO16_OFFSET,
-                                                              DEFAULT_SERVO17_OFFSET,                    MM_SERVO17_OFFSET,
-                                                              DEFAULT_SERVO18_OFFSET,                    MM_SERVO18_OFFSET,
-                                                              DEFAULT_SERVO19_OFFSET,                    MM_SERVO19_OFFSET,
-                                                              DEFAULT_SERVO20_OFFSET,                    MM_SERVO20_OFFSET,
-                                                              DEFAULT_SERVO21_OFFSET,                    MM_SERVO21_OFFSET,
-                                                              DEFAULT_SERVO22_OFFSET,                    MM_SERVO22_OFFSET,
-                                                              DEFAULT_SERVO23_OFFSET,                    MM_SERVO23_OFFSET,
-                                                              DEFAULT_SERVO24_OFFSET,                    MM_SERVO24_OFFSET,
-                                                              DEFAULT_SERVO25_OFFSET,                    MM_SERVO25_OFFSET,
-                                                              DEFAULT_SERVO26_OFFSET,                    MM_SERVO26_OFFSET,
-                                                              DEFAULT_SERVO27_OFFSET,                    MM_SERVO27_OFFSET,
-                                                              DEFAULT_SERVO28_OFFSET,                    MM_SERVO28_OFFSET,
-                                                              DEFAULT_SERVO29_OFFSET,                    MM_SERVO29_OFFSET,
-                                                              DEFAULT_SERVO30_OFFSET,                    MM_SERVO30_OFFSET,
-                                                              DEFAULT_SERVO31_OFFSET,                    MM_SERVO31_OFFSET,
-                                                              DEFAULT_WALK_X_OFFSET,                     WALK_X_OFFSET,
-                                                              DEFAULT_WALK_Y_OFFSET,                     WALK_Y_OFFSET,
-                                                              DEFAULT_WALK_Z_OFFSET,                     WALK_Z_OFFSET,
-                                                              DEFAULT_WALK_ROLL_OFFSET,                  WALK_ROLL_OFFSET,
-                                                              DEFAULT_WALK_PITCH_OFFSET,                 WALK_PITCH_OFFSET,
-                                                              DEFAULT_WALK_YAW_OFFSET,                   WALK_YAW_OFFSET,
-                                                              DEFAULT_WALK_HIP_PITCH_OFF&0xFF,           WALK_HIP_PITCH_OFF,
-                                                              DEFAULT_WALK_HIP_PITCH_OFF>>8,             WALK_HIP_PITCH_OFF+1,
-                                                              DEFAULT_WALK_PERIOD_TIME&0xFF,             WALK_PERIOD_TIME,
-                                                              DEFAULT_WALK_PERIOD_TIME>>8,               WALK_PERIOD_TIME+1,
-                                                              DEFAULT_WALK_DSP_RATIO,                    WALK_DSP_RATIO,
-                                                              DEFAULT_WALK_STEP_FW_BW_RATIO,             WALK_STEP_FW_BW_RATIO,
-                                                              DEFAULT_WALK_FOOT_HEIGHT,                  WALK_FOOT_HEIGHT,
-                                                              DEFAULT_WALK_SWING_RIGHT_LEFT,             WALK_SWING_RIGHT_LEFT,
-                                                              DEFAULT_WALK_SWING_TOP_DOWN,               WALK_SWING_TOP_DOWN,
-                                                              DEFAULT_WALK_PELVIS_OFFSET,                WALK_PELVIS_OFFSET,
-                                                              DEFAULT_WALK_ARM_SWING_GAIN,               WALK_ARM_SWING_GAIN,
-                                                              DEFAULT_WALK_MAX_VEL,                      WALK_MAX_VEL,
-                                                              DEFAULT_WALK_MAX_ROT_VEL,                  WALK_MAX_ROT_VEL,
-                                                              DEFAULT_HEAD_PAN_P&0xFF,                   HEAD_PAN_P,
-                                                              DEFAULT_HEAD_PAN_P>>8,                     HEAD_PAN_P+1,
-                                                              DEFAULT_HEAD_PAN_I&0xFF,                   HEAD_PAN_I,
-                                                              DEFAULT_HEAD_PAN_I>>8,                     HEAD_PAN_I+1,
-                                                              DEFAULT_HEAD_PAN_D&0xFF,                   HEAD_PAN_D,
-                                                              DEFAULT_HEAD_PAN_D>>8,                     HEAD_PAN_D+1,
-                                                              DEFAULT_HEAD_PAN_I_CLAMP&0xFF,             HEAD_PAN_I_CLAMP,
-                                                              DEFAULT_HEAD_PAN_I_CLAMP>>8,               HEAD_PAN_I_CLAMP+1,
-                                                              DEFAULT_HEAD_PAN_D>>8,                     HEAD_PAN_D+1,
-                                                              DEFAULT_HEAD_TILT_P&0xFF,                  HEAD_TILT_P,
-                                                              DEFAULT_HEAD_TILT_P>>8,                    HEAD_TILT_P+1,
-                                                              DEFAULT_HEAD_TILT_I&0xFF,                  HEAD_TILT_I,
-                                                              DEFAULT_HEAD_TILT_I>>8,                    HEAD_TILT_I+1,
-                                                              DEFAULT_HEAD_TILT_D&0xFF,                  HEAD_TILT_D,
-                                                              DEFAULT_HEAD_TILT_D>>8,                    HEAD_TILT_D+1,
-                                                              DEFAULT_HEAD_TILT_I_CLAMP&0xFF,            HEAD_TILT_I_CLAMP,
-                                                              DEFAULT_HEAD_TILT_I_CLAMP>>8,              HEAD_TILT_I_CLAMP+1,
-                                                              DEFAULT_GRIPPER_LEFT_TOP_ID,               GRIPPER_LEFT_TOP_ID,
-                                                              DEFAULT_GRIPPER_LEFT_BOT_ID,               GRIPPER_LEFT_BOT_ID,
-                                                              DEFAULT_GRIPPER_LEFT_MAX_ANGLE&0xFF,       GRIPPER_LEFT_MAX_ANGLE,
-                                                              DEFAULT_GRIPPER_LEFT_MAX_ANGLE>>8,         GRIPPER_LEFT_MAX_ANGLE+1,
-                                                              DEFAULT_GRIPPER_LEFT_MIN_ANGLE&0xFF,       GRIPPER_LEFT_MIN_ANGLE,
-                                                              DEFAULT_GRIPPER_LEFT_MIN_ANGLE>>8,         GRIPPER_LEFT_MIN_ANGLE+1,
-                                                              DEFAULT_GRIPPER_LEFT_MAX_FORCE&0xFF,       GRIPPER_LEFT_MAX_FORCE,
-                                                              DEFAULT_GRIPPER_LEFT_MAX_FORCE>>8,         GRIPPER_LEFT_MAX_FORCE+1,
-                                                              DEFAULT_GRIPPER_RIGHT_TOP_ID,              GRIPPER_RIGHT_TOP_ID,
-                                                              DEFAULT_GRIPPER_RIGHT_BOT_ID,              GRIPPER_RIGHT_BOT_ID,
-                                                              DEFAULT_GRIPPER_RIGHT_MAX_ANGLE&0xFF,      GRIPPER_RIGHT_MAX_ANGLE,
-                                                              DEFAULT_GRIPPER_RIGHT_MAX_ANGLE>>8,        GRIPPER_RIGHT_MAX_ANGLE+1,
-                                                              DEFAULT_GRIPPER_RIGHT_MIN_ANGLE&0xFF,      GRIPPER_RIGHT_MIN_ANGLE,
-                                                              DEFAULT_GRIPPER_RIGHT_MIN_ANGLE>>8,        GRIPPER_RIGHT_MIN_ANGLE+1,
-                                                              DEFAULT_GRIPPER_RIGHT_MAX_FORCE&0xFF,      GRIPPER_RIGHT_MAX_FORCE,
-                                                              DEFAULT_GRIPPER_RIGHT_MAX_FORCE>>8,        GRIPPER_RIGHT_MAX_FORCE+1, 
-                                                              DEFAULT_SMART_CHARGER_PERIOD&0xFF,         SMART_CHARGER_PERIOD,
-                                                              DEFAULT_SMART_CHARGER_PERIOD>>8,           SMART_CHARGER_PERIOD+1,
-                                                              DEFAULT_STAIRS_PHASE1_TIME&0xFF,           STAIRS_PHASE1_TIME,
-                                                              DEFAULT_STAIRS_PHASE1_TIME>>8,             STAIRS_PHASE1_TIME+1,
-                                                              DEFAULT_STAIRS_PHASE2_TIME&0xFF,           STAIRS_PHASE2_TIME,
-                                                              DEFAULT_STAIRS_PHASE2_TIME>>8,             STAIRS_PHASE2_TIME+1,
-                                                              DEFAULT_STAIRS_PHASE3_TIME&0xFF,           STAIRS_PHASE3_TIME,
-                                                              DEFAULT_STAIRS_PHASE3_TIME>>8,             STAIRS_PHASE3_TIME+1,
-                                                              DEFAULT_STAIRS_PHASE4_TIME&0xFF,           STAIRS_PHASE4_TIME,
-                                                              DEFAULT_STAIRS_PHASE4_TIME>>8,             STAIRS_PHASE4_TIME+1,
-                                                              DEFAULT_STAIRS_PHASE5_TIME&0xFF,           STAIRS_PHASE5_TIME,
-                                                              DEFAULT_STAIRS_PHASE5_TIME>>8,             STAIRS_PHASE5_TIME+1,
-                                                              DEFAULT_STAIRS_PHASE6_TIME&0xFF,           STAIRS_PHASE6_TIME,
-                                                              DEFAULT_STAIRS_PHASE6_TIME>>8,             STAIRS_PHASE6_TIME+1,
-                                                              DEFAULT_STAIRS_PHASE7_TIME&0xFF,           STAIRS_PHASE7_TIME,
-                                                              DEFAULT_STAIRS_PHASE7_TIME>>8,             STAIRS_PHASE7_TIME+1,
-                                                              DEFAULT_STAIRS_PHASE8_TIME&0xFF,           STAIRS_PHASE8_TIME,
-                                                              DEFAULT_STAIRS_PHASE8_TIME>>8,             STAIRS_PHASE8_TIME+1,
-                                                              DEFAULT_STAIRS_PHASE9_TIME&0xFF,           STAIRS_PHASE9_TIME,
-                                                              DEFAULT_STAIRS_PHASE9_TIME>>8,             STAIRS_PHASE9_TIME+1,
-                                                              DEFAULT_STAIRS_X_OFFSET,                   STAIRS_X_OFFSET,
-                                                              DEFAULT_STAIRS_Y_OFFSET,                   STAIRS_Y_OFFSET,
-                                                              DEFAULT_STAIRS_Z_OFFSET,                   STAIRS_Z_OFFSET,
-                                                              DEFAULT_STAIRS_R_OFFSET,                   STAIRS_R_OFFSET,
-                                                              DEFAULT_STAIRS_P_OFFSET,                   STAIRS_P_OFFSET,
-                                                              DEFAULT_STAIRS_A_OFFSET,                   STAIRS_A_OFFSET,
-                                                              DEFAULT_STAIRS_Y_SHIFT,                    STAIRS_Y_SHIFT,
-                                                              DEFAULT_STAIRS_X_SHIFT,                    STAIRS_X_SHIFT,
-                                                              DEFAULT_STAIRS_Z_OVERSHOOT,                STAIRS_Z_OVERSHOOT, 
-                                                              DEFAULT_STAIRS_Z_HEIGHT,                   STAIRS_Z_HEIGHT,
-                                                              DEFAULT_STAIRS_HIP_PITCH_OFF&0xFF,         STAIRS_HIP_PITCH_OFF,
-                                                              DEFAULT_STAIRS_HIP_PITCH_OFF>>8,           STAIRS_HIP_PITCH_OFF+1,
-                                                              DEFAULT_STAIRS_R_SHIFT,                    STAIRS_R_SHIFT,
-                                                              DEFAULT_STAIRS_P_SHIFT,                    STAIRS_P_SHIFT,
-                                                              DEFAULT_STAIRS_A_SHIFT,                    STAIRS_A_SHIFT,
-                                                              DEFAULT_STAIRS_Y_SPREAD,                   STAIRS_Y_SPREAD,
-                                                              DEFAULT_STAIRS_X_SHIFT_BODY,               STAIRS_X_SHIFT_BODY};
+uint16_t eeprom_data[] __attribute__ ((section (".eeprom")))={VALID_PAGE,                                0xFFFF};
 
 /* Private function prototypes -----------------------------------------------*/
 /* Private functions ---------------------------------------------------------*/