Program for RoboCup 2016 Leipzig

Dependencies:   mbed AQM1602 HMC6352 PID

Files at this revision

API Documentation at this revision

Comitter:
lilac0112_1
Date:
Tue Jun 14 07:22:22 2016 +0000
Commit message:
Code of Japan open.

Changed in this revision

lib/AQM1602.lib Show annotated file Show diff for this revision Revisions of this file
lib/HMC6352.lib Show annotated file Show diff for this revision Revisions of this file
lib/PID.lib Show annotated file Show diff for this revision Revisions of this file
lib/adns_9800/adns_9800.cpp Show annotated file Show diff for this revision Revisions of this file
lib/adns_9800/adns_9800.h Show annotated file Show diff for this revision Revisions of this file
lib/adns_9800/adns_9800_regs.h Show annotated file Show diff for this revision Revisions of this file
lib/adns_9800/adns_9800_srom_a4.h Show annotated file Show diff for this revision Revisions of this file
main.cpp Show annotated file Show diff for this revision Revisions of this file
main_processing/setup_command_active/active.cpp Show annotated file Show diff for this revision Revisions of this file
main_processing/setup_command_active/active.h Show annotated file Show diff for this revision Revisions of this file
main_processing/setup_command_active/command.cpp Show annotated file Show diff for this revision Revisions of this file
main_processing/setup_command_active/command.h Show annotated file Show diff for this revision Revisions of this file
main_processing/setup_command_active/command_functions.cpp Show annotated file Show diff for this revision Revisions of this file
main_processing/setup_command_active/command_functions.h Show annotated file Show diff for this revision Revisions of this file
main_processing/setup_command_active/setup.cpp Show annotated file Show diff for this revision Revisions of this file
main_processing/setup_command_active/setup.h Show annotated file Show diff for this revision Revisions of this file
main_processing/strategy/LineProcess.cpp Show annotated file Show diff for this revision Revisions of this file
main_processing/strategy/LineProcess.h Show annotated file Show diff for this revision Revisions of this file
main_processing/strategy/old_strategy.cpp Show annotated file Show diff for this revision Revisions of this file
main_processing/strategy/old_strategy.h Show annotated file Show diff for this revision Revisions of this file
main_processing/strategy/strategy.cpp Show annotated file Show diff for this revision Revisions of this file
main_processing/strategy/strategy.h Show annotated file Show diff for this revision Revisions of this file
main_processing/strategy/strategy2.cpp Show annotated file Show diff for this revision Revisions of this file
main_processing/strategy/strategy2.h Show annotated file Show diff for this revision Revisions of this file
main_processing/strategy_parts/input.cpp Show annotated file Show diff for this revision Revisions of this file
main_processing/strategy_parts/input.h Show annotated file Show diff for this revision Revisions of this file
main_processing/strategy_parts/output.cpp Show annotated file Show diff for this revision Revisions of this file
main_processing/strategy_parts/output.h Show annotated file Show diff for this revision Revisions of this file
mbed.bld Show annotated file Show diff for this revision Revisions of this file
minilib/MathTable.h Show annotated file Show diff for this revision Revisions of this file
minilib/switch.cpp Show annotated file Show diff for this revision Revisions of this file
minilib/switch.h Show annotated file Show diff for this revision Revisions of this file
minilib/txrx.cpp Show annotated file Show diff for this revision Revisions of this file
minilib/txrx.h Show annotated file Show diff for this revision Revisions of this file
minilib/wordString2.cpp Show annotated file Show diff for this revision Revisions of this file
minilib/wordString2.h Show annotated file Show diff for this revision Revisions of this file
setting/ActiveConfig.h Show annotated file Show diff for this revision Revisions of this file
setting/CommandConfig.h Show annotated file Show diff for this revision Revisions of this file
setting/IrConfig.h Show annotated file Show diff for this revision Revisions of this file
setting/LineConfig.h Show annotated file Show diff for this revision Revisions of this file
setting/PinConfig.h Show annotated file Show diff for this revision Revisions of this file
setting/def.h Show annotated file Show diff for this revision Revisions of this file
setting/extern.h Show annotated file Show diff for this revision Revisions of this file
setting/main.h Show annotated file Show diff for this revision Revisions of this file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/lib/AQM1602.lib	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,1 @@
+http://developer.mbed.org/users/yasuyuki/code/AQM1602/#4c3df2da124c
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/lib/HMC6352.lib	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,1 @@
+http://mbed.org/users/aberk/code/HMC6352/#83c0cb554099
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/lib/PID.lib	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,1 @@
+http://mbed.org/users/aberk/code/PID/#6e12a3e5af19
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/lib/adns_9800/adns_9800.cpp	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,158 @@
+/**
+ * @author Alexander Entinger, MSc / LXRobotics
+ * @brief this class acts as interface for accessing the adns-9800 sensor - based on https://github.com/mrjohnk/ADNS-9800
+ * @file adns_9800.cpp
+ */
+ 
+#include "adns_9800.h"
+#include "adns_9800_regs.h"
+#include "adns_9800_srom_a4.h"
+ 
+/**
+ * @brief Constructor
+ */
+adns_9800::adns_9800(PinName mosi, PinName miso, PinName sclk, PinName ncs) : m_spi(mosi, miso, sclk), m_ncs_pin(ncs)
+{
+    m_spi.format(8, 3); // 8 bits with mode 3 =>Polarity = 1, Phase = 1
+    m_spi.frequency(1000000); // 1 MHz
+    
+    startup();
+}
+    
+/**
+ * @brief Destructor
+ */
+adns_9800::~adns_9800()
+{
+    
+}
+
+/**
+ * @brief returns true if a motion has occured since the last readout
+ */
+bool adns_9800::new_motion_data_available()
+{
+    uint8_t const motion_reg = read_reg(REG_Motion);
+    bool const new_data_available = (motion_reg & 0x80) > 0;
+    return new_data_available;
+}
+    
+/**
+ * @brief retrieves the latest delta values
+ */
+void adns_9800::get_delta_x_y(int16_t &delta_x, int16_t &delta_y)
+{
+    uint16_t delta_x_l = (uint16_t)(read_reg(REG_Delta_X_L));
+    uint16_t delta_x_h = (uint16_t)(read_reg(REG_Delta_X_H)) << 8;
+    delta_x = (int16_t)(delta_x_h | delta_x_l);
+    
+    uint16_t delta_y_l = (uint16_t)(read_reg(REG_Delta_Y_L));
+    uint16_t delta_y_h = (uint16_t)(read_reg(REG_Delta_Y_H)) << 8;
+    delta_y = (int16_t)(delta_y_h | delta_y_l);
+}
+
+/**
+ * @brief start and stop communication with the sensor by clearing/setting the ncs pin
+ */
+void adns_9800::com_begin()
+{
+    m_ncs_pin = 0;
+}
+void adns_9800::com_end()
+{
+    m_ncs_pin = 1;
+}
+
+/**
+ * @brief provide read/write access to a adns register
+ */
+uint8_t adns_9800::read_reg(uint8_t const address)
+{
+  com_begin();
+  
+  // send adress of the register, with MSBit = 0 to indicate it's a read
+  m_spi.write(address & 0x7f );
+  wait_us(100); // tSRAD
+  // read data
+  uint8_t data = m_spi.write(0);
+  
+  wait_us(1); // tSCLK-NCS for read operation is 120ns
+  com_end();
+  wait_us(19); //  tSRW/tSRR (=20us) minus tSCLK-NCS
+
+  return data; 
+}
+void adns_9800::write_reg(uint8_t const address, uint8_t const data)
+{
+  com_begin();
+  
+  //send adress of the register, with MSBit = 1 to indicate it's a write
+  m_spi.write(address | 0x80 );
+  //sent data
+  m_spi.write(data);
+  
+  wait_us(20); // tSCLK-NCS for write operation
+  com_end();
+  wait_us(100); // tSWW/tSWR (=120us) minus tSCLK-NCS. Could be shortened, but is looks like a safe lower bound 
+}
+
+/**
+ * @brief upload the firmware
+ */
+void adns_9800::upload_firmware()
+{
+  // set the configuration_IV register in 3k firmware mode
+  write_reg(REG_Configuration_IV, 0x02); // bit 1 = 1 for 3k mode, other bits are reserved 
+  
+  // write 0x1d in SROM_enable reg for initializing
+  write_reg(REG_SROM_Enable, 0x1d); 
+  
+  // wait for more than one frame period
+  wait_ms(10); // assume that the frame rate is as low as 100fps... even if it should never be that low
+  
+  // write 0x18 to SROM_enable to start SROM download
+  write_reg(REG_SROM_Enable, 0x18); 
+  
+  // write the SROM file (=firmware data) 
+  com_begin();
+  m_spi.write(REG_SROM_Load_Burst | 0x80); // write burst destination adress
+  wait_us(15);
+  
+  // send all bytes of the firmware
+  for(int i = 0; i < firmware_length; i++)
+  { 
+    m_spi.write(firmware_data[i]);
+    wait_us(15);
+  }
+  
+  com_end(); 
+}
+
+/**
+ * @brief starts the sensor up
+ */
+void adns_9800::startup()
+{
+  com_end(); // ensure that the serial port is reset
+  com_begin(); // ensure that the serial port is reset
+  com_end(); // ensure that the serial port is reset
+  write_reg(REG_Power_Up_Reset, 0x5a); // force reset
+  wait_ms(50); // wait for it to reboot
+  // read registers 0x02 to 0x06 (and discard the data)
+  read_reg(REG_Motion);
+  read_reg(REG_Delta_X_L);
+  read_reg(REG_Delta_X_H);
+  read_reg(REG_Delta_Y_L);
+  read_reg(REG_Delta_Y_H);
+  // upload the firmware
+  upload_firmware();
+  wait_ms(10);
+  //enable laser(bit 0 = 0b), in normal mode (bits 3,2,1 = 000b)
+  // reading the actual value of the register is important because the real
+  // default value is different from what is said in the datasheet, and if you
+  // change the reserved bytes (like by writing 0x00...) it would not work.
+  uint8_t laser_ctrl0 = read_reg(REG_LASER_CTRL0);
+  write_reg(REG_LASER_CTRL0, laser_ctrl0 & 0xf0 );
+  
+  wait_ms(1);
+}
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/lib/adns_9800/adns_9800.h	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,59 @@
+/**
+ * @author Alexander Entinger, MSc / LXRobotics
+ * @brief this class acts as interface for accessing the adns-9800 sensor - based on https://github.com/mrjohnk/ADNS-9800
+ * @file adns_9800.h
+ */
+ 
+#ifndef ADNS_9800_H_
+#define ADNS_9800_H_
+
+#include "mbed.h"
+
+class adns_9800
+{
+public:
+    /**
+     * @brief Constructor
+     */
+    adns_9800(PinName mosi, PinName miso, PinName sclk, PinName ncs);
+    
+    /**
+     * @brief Destructor
+     */
+    ~adns_9800();
+
+    /**
+     * @brief returns true if a motion has occured since the last readout
+     */
+    bool new_motion_data_available();
+    
+    /**
+     * @brief retrieves the latest delta values
+     */
+    void get_delta_x_y(int16_t &delta_x, int16_t &delta_y);
+        
+private:
+    SPI m_spi;
+    DigitalOut m_ncs_pin;
+    
+    /**
+     * @brief start and stop communication with the sensor by clearing/setting the ncs pin
+     */
+    void com_begin();
+    void com_end();
+    /**
+     * @brief provide read/write access to a adns register
+     */
+    uint8_t read_reg(uint8_t const address);
+    void write_reg(uint8_t const address, uint8_t const data);
+    /**
+     * @brief upload the firmware
+     */
+    void upload_firmware();
+    /**
+     * @brief starts the sensor up
+     */
+    void startup();
+};
+
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/lib/adns_9800/adns_9800_regs.h	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,56 @@
+/**
+ * @author Alexander Entinger, MSc / LXRobotics
+ * @brief this file contains the register defintions for the adns-9800 sensor - based on https://github.com/mrjohnk/ADNS-9800
+ * @file adns_9800_regs.h
+ */
+ 
+#ifndef ADNS_9800_REGS_H_
+#define ADNS_9800_REGS_H_
+
+#define REG_Product_ID                           0x00
+#define REG_Revision_ID                          0x01
+#define REG_Motion                               0x02
+#define REG_Delta_X_L                            0x03
+#define REG_Delta_X_H                            0x04
+#define REG_Delta_Y_L                            0x05
+#define REG_Delta_Y_H                            0x06
+#define REG_SQUAL                                0x07
+#define REG_Pixel_Sum                            0x08
+#define REG_Maximum_Pixel                        0x09
+#define REG_Minimum_Pixel                        0x0a
+#define REG_Shutter_Lower                        0x0b
+#define REG_Shutter_Upper                        0x0c
+#define REG_Frame_Period_Lower                   0x0d
+#define REG_Frame_Period_Upper                   0x0e
+#define REG_Configuration_I                      0x0f
+#define REG_Configuration_II                     0x10
+#define REG_Frame_Capture                        0x12
+#define REG_SROM_Enable                          0x13
+#define REG_Run_Downshift                        0x14
+#define REG_Rest1_Rate                           0x15
+#define REG_Rest1_Downshift                      0x16
+#define REG_Rest2_Rate                           0x17
+#define REG_Rest2_Downshift                      0x18
+#define REG_Rest3_Rate                           0x19
+#define REG_Frame_Period_Max_Bound_Lower         0x1a
+#define REG_Frame_Period_Max_Bound_Upper         0x1b
+#define REG_Frame_Period_Min_Bound_Lower         0x1c
+#define REG_Frame_Period_Min_Bound_Upper         0x1d
+#define REG_Shutter_Max_Bound_Lower              0x1e
+#define REG_Shutter_Max_Bound_Upper              0x1f
+#define REG_LASER_CTRL0                          0x20
+#define REG_Observation                          0x24
+#define REG_Data_Out_Lower                       0x25
+#define REG_Data_Out_Upper                       0x26
+#define REG_SROM_ID                              0x2a
+#define REG_Lift_Detection_Thr                   0x2e
+#define REG_Configuration_V                      0x2f
+#define REG_Configuration_IV                     0x39
+#define REG_Power_Up_Reset                       0x3a
+#define REG_Shutdown                             0x3b
+#define REG_Inverse_Product_ID                   0x3f
+#define REG_Motion_Burst                         0x50
+#define REG_SROM_Load_Burst                      0x62
+#define REG_Pixel_Burst                          0x64
+
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/lib/adns_9800/adns_9800_srom_a4.h	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,219 @@
+/**
+ * @author Alexander Entinger, MSc / LXRobotics
+ * @brief this file contains the firmware for the mouse sensor - based on https://github.com/mrjohnk/ADNS-9800
+ * @file adns_9800_srom_a4.h
+ */
+
+#ifndef ADNS_9800_SROM_A4_H_
+#define ADNS_9800_SROM_A4_H_
+
+static uint16_t const firmware_length = 3070;
+
+static uint8_t firmware_data[firmware_length] = {
+0x03, 0xa4, 0x6e, 0x16, 0x6d, 0x89, 0x3e, 0xfe, 0x5f, 0x1c, 0xb8, 0xf2, 0x47, 0x0c, 0x7b, 
+0x74, 0x6a, 0x56, 0x0f, 0x7d, 0x76, 0x71, 0x4b, 0x0c, 0x97, 0xb6, 0xcf, 0xfd, 0x78, 0x72, 
+0x66, 0x2f, 0xbd, 0xf8, 0x53, 0x24, 0xab, 0xd4, 0x2c, 0xb0, 0xe4, 0x32, 0xf1, 0x6a, 0x56, 
+0x2e, 0xbf, 0xfc, 0x7a, 0x57, 0x0d, 0x79, 0x70, 0x66, 0x46, 0x0e, 0x7f, 0x5d, 0x19, 0x91, 
+0xaa, 0xc2, 0x0d, 0x8e, 0x7f, 0x5d, 0x19, 0xb0, 0xe2, 0x46, 0xef, 0x5c, 0x3a, 0xd7, 0x2c, 
+0xbb, 0xf4, 0x6a, 0x37, 0xcd, 0x18, 0xb2, 0xc7, 0x0c, 0x9a, 0x97, 0x8f, 0x52, 0xfd, 0x0d, 
+0xb8, 0x41, 0x00, 0x9e, 0x8e, 0x9a, 0x1e, 0x6d, 0x0c, 0xe2, 0xaa, 0x13, 0x93, 0xb8, 0xc1, 
+0x2a, 0x29, 0xbb, 0x0b, 0xe3, 0x71, 0x08, 0x6d, 0xfd, 0xb6, 0xd9, 0xcf, 0x65, 0x21, 0x27, 
+0x45, 0x1b, 0xbe, 0xe2, 0x61, 0x86, 0x3c, 0xbf, 0x68, 0x9c, 0xd6, 0x75, 0x01, 0x5e, 0xe0, 
+0xc6, 0x92, 0x79, 0xf4, 0x6a, 0xa9, 0xbb, 0x2a, 0x79, 0xd0, 0xe1, 0x5c, 0x32, 0xb1, 0x5a, 
+0x1b, 0xba, 0xaf, 0x11, 0xea, 0x24, 0x6a, 0x83, 0x4f, 0x8d, 0xed, 0x19, 0x62, 0x70, 0x54, 
+0xfb, 0x0e, 0x1f, 0x83, 0xcc, 0xf0, 0xb7, 0xae, 0x05, 0xd3, 0x42, 0x5d, 0x48, 0xa0, 0x7a, 
+0x0b, 0x73, 0xb3, 0xc8, 0xa6, 0xb7, 0x1b, 0x08, 0x13, 0x9b, 0x89, 0x44, 0x42, 0xae, 0xd8, 
+0x6a, 0xba, 0x9b, 0x84, 0x25, 0x8b, 0xa4, 0x5e, 0x0b, 0x85, 0xb0, 0x8f, 0x8d, 0x80, 0x9c, 
+0xd1, 0x52, 0xc7, 0xcb, 0xff, 0x8d, 0x8b, 0xdd, 0x87, 0xf2, 0x63, 0xca, 0xe7, 0x4f, 0x4a, 
+0x57, 0x3c, 0xdf, 0xaf, 0xcb, 0x5c, 0xbb, 0x39, 0x0b, 0x01, 0x9c, 0x79, 0x22, 0x15, 0xb8, 
+0xa0, 0xd3, 0x72, 0x02, 0x35, 0x20, 0x40, 0xe0, 0x17, 0xde, 0x89, 0x88, 0xce, 0xe9, 0x2b, 
+0x75, 0xba, 0xa0, 0x96, 0x24, 0x1e, 0x71, 0xb5, 0x15, 0x00, 0x61, 0xe0, 0x5c, 0x93, 0x4e, 
+0xea, 0x53, 0xd0, 0xfc, 0xef, 0xae, 0x2b, 0xeb, 0x8f, 0xc7, 0x69, 0x68, 0xc7, 0xfc, 0x1a, 
+0x1f, 0x41, 0x0d, 0xd0, 0xc1, 0x03, 0xaf, 0xc9, 0xfd, 0xe4, 0x21, 0x43, 0xc4, 0xef, 0xc2, 
+0xdd, 0x7b, 0x73, 0xbc, 0xca, 0xf4, 0xa5, 0x2e, 0x83, 0x90, 0x1f, 0x78, 0x41, 0xc3, 0x13, 
+0x8e, 0x95, 0x0a, 0x57, 0xdf, 0x0a, 0x87, 0x40, 0x2b, 0xd9, 0xba, 0x56, 0x59, 0x9d, 0x2c, 
+0xb2, 0xb8, 0xb3, 0xfb, 0x77, 0x78, 0x3a, 0xef, 0xbf, 0x2d, 0xc8, 0xb9, 0x94, 0x62, 0x47, 
+0x92, 0x98, 0x42, 0x23, 0x07, 0xd9, 0x39, 0x46, 0x5e, 0x6f, 0xe0, 0x46, 0x14, 0x0e, 0x3d, 
+0x74, 0x40, 0x21, 0xb4, 0x67, 0x05, 0xa8, 0xe2, 0x12, 0x93, 0x41, 0xc2, 0x80, 0xb9, 0x56, 
+0x4b, 0xf9, 0x5a, 0x15, 0x9c, 0x37, 0xc4, 0x4b, 0x05, 0xad, 0x5a, 0xaf, 0xa1, 0x3e, 0xe4, 
+0x6e, 0xc5, 0x91, 0xb6, 0x75, 0x7d, 0x1b, 0xe4, 0xc5, 0x4d, 0x28, 0x6b, 0xe9, 0xad, 0x20, 
+0x8b, 0x64, 0x91, 0x57, 0x4f, 0xdf, 0x9a, 0x97, 0x7e, 0xbe, 0x8e, 0xd6, 0xd6, 0x3b, 0x17, 
+0xf9, 0x19, 0x28, 0xb2, 0x2e, 0x8f, 0x26, 0xb4, 0x9b, 0xe5, 0xde, 0x0f, 0x8d, 0x0a, 0x9a, 
+0x9d, 0x1b, 0xde, 0x6f, 0xcb, 0x84, 0xba, 0x26, 0xd0, 0x12, 0xef, 0x30, 0x38, 0x43, 0xac, 
+0xb7, 0xa7, 0xef, 0x09, 0x7c, 0x52, 0x27, 0xfc, 0x2e, 0xab, 0x50, 0xa0, 0x21, 0x40, 0xe7, 
+0xc1, 0x5f, 0x02, 0x41, 0x84, 0xa8, 0x54, 0xa8, 0x2e, 0x37, 0x6f, 0xd8, 0xb1, 0xa4, 0xd0, 
+0x75, 0xef, 0x31, 0xca, 0x54, 0x1e, 0x33, 0xad, 0x19, 0xa1, 0x94, 0xbc, 0x1b, 0x34, 0x6c, 
+0xfb, 0x5f, 0xcc, 0x45, 0x76, 0xc8, 0x96, 0xce, 0x1c, 0x3a, 0x0e, 0x77, 0xed, 0xd8, 0xd2, 
+0x96, 0xac, 0x77, 0x30, 0xe1, 0xef, 0xb0, 0x33, 0xf0, 0x6e, 0x3d, 0xce, 0x5e, 0x6d, 0xde, 
+0x8a, 0xdc, 0x9b, 0x91, 0x63, 0x2a, 0x95, 0x20, 0x0d, 0xfd, 0x78, 0xba, 0xcb, 0x15, 0x43, 
+0xc9, 0x20, 0x96, 0x83, 0x06, 0xd9, 0x11, 0xf3, 0xe2, 0x13, 0xcf, 0x9c, 0x91, 0x7f, 0x33, 
+0x46, 0xa7, 0xe2, 0xd3, 0x75, 0xff, 0x4f, 0x0c, 0x0c, 0xaf, 0xcd, 0xa6, 0x9c, 0xa6, 0x73, 
+0xe2, 0x6d, 0x17, 0x16, 0xb5, 0x99, 0x80, 0x35, 0xd9, 0x61, 0xf3, 0x48, 0x23, 0xff, 0xae, 
+0x53, 0x89, 0xfa, 0x55, 0x1c, 0x37, 0xa5, 0xe8, 0x62, 0x12, 0xb2, 0x22, 0x04, 0xed, 0x42, 
+0xb6, 0x65, 0xc4, 0x41, 0x42, 0x72, 0xca, 0x7e, 0x5e, 0x2f, 0x69, 0x46, 0xef, 0xbd, 0x7e, 
+0xdf, 0x35, 0x1e, 0x5b, 0x77, 0xaf, 0x8d, 0x39, 0xf8, 0xa7, 0xd8, 0x31, 0x00, 0xd3, 0x85, 
+0x66, 0xd5, 0xcd, 0x59, 0xd6, 0x5e, 0x9f, 0xb2, 0x3f, 0x09, 0xd1, 0xc4, 0x5b, 0x74, 0x62, 
+0xd3, 0x30, 0x35, 0xf3, 0xe3, 0x7d, 0x7f, 0xab, 0x38, 0xc2, 0x33, 0x42, 0xd0, 0x67, 0xd0, 
+0xf4, 0xcf, 0x97, 0xec, 0x35, 0x31, 0xfe, 0x94, 0x9c, 0xa1, 0x66, 0x91, 0xc8, 0x05, 0x45, 
+0x19, 0x85, 0x0f, 0x4a, 0xb0, 0x3a, 0x20, 0x44, 0xa4, 0x6b, 0x33, 0x0c, 0xa6, 0xb4, 0x4c, 
+0x46, 0x30, 0x15, 0x2d, 0xbb, 0x04, 0x3c, 0x9d, 0x48, 0xf6, 0x84, 0x9a, 0x62, 0x07, 0xe9, 
+0x6c, 0x8f, 0xde, 0x29, 0x28, 0x5a, 0x17, 0xec, 0x56, 0xf3, 0xc4, 0xe0, 0x86, 0x2f, 0xb5, 
+0x1c, 0x8f, 0xaa, 0xc6, 0xc0, 0xcf, 0x0d, 0xcf, 0x1d, 0x4f, 0xb2, 0xbf, 0x26, 0x5c, 0x7c, 
+0x8d, 0xd3, 0xe4, 0x56, 0xd1, 0xe8, 0x90, 0x94, 0x6a, 0xba, 0x27, 0xba, 0xf7, 0xba, 0x39, 
+0xc8, 0x08, 0x03, 0x25, 0x7f, 0x16, 0x8f, 0x61, 0xbf, 0xdf, 0x45, 0x88, 0x7d, 0x90, 0x80, 
+0x55, 0x58, 0x72, 0x4f, 0xf8, 0xd0, 0x94, 0xbb, 0x55, 0x2a, 0x47, 0x4f, 0xaa, 0x87, 0x2d, 
+0xd4, 0xe7, 0xaf, 0x08, 0x33, 0xc9, 0xec, 0x0b, 0x5b, 0xb8, 0x53, 0x27, 0x2e, 0xfb, 0xad, 
+0x69, 0xb6, 0x53, 0x64, 0x48, 0x13, 0x41, 0xf8, 0x02, 0x06, 0x6f, 0xb8, 0xcc, 0x64, 0xec, 
+0x65, 0x65, 0x7e, 0xdf, 0x3f, 0x1e, 0xe1, 0xee, 0xde, 0x3c, 0x1a, 0xe8, 0x0f, 0xf0, 0x2c, 
+0xea, 0x6e, 0x52, 0x77, 0x34, 0x41, 0xa1, 0xcc, 0x72, 0x8f, 0x6e, 0x9c, 0x3b, 0x8d, 0x39, 
+0xdf, 0xd4, 0x08, 0x24, 0xba, 0x36, 0xc7, 0x09, 0xf2, 0xf1, 0xa2, 0xd1, 0xe0, 0xa3, 0x6a, 
+0x5c, 0xc7, 0xb2, 0x0d, 0x1c, 0xfb, 0x5f, 0xc8, 0x86, 0xd8, 0x3e, 0x1c, 0xb7, 0x1f, 0x2d, 
+0xd8, 0xf2, 0xcd, 0x52, 0xeb, 0xde, 0x50, 0x14, 0xb7, 0xc7, 0xa2, 0x8b, 0x78, 0x70, 0x11, 
+0x87, 0x1a, 0xc5, 0xb8, 0xe5, 0x5e, 0xa5, 0xc9, 0x94, 0x22, 0x66, 0x7b, 0x8b, 0x74, 0xab, 
+0x85, 0x28, 0x95, 0x90, 0x6e, 0x07, 0xdd, 0x79, 0x57, 0xb3, 0x75, 0xc8, 0x18, 0x67, 0x39, 
+0x06, 0x21, 0x55, 0xba, 0xba, 0xda, 0xf9, 0x3b, 0xe9, 0x5d, 0xc9, 0x1f, 0x6f, 0x61, 0x3b, 
+0xc2, 0x7e, 0x3d, 0x07, 0xa6, 0x84, 0x91, 0xb7, 0x63, 0x7e, 0x5f, 0xfc, 0xd1, 0x7d, 0x08, 
+0xdd, 0x79, 0x07, 0xe1, 0x9e, 0x11, 0x25, 0xe8, 0x10, 0x05, 0x66, 0xfa, 0xca, 0xc3, 0x41, 
+0x01, 0x27, 0x54, 0xd2, 0x46, 0xae, 0xe3, 0xff, 0x43, 0xae, 0x8d, 0x0e, 0x31, 0x13, 0x1f, 
+0x95, 0x79, 0x82, 0x86, 0x7e, 0xfb, 0xd4, 0x17, 0x57, 0xb8, 0x25, 0xe7, 0x1d, 0x18, 0x8f, 
+0x06, 0x1a, 0xe5, 0xef, 0x55, 0x28, 0x72, 0x42, 0xae, 0xdf, 0x9e, 0xbb, 0x14, 0xab, 0xd8, 
+0x36, 0x4f, 0x46, 0x4b, 0x35, 0x92, 0x64, 0x6d, 0xbb, 0x60, 0xc2, 0x0b, 0x6f, 0x57, 0x5e, 
+0x3a, 0x8f, 0x3d, 0xcb, 0xe5, 0xda, 0x6c, 0x5c, 0x85, 0x8f, 0x9d, 0xa6, 0x7e, 0x1e, 0x49, 
+0x1a, 0xcc, 0xc9, 0xec, 0x04, 0xab, 0x35, 0xf2, 0x9b, 0xe7, 0xb3, 0x52, 0xb1, 0x1c, 0xc1, 
+0xfe, 0x5c, 0x0b, 0xf5, 0x72, 0x0b, 0xec, 0x8e, 0xcd, 0x67, 0x98, 0xbf, 0xa5, 0x28, 0xca, 
+0x48, 0x9b, 0x60, 0x1c, 0xee, 0x00, 0xde, 0x01, 0xbc, 0xa4, 0x02, 0xd2, 0x19, 0xb6, 0x05, 
+0xd6, 0x52, 0x78, 0xdb, 0x20, 0xbd, 0x3f, 0x95, 0x97, 0xb1, 0x59, 0x3d, 0x9d, 0x83, 0xc2, 
+0xfd, 0x23, 0xa5, 0xfd, 0xd8, 0x20, 0x92, 0x27, 0xee, 0x3c, 0xe9, 0x5a, 0x61, 0x11, 0xe1, 
+0x31, 0xb4, 0x4c, 0xb4, 0xa9, 0xe2, 0x6d, 0x2e, 0xae, 0x5f, 0x37, 0x8e, 0x07, 0xfd, 0xed, 
+0x85, 0x07, 0x79, 0x43, 0x7e, 0xfa, 0xd6, 0x03, 0xe8, 0x5b, 0x65, 0x2a, 0xe4, 0xf9, 0x36, 
+0x9e, 0xff, 0x53, 0x6d, 0x51, 0x50, 0x61, 0x72, 0x18, 0xcd, 0x3d, 0xe4, 0xb6, 0x27, 0x10, 
+0x4a, 0xdd, 0xfd, 0xa3, 0x36, 0x67, 0xac, 0xc7, 0x85, 0x1c, 0xd3, 0xe7, 0x17, 0x74, 0xe2, 
+0x8e, 0xee, 0xa6, 0xf4, 0xb6, 0x86, 0x24, 0xcf, 0x40, 0xdf, 0x35, 0x08, 0x0f, 0x55, 0xdd, 
+0x51, 0xe9, 0x7c, 0x39, 0x78, 0x5c, 0xdf, 0x20, 0x2a, 0xeb, 0xed, 0x35, 0x10, 0x26, 0x98, 
+0x77, 0x69, 0x4e, 0x51, 0x7a, 0xb2, 0x9f, 0x1d, 0xbc, 0x06, 0xcd, 0xcf, 0x4d, 0xb9, 0xfa, 
+0xb7, 0xaf, 0x6a, 0x07, 0x0c, 0x96, 0x42, 0x57, 0x6c, 0x3d, 0xa5, 0xfe, 0x91, 0xe3, 0x76, 
+0x9f, 0xdd, 0x3c, 0x83, 0x25, 0xab, 0x24, 0x89, 0x47, 0x7c, 0xba, 0xd7, 0x7d, 0x72, 0x90, 
+0x80, 0xb0, 0x03, 0xa4, 0xef, 0x04, 0x0a, 0x9e, 0x5a, 0x14, 0x1c, 0xab, 0x75, 0x47, 0x05, 
+0xcb, 0xa2, 0x97, 0x0d, 0x6a, 0xa5, 0x7c, 0xa4, 0x40, 0x90, 0xe2, 0x6c, 0xfa, 0xd4, 0xbd, 
+0x69, 0xd0, 0x06, 0x53, 0x67, 0xfa, 0xe7, 0xcc, 0x06, 0x42, 0x45, 0xbe, 0xbd, 0x6f, 0x3e, 
+0x48, 0x70, 0xf5, 0x2b, 0x83, 0xc7, 0xba, 0x54, 0x9c, 0xab, 0x54, 0x1f, 0x81, 0xe2, 0x11, 
+0x82, 0x51, 0x02, 0x51, 0x63, 0x13, 0x86, 0x38, 0xb1, 0x56, 0x0c, 0x4d, 0x68, 0xf3, 0x53, 
+0x1d, 0xfb, 0xe3, 0x15, 0xe8, 0x42, 0xf3, 0x27, 0x9b, 0xa5, 0x4a, 0x86, 0x90, 0xe1, 0x17, 
+0xdc, 0x99, 0xe2, 0x5c, 0x79, 0xc6, 0x5f, 0x7e, 0x33, 0xc0, 0x41, 0xb6, 0x9e, 0xfc, 0x10, 
+0x8a, 0xf4, 0xfd, 0xe9, 0xd2, 0x52, 0x53, 0x54, 0x89, 0x04, 0xbd, 0x69, 0xd2, 0x54, 0x32, 
+0x96, 0xec, 0x44, 0x08, 0xc3, 0x86, 0x10, 0xd1, 0x3e, 0x32, 0xb5, 0x4f, 0x52, 0x49, 0x58, 
+0x49, 0xf2, 0x8d, 0x83, 0x89, 0xf3, 0x24, 0x83, 0x65, 0x72, 0x53, 0xaf, 0x2d, 0x90, 0x61, 
+0x99, 0x92, 0x31, 0x75, 0x93, 0x46, 0xe5, 0xd3, 0x48, 0x11, 0x01, 0xc9, 0x10, 0x98, 0x66, 
+0x86, 0x79, 0x19, 0x73, 0x7d, 0xda, 0xa1, 0xb0, 0x41, 0x9e, 0xcd, 0xdc, 0xc2, 0x66, 0x86, 
+0xdd, 0xb8, 0xc9, 0xe3, 0xe7, 0x80, 0x96, 0xf5, 0x38, 0x72, 0xa5, 0xda, 0xe5, 0x38, 0x13, 
+0x57, 0x2b, 0xbd, 0x32, 0xc7, 0x44, 0xe0, 0xe3, 0x2d, 0xed, 0x54, 0x40, 0x74, 0x9d, 0x02, 
+0x55, 0x38, 0x45, 0x89, 0x6f, 0x14, 0x40, 0xf6, 0x7b, 0x41, 0x1e, 0x04, 0xdb, 0xa4, 0xd9, 
+0xf3, 0x90, 0xae, 0x10, 0xc9, 0xc3, 0x72, 0x5d, 0x0d, 0x01, 0x51, 0xf1, 0xd1, 0x96, 0x43, 
+0xc6, 0x1a, 0x98, 0x3d, 0xbd, 0xcd, 0xdf, 0x44, 0x82, 0xd0, 0x17, 0xa2, 0x9e, 0x6c, 0x0c, 
+0x2f, 0x46, 0xeb, 0xd8, 0x4a, 0xce, 0xfe, 0xbe, 0xcd, 0xf9, 0xd4, 0xe3, 0x36, 0xf3, 0xd8, 
+0x1c, 0x00, 0x24, 0xf2, 0xac, 0x03, 0x11, 0xb6, 0x18, 0x8f, 0x9c, 0xba, 0xf6, 0x4f, 0xfd, 
+0x78, 0x72, 0x83, 0xbf, 0x3e, 0x5c, 0x24, 0xf9, 0x4d, 0xea, 0x85, 0x74, 0x25, 0xe3, 0x46, 
+0x7b, 0x5e, 0xfe, 0xbd, 0xbf, 0x5e, 0x68, 0x51, 0xe5, 0x53, 0x85, 0x9a, 0x03, 0x4c, 0x09, 
+0xf0, 0x6b, 0xc2, 0x97, 0xfc, 0xcc, 0x96, 0x2c, 0xaf, 0xf7, 0x8c, 0x26, 0xd8, 0xc7, 0xfc, 
+0xda, 0x1f, 0x0e, 0x0f, 0x39, 0x1a, 0xb2, 0x0a, 0x98, 0x1a, 0x15, 0xdc, 0x3e, 0x4b, 0x9e, 
+0x9d, 0x40, 0x3e, 0x71, 0x5b, 0x66, 0xc3, 0x88, 0xf8, 0x57, 0x14, 0x06, 0xc7, 0x2c, 0xcd, 
+0x31, 0x8e, 0x1e, 0x88, 0x79, 0x9f, 0x33, 0x94, 0xea, 0x21, 0x08, 0x0d, 0x35, 0x7d, 0xa2, 
+0x57, 0x46, 0xe3, 0x0f, 0xb9, 0xa9, 0xbc, 0xd2, 0x06, 0xb8, 0xfa, 0xf9, 0xb0, 0xf3, 0xc3, 
+0x8a, 0x38, 0x82, 0x06, 0x7f, 0xd9, 0xce, 0x92, 0xa2, 0x9e, 0xfc, 0x2a, 0xc8, 0x51, 0xb7, 
+0x7d, 0xdb, 0x47, 0x37, 0xaf, 0x8b, 0xb8, 0x6d, 0x70, 0x21, 0x02, 0x63, 0x5e, 0xbd, 0x38, 
+0xf1, 0xe1, 0x9f, 0xe3, 0xe2, 0x79, 0x3b, 0x42, 0x05, 0xe2, 0xc6, 0x13, 0x7a, 0xe2, 0x91, 
+0x73, 0xe2, 0x79, 0x8b, 0x2f, 0x7f, 0x88, 0x02, 0x06, 0x4e, 0xb8, 0x66, 0xb8, 0xc0, 0xc4, 
+0x3b, 0x1c, 0x3e, 0x96, 0x0f, 0xbb, 0x7f, 0xe8, 0x85, 0x5b, 0xb2, 0xf6, 0xa7, 0x48, 0x5b, 
+0x95, 0x83, 0x57, 0xe0, 0xe8, 0x22, 0x67, 0x07, 0x3c, 0x27, 0x65, 0x66, 0xe8, 0x84, 0xab, 
+0xea, 0xf5, 0xb5, 0x00, 0xec, 0xa4, 0xa3, 0xe8, 0x25, 0x77, 0xd1, 0x81, 0x9c, 0x87, 0xd3, 
+0x1a, 0x31, 0x58, 0xa4, 0x0a, 0xa8, 0x71, 0x9c, 0x52, 0x88, 0x4d, 0x50, 0xff, 0xdb, 0x41, 
+0x81, 0x04, 0xc3, 0x84, 0xaa, 0x72, 0x79, 0x2f, 0x9b, 0x2d, 0x2f, 0x1c, 0xa5, 0x6b, 0x68, 
+0x9b, 0x3b, 0x6b, 0x1c, 0x67, 0xeb, 0x42, 0xe0, 0xe3, 0x2c, 0x7b, 0x52, 0x8e, 0xc1, 0x7e, 
+0xd8, 0xab, 0x02, 0x46, 0xd1, 0x83, 0x38, 0x1a, 0x18, 0xad, 0x90, 0x7f, 0xdb, 0x22, 0xc1, 
+0x80, 0xea, 0xf7, 0x67, 0x1d, 0xa7, 0xb2, 0x40, 0xdb, 0xc3, 0xc4, 0xd5, 0x8b, 0x49, 0xf8, 
+0xdc, 0x25, 0x80, 0x7e, 0xfa, 0x64, 0xac, 0x36, 0x4d, 0x74, 0x6f, 0x3e, 0x57, 0x23, 0xb4, 
+0x49, 0x7c, 0x6f, 0x3e, 0x7c, 0xa7, 0x34, 0xb7, 0x6b, 0x66, 0xf8, 0xd1, 0x69, 0x6d, 0x83, 
+0xc5, 0x8a, 0xe2, 0x42, 0x3f, 0x8b, 0x5e, 0x5a, 0xd5, 0xcd, 0x47, 0x64, 0xeb, 0x4e, 0xef, 
+0x62, 0x19, 0x37, 0xd3, 0x8e, 0x68, 0x51, 0x4a, 0x96, 0xbb, 0x5b, 0xa0, 0x34, 0xd8, 0xb4, 
+0xf4, 0xb0, 0x99, 0x53, 0xb1, 0x70, 0xc3, 0x1d, 0x6e, 0x2b, 0x03, 0x76, 0xc9, 0x00, 0x0b, 
+0x10, 0xca, 0xb7, 0xf3, 0xbe, 0x4b, 0xe2, 0xb4, 0x6c, 0x4a, 0x9f, 0x59, 0x39, 0x30, 0xc7, 
+0xc3, 0x88, 0x38, 0x63, 0xc4, 0xcf, 0xd1, 0xfd, 0xf0, 0x6d, 0xfe, 0x68, 0x92, 0x98, 0x11, 
+0x7d, 0x90, 0x0c, 0x64, 0x23, 0xe8, 0x25, 0x77, 0xd1, 0x81, 0x75, 0xa4, 0xf4, 0x35, 0x6f, 
+0xe4, 0x9c, 0x7a, 0x48, 0xd0, 0xde, 0x37, 0x42, 0xf8, 0x5b, 0xe9, 0x16, 0xba, 0x16, 0x4b, 
+0x7c, 0xdb, 0x2c, 0x0e, 0xa0, 0xbc, 0x5c, 0x82, 0x71, 0xa0, 0x9d, 0x3a, 0x0a, 0x7e, 0xd0, 
+0xdc, 0x93, 0x79, 0xf6, 0x78, 0xb5, 0x89, 0xd9, 0x70, 0x5d, 0xe0, 0x9d, 0xe7, 0xea, 0xee, 
+0x88, 0x52, 0x18, 0x11, 0x7d, 0xf1, 0xce, 0xc1, 0x69, 0x8d, 0x3f, 0xea, 0x51, 0xc1, 0x49, 
+0xb1, 0xc4, 0xa6, 0xf0, 0xdc, 0xbd, 0x61, 0xb7, 0x2c, 0x85, 0x4a, 0xcb, 0xdd, 0x96, 0x50, 
+0x8b, 0x68, 0xf7, 0x7e, 0xb9, 0x1c, 0x19, 0xfb, 0x5c, 0x79, 0xf8, 0x7d, 0xe9, 0xf3, 0x0e, 
+0xc7, 0x6e, 0x1c, 0x67, 0xb4, 0xb7, 0x4a, 0xc5, 0xbe, 0x3c, 0x8c, 0x94, 0x36, 0x02, 0x8f, 
+0x81, 0x57, 0xe7, 0x4b, 0xd6, 0x2b, 0x10, 0xbe, 0x3c, 0x97, 0xbb, 0x41, 0x88, 0x6f, 0x13, 
+0xe6, 0x27, 0x13, 0x4b, 0xd5, 0x44, 0xa9, 0xd9, 0x2d, 0xcd, 0x51, 0x91, 0x03, 0x14, 0xd5, 
+0x6b, 0x3d, 0xb5, 0x98, 0xf0, 0x09, 0xaa, 0x42, 0x8e, 0x82, 0xe8, 0xf1, 0x36, 0xec, 0xb5, 
+0x48, 0x5f, 0x9f, 0xca, 0x16, 0x5a, 0x3f, 0x4d, 0xbb, 0xa6, 0xd4, 0x08, 0x1a, 0xfb, 0xe5, 
+0xeb, 0x40, 0x04, 0xe8, 0x40, 0x84, 0xc4, 0x8e, 0x74, 0xae, 0x47, 0x4d, 0xfc, 0xb5, 0x91, 
+0xe2, 0x33, 0xf2, 0xf7, 0xae, 0xcd, 0x10, 0x47, 0xb1, 0x4b, 0xe2, 0xa2, 0x8d, 0x7c, 0x2c, 
+0x32, 0x6f, 0xdd, 0xc4, 0xc2, 0xf1, 0x09, 0x56, 0x2d, 0x1e, 0x9d, 0x7d, 0x67, 0x32, 0x61, 
+0x7f, 0x12, 0xe4, 0x3f, 0xfa, 0xe2, 0x7d, 0x7b, 0xd4, 0x67, 0x4e, 0x7f, 0x14, 0x6a, 0x6c, 
+0x8e, 0x74, 0x9b, 0xbc, 0x3d, 0xc4, 0x70, 0xc4, 0x37, 0xd5, 0x60, 0xe0, 0x87, 0xbd, 0xb8, 
+0x1a, 0x75, 0x9d, 0x7a, 0x80, 0xc1, 0xa9, 0x1f, 0xad, 0x7b, 0x27, 0xe5, 0x4c, 0xb0, 0x06, 
+0xd0, 0xfb, 0x1c, 0x5a, 0xeb, 0xbd, 0x2e, 0x96, 0x49, 0x13, 0x43, 0x06, 0x8b, 0xcb, 0x6a, 
+0xf0, 0x5d, 0x56, 0x6c, 0x4e, 0x18, 0x26, 0xd4, 0xc8, 0x53, 0x48, 0x70, 0xe2, 0x0f, 0x9c, 
+0xa1, 0x35, 0x01, 0x96, 0xc7, 0x0b, 0xc9, 0x4b, 0xd3, 0x19, 0xe8, 0x5a, 0x75, 0xad, 0xc8, 
+0x52, 0xce, 0x3c, 0x2e, 0xfd, 0x5f, 0x04, 0xcf, 0x9e, 0xd6, 0x33, 0xdb, 0x08, 0x34, 0xba, 
+0x34, 0x9b, 0xf4, 0x25, 0xaa, 0x7f, 0x52, 0x37, 0x4f, 0x8b, 0x94, 0x95, 0x94, 0x2d, 0x88, 
+0x10, 0xd1, 0x05, 0x07, 0xcf, 0xd4, 0x04, 0xdb, 0x95, 0xbe, 0x36, 0xd0, 0x1c, 0x1c, 0xa4, 
+0x85, 0x0a, 0x02, 0x80, 0xde, 0xb1, 0x1b, 0x56, 0xaf, 0x51, 0x22, 0xa7, 0xa4, 0x4a, 0x2c, 
+0x2f, 0x17, 0x7c, 0x13, 0x4c, 0x36, 0xad, 0x90, 0x8c, 0xea, 0xd4, 0x58, 0x3a, 0xca, 0xea, 
+0x1d, 0x5c, 0x6c, 0x93, 0xad, 0x59, 0xed, 0xb1, 0x17, 0xa4, 0x22, 0x95, 0x67, 0xbe, 0xbb, 
+0x25, 0xaf, 0x65, 0xc8, 0xe5, 0x90, 0xe1, 0x17, 0xdc, 0x7a, 0x47, 0xe9, 0x8f, 0xc3, 0xc3, 
+0x5a, 0xdc, 0x20, 0x20, 0x4a, 0x09, 0xfc, 0x39, 0x51, 0x29, 0x31, 0xfb, 0xa0, 0x0a, 0x61, 
+0x08, 0x9b, 0xb9, 0xb3, 0x6c, 0x95, 0xc5, 0x94, 0x00, 0x66, 0xf1, 0xb9, 0x79, 0x90, 0x7f, 
+0x95, 0x5f, 0x55, 0xe1, 0x13, 0x6b, 0x87, 0xa8, 0x62, 0x21, 0x98, 0xf2, 0x57, 0x19, 0x92, 
+0x10, 0xb3, 0x24, 0x81, 0x12, 0x21, 0xff, 0xd6, 0xf9, 0x73, 0x71, 0xc2, 0x62, 0x09, 0x31, 
+0xeb, 0xe0, 0x7a, 0x35, 0x60, 0x8d, 0xc9, 0xb1, 0xe5, 0xa7, 0x8b, 0xca, 0xbc, 0x2d, 0xfa, 
+0x63, 0xc7, 0x68, 0x1d, 0x19, 0xb5, 0x61, 0x78, 0xd0, 0x8b, 0xdb, 0xc0, 0x39, 0x22, 0x55, 
+0x6a, 0x28, 0xc2, 0x52, 0x1e, 0x6b, 0xf7, 0x1d, 0xb6, 0xfa, 0x4f, 0xcf, 0x27, 0x7c, 0xaf, 
+0x7f, 0x0c, 0x96, 0xba, 0xce, 0x2a, 0x54, 0x59, 0x5b, 0x20, 0xfb, 0x42, 0x87, 0x44, 0xd9, 
+0x2e, 0x10, 0x43, 0xab, 0x58, 0x92, 0xb6, 0x8d, 0x78, 0xf3, 0xa3, 0xde, 0x0e, 0x07, 0x75, 
+0x68, 0x52, 0x26, 0x3f, 0x3d, 0xec, 0xd0, 0x36, 0xdf, 0x1a, 0x16, 0x88, 0x5f, 0xbd, 0x1c, 
+0x4d, 0x9e, 0x27, 0x4c, 0x12, 0x07, 0x0d, 0x2b, 0xb1, 0xdc, 0x00, 0x45, 0x54, 0x3d, 0xfc, 
+0xcf, 0xfa, 0xc9, 0x06, 0x4b, 0x08, 0x64, 0xac, 0x8d, 0x17, 0x4d, 0xdf, 0x83, 0x24, 0xfb, 
+0xf6, 0x9e, 0x5f, 0xf9, 0x0f, 0x8d, 0x07, 0x18, 0xb1, 0xb2, 0x37, 0xd2, 0x66, 0x9c, 0x82, 
+0x09, 0x75, 0x52, 0x5b, 0x19, 0x74, 0x59, 0xa3, 0x64, 0x6d, 0x17, 0x93, 0x3a, 0x13, 0xd2, 
+0xda, 0x97, 0xa4, 0x2b, 0x55, 0x7a, 0x32, 0xf9, 0x2f, 0x9b, 0xaa, 0x87, 0x6d, 0xce, 0x1d, 
+0x07, 0x9a, 0x52, 0xfa, 0x40, 0xc5, 0x20, 0x43, 0xcc, 0xa8, 0xc3, 0x84, 0x2c, 0x44, 0x8b, 
+0x44, 0x88, 0x62, 0xe7, 0x68, 0x4c, 0x2a, 0x69, 0xa7, 0xcf, 0x6f, 0x4d, 0x06, 0xed, 0x8a, 
+0x8f, 0x9a, 0x62, 0xca, 0xed, 0xa5, 0x57, 0x18, 0x86, 0x9d, 0xe8, 0x7c, 0x14, 0xeb, 0x71, 
+0xeb, 0xc0, 0xf4, 0x3a, 0x98, 0x11, 0x01, 0xc0, 0xa3, 0x53, 0xaf, 0x20, 0x7e, 0xde, 0x22, 
+0x5c, 0x1f, 0x60, 0x8b, 0xb7, 0x5f, 0x74, 0x76, 0xd0, 0x87, 0xfa, 0x11, 0xd3, 0xa5, 0xba, 
+0x5c, 0x82, 0xe1, 0x52, 0x54, 0x6b, 0x69, 0xeb, 0x31, 0x43, 0x01, 0x1a, 0x55, 0x7f, 0xdc, 
+0x2f, 0xd8, 0x01, 0x26, 0x6f, 0x1c, 0x2d, 0x72, 0x7b, 0xc8, 0x93, 0x99, 0x2a, 0x08, 0xa8, 
+0x6f, 0xb4, 0x28, 0x40, 0x8a, 0x8a, 0x4e, 0xd5, 0x3b, 0x39, 0x45, 0xa8, 0xe4, 0xe7, 0x73, 
+0x8f, 0x00, 0x64, 0xd3, 0xc7, 0x87, 0xde, 0x43, 0x82, 0x2c, 0xe8, 0x57, 0x17, 0x29, 0xce, 
+0xb8, 0x47, 0xd6, 0x08, 0x79, 0xd7, 0xc4, 0xe9, 0x23, 0x43, 0x9d, 0xb8, 0xcb, 0x78, 0x08, 
+0x32, 0xf1, 0xec, 0x84, 0x80, 0x1e, 0xb9, 0x29, 0x12, 0x0c, 0x29, 0xcc, 0x9c, 0xd0, 0x10, 
+0xa7, 0xd6, 0x8a, 0xe9, 0xf6, 0xfa, 0x8d, 0x7e, 0x95, 0x2e, 0x57, 0xcf, 0x8e, 0x38, 0x6b, 
+0x35, 0xf0, 0xbc, 0xa6, 0x4e, 0x13, 0x7b, 0x41, 0x19, 0x15, 0x5d, 0x99, 0xbd, 0x22, 0x40, 
+0x6a, 0x07, 0x2d, 0xd5, 0xd6, 0xff, 0x1d, 0x7b, 0xa6, 0xc4, 0xaa, 0x77, 0x44, 0x78, 0x2f, 
+0x55, 0x9f, 0x7d, 0x53, 0xf0, 0x2b, 0x2b, 0xba, 0x36, 0xc2, 0xf8, 0x6d, 0xf0, 0x2b, 0xbb, 
+0x6b, 0x97, 0x05, 0xb4, 0x4a, 0xc2, 0x86, 0x62, 0xb8, 0x76, 0xe7, 0xbb, 0xdf, 0x9c, 0x5a, 
+0x70, 0x19, 0x95, 0x59, 0x15, 0xcf, 0xa6, 0xa9, 0x7a, 0x24, 0x4c, 0xc6, 0x65, 0xb9, 0xda, 
+0x17, 0x6f, 0x2b, 0x55, 0x07, 0x32, 0x72, 0xd1, 0xee, 0x9c, 0x3a, 0x51, 0x98, 0x36, 0x37, 
+0xf8, 0x61, 0xfc, 0x91, 0xbc, 0xcb, 0x34, 0xd8, 0x43, 0xa0, 0x7a, 0xea, 0xc4, 0x8a, 0x64, 
+0x4d, 0xe0, 0x03, 0x93, 0xfb, 0xb4, 0xd8, 0x11, 0x21, 0x11, 0x66, 0x97, 0xb9, 0xba, 0x81, 
+0x29, 0xc2, 0x8f, 0x8c, 0x14, 0x18, 0x22, 0x94, 0xc4, 0xb0, 0xf1, 0x10, 0xc4, 0x8b, 0x5d, 
+0x8d, 0x7f, 0x14, 0xaf, 0x46, 0x19, 0x36, 0xa4, 0x36, 0x22, 0x18, 0x18, 0xe3, 0xab, 0x2c, 
+0x91, 0x03, 0xf7, 0xc5, 0xf5, 0xf5, 0x59, 0xc2, 0xd2, 0xf7, 0xc7, 0x64, 0x54, 0x76, 0xfb, 
+0x71, 0x70, 0xe8, 0xb2, 0x44, 0xa1, 0x2d, 0x59, 0x17, 0x02, 0xd6, 0x6f, 0x7a, 0xeb, 0xe0, 
+0x53, 0x81, 0xf6, 0x5e, 0x7f, 0x37, 0xd4, 0x52, 0x13, 0x04, 0x44, 0xd5, 0xc8, 0xd3, 0xdd, 
+0x6f, 0xd5, 0xfb, 0x71, 0x20, 0xe3, 0x0d, 0x0c, 0x47, 0x25, 0xa1, 0x41, 0xd2, 0xc7, 0xe5, 
+0xc9, 0xd9, 0x27, 0xa5, 0x38, 0xe4, 0x30, 0xbb, 0x86, 0x07, 0x84, 0xef, 0x24, 0x9f, 0xf9, 
+0x52, 0x74, 0xd2, 0x50, 0x73, 0xc4, 0x27, 0x73, 0x3b, 0x8d, 0x9c, 0xa6, 0xf6, 0x4b, 0x25, 
+0x91, 0xc5, 0x9e, 0x1e, 0xb2, 0x78, 0x0c, 0x23, 0x80, 0xdd, 0xa3, 0x21, 0xf5, 0xa9, 0x9e, 
+0x00, 0x16, 0x19, 0xbc, 0xd9, 0x55, 0x09, 0x90, 0xa2, 0xc6, 0xef, 0x3d, 0xf8, 0x72, 0x66, 
+0x2f, 0xdc, 0x3a, 0xf6, 0x4f, 0xfd, 0x59, 0x30, 0xe2, 0x27, 0xcc, 0xfb, 0x55, 0x09, 0x71, 
+0x41, 0xe1, 0x21, 0xa1, 0xa1, 0xc0, 0xe3, 0x25, 0xa9, 0xd0, 0x22, 0xc6, 0xef, 0x5c, 0x1b, 
+0xb4, 0xea, 0x56, 0x2e, 0xbf, 0xfc, 0x5b, 0x34, 0xcb, 0x14, 0x8b, 0x94, 0xaa, 0xb7, 0xec, 
+0x5a, 0x36, 0xcf, 0x1c, 0xba, 0xf6, 0x4d, 0xdb, 0x35, 0xf3 };
+
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/main.cpp	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,10 @@
+#include "mbed.h"
+#include "extern.h"
+#include "main.h"
+
+int main(void) {
+    SetUp();
+    while(1){
+        Command();
+    }
+}
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/main_processing/setup_command_active/active.cpp	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,108 @@
+#include "mbed.h"
+#include "extern.h"
+
+void Active(void){
+    uint8_t i;
+    void (*DutyFunction[DUTY_NUM])(void) = {
+        Active2Command
+    };
+    for(i=0; i<DUTY_NUM; i++){
+        Duty[i].attach(DutyFunction[i], dutycycle[i]);
+    }
+    sys.stopflag=0;
+    //スタート直前の処理
+    SetUp2();
+    while(1){
+        //pc.printf("sys.stopflag=%d\r\n", sys.stopflag);
+        //StrategyFunction[sys.strategy]();
+        act[sys.strategy].ActiveFunction();
+        if(sys.stopflag==1){
+            //システム上の停止処理
+            button.detach();
+            last_statesum = statesum = 0;
+            state[0] = state[1] = state[2] = state[3] = 0;
+        
+            for(i=0; i<DUTY_NUM; i++){
+                Duty[DUTY_SW].detach();
+            }
+            sys.stopflag=0;
+            //その他停止処理
+            StopProcess();
+            break;
+        }
+    }
+    return;
+}
+void Active_old(void){
+    uint8_t i;
+    void (*DutyFunction[DUTY_NUM])(void) = {
+        Active2Command
+    };
+    void (*StrategyFunction[STRATEGY_NUM])(void) = {
+        //modeAttack5,
+        modeAttack2,
+        //modeAttack4,
+        modeAttack1,
+        modeAttack2,
+        modeAttack3,
+        modeAttack4,
+        modeAttack5,
+        
+        modeDebug0,
+        modeDebug1,
+        modeDebug2,
+        modeDebug3,
+        modeDebug4,
+        modeDebug5,
+    };
+    for(i=0; i<DUTY_NUM; i++){
+        Duty[i].attach(DutyFunction[i], dutycycle[i]);
+    }
+    sys.stopflag=0;
+    //スタート直前の処理
+    SetUp2();
+    while(1){
+        //pc.printf("sys.stopflag=%d\r\n", sys.stopflag);
+        StrategyFunction[sys.strategy]();
+        if(sys.stopflag==1){
+            //システム上の停止処理
+            button.detach();
+            last_statesum = statesum = 0;
+            state[0] = state[1] = state[2] = state[3] = 0;
+        
+            for(i=0; i<DUTY_NUM; i++){
+                Duty[DUTY_SW].detach();
+            }
+            sys.stopflag=0;
+            //その他停止処理
+            StopProcess();
+            break;
+        }
+    }
+    return;
+}
+//for transition
+void ResetState(void){
+    last_statesum = statesum = 0;
+    state[0] = state[1] = state[2] = state[3] = 0;
+}
+void Active2Command(void){
+    uint8_t i;
+    for(i=0; i<4; i++){
+        if(CountSw(i)==1) state[i]=1;
+    }
+    last_statesum = statesum;
+    statesum = state[0]+state[1]+state[2]+state[3];
+    if((statesum>=1)&&(!(statesum==last_statesum))){
+        button.attach(&ResetState, 1.0);
+    }
+    if((statesum>=2)&&(1)){
+        if((state[0]==1)&&(state[1]==1)&&(state[2]==0)&&(state[3]==0)){
+            sys.stopflag=1;
+        }
+        else{
+            button.detach();
+            ResetState();
+        }
+    }
+}
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/main_processing/setup_command_active/active.h	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,10 @@
+#ifndef _ACTIVE_H_
+#define _ACTIVE_H_
+
+//modeActive
+void Active(void);
+//for transition
+void ResetState(void);
+void Active2Command(void);
+
+#endif //_ACTIVE_H_
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/main_processing/setup_command_active/command.cpp	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,98 @@
+#include "mbed.h"
+#include "extern.h"
+
+void Command(void){
+    uint8_t SwState,x=0,y=0, z;
+    uint8_t i;
+    
+    sys.jump_flag=JUMP_TAG_MAX;
+    LcdPrint(&x,&y);
+    while(1){
+        SwState = ReadSw();
+        if(SwState == NONE){
+            if(x!=0){
+                z = item[y].CommandFunction(x);
+                if(z==1){
+                    x=0;
+                    //jump
+                    if(sys.jump_flag!=JUMP_TAG_MAX){
+                        for(i=0; i<STATE_NUM_Y; i++){
+                            if(sys.jump_flag==item[i].tag_num) break;
+                        }
+                        if(i<STATE_NUM_Y){
+                            y = i;
+                            y %= STATE_NUM_Y;
+                        }
+                        sys.jump_flag=JUMP_TAG_MAX;
+                    }
+                    LcdPrint(&x,&y);
+                }
+                //Z==1...Once
+                //Z==0...Endless
+            }
+            
+            continue;
+        }
+        if(SwState == UP){
+            y += -1 + STATE_NUM_Y;
+            y %= STATE_NUM_Y;
+            x=0;
+        }
+        if(SwState == DOWN){
+            y++;
+            y %= STATE_NUM_Y;
+            x=0;
+        }
+        if(SwState == RIGHT){
+            if(item[y].str_num<=1) x=0;
+            else x++;
+            x %= item[y].str_num;
+        }
+        if(SwState == LEFT){
+            x=0;
+        }
+        if(x==0){
+            X_ZERO_Function(&x,&y);
+        }
+        else{
+            X_NZERO_Function(&x,&y);
+        }
+        LcdPrint(&x,&y);
+    }
+}
+uint8_t X_ZERO_Function(uint8_t *x, uint8_t *y){
+    uint8_t i;
+    if(sys.jump_flag!=JUMP_TAG_MAX){//jump
+        for(i=0; i<STATE_NUM_Y; i++){
+            if(sys.jump_flag==item[i].tag_num) break;
+        }
+        if(i<STATE_NUM_Y){
+            *y = i;
+            *y %= STATE_NUM_Y;
+        }
+        sys.jump_flag=JUMP_TAG_MAX;
+    }
+    
+    ReadCmps();
+    //cmps_set.CmpsInitialValue = cmps_set.cmps;
+    wait_ms(10);
+    cmps_set.CmpsDiff = REFERENCE - cmps_set.cmps;
+    cmps_set.FrontDeg=0;
+    
+    LineKeeper=LINE_FREE;//line
+    return 0;
+}
+uint8_t X_NZERO_Function(uint8_t *x, uint8_t *y){
+    LineKeeper=LINE_FIX;//line
+    return 0;
+}
+uint8_t LcdPrint(uint8_t *x, uint8_t *y){
+    Lcd.cls();
+    Lcd.locate(0, 0);
+    Lcd.print(item[*y].LcdStr[0]);
+    Lcd.locate(7, 0);
+    Lcd.print(">");
+    Lcd.locate(9, 0);
+    if(*x!=0) Lcd.print(item[*y].LcdStr[*x]);
+    return 0;
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/main_processing/setup_command_active/command.h	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,9 @@
+#ifndef _COMMAND_H_
+#define _COMMAND_H_
+
+void Command(void);
+uint8_t X_ZERO_Function(uint8_t *x, uint8_t *y);
+uint8_t X_NZERO_Function(uint8_t *x, uint8_t *y);
+uint8_t LcdPrint(uint8_t *x, uint8_t *y);
+
+#endif //_COMMAND_H_
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/main_processing/setup_command_active/command_functions.cpp	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,264 @@
+#include "mbed.h"
+#include "extern.h"
+
+uint8_t ZeroFunction(uint8_t x){
+    char buf[LCD_COLUMN_NUM];
+    if(x==1){
+        sprintf(buf, "%2d%.14s", sys.strategy, act[sys.strategy].LcdStr);
+        Lcd.locate(0, 1);Lcd.print(buf);wait_ms(50);return 0;
+    }
+    else if(x==2){
+        sprintf(buf, "%2d:S%2d M%2d L%2d", 
+            sys.pow_num, 
+            ir_pow_val[sys.pow_num][POW_SHORT], 
+            ir_pow_val[sys.pow_num][POW_MIDDLE], 
+            ir_pow_val[sys.pow_num][POW_LONG]
+        );
+        Lcd.locate(0, 1);Lcd.print(buf);
+        return 0;
+    }
+    else{//x==3
+        sprintf(buf, "SeeYouAgain!");
+        Lcd.locate(0, 1);Lcd.print(buf);wait(0.5);
+        NVIC_SystemReset();
+        return 1;
+    }
+}
+uint8_t Start(uint8_t x){
+    char buf[LCD_COLUMN_NUM];
+    uint8_t temp;
+    temp = sys.strategy;
+    sprintf(buf, "CatPot");
+    Lcd.locate(0, 1);Lcd.print(buf);
+    sys.strategy=0;
+    sys.TurnStartFlag=0;
+    Active();
+    sys.strategy=temp;
+    //reset
+    NVIC_SystemReset();
+    return 1;
+}
+uint8_t TurnAndStart(uint8_t x){
+    char buf[LCD_COLUMN_NUM];
+    uint8_t temp;
+    temp = sys.strategy;
+    sprintf(buf, "CatPot");
+    Lcd.locate(0, 1);Lcd.print(buf);
+    sys.strategy=0;
+    sys.TurnStartFlag=1;
+    Active();
+    sys.strategy=temp;
+    //reset
+    NVIC_SystemReset();
+    return 1;
+}
+uint8_t GetIr(uint8_t x){
+    char buf[LCD_COLUMN_NUM];
+    ReadIr();
+    
+    //if(x==1) sprintf(buf, "SHRT:%2d, LNG:%2d", data.irSpot[0], data.irSpot[1]);
+    //if(x==2) sprintf(buf, "NOTE:%2d", data.irNotice);
+    //if(x==3) sprintf(buf, "POSITION:%2d", data.irPosition);
+    if(x==1) sprintf(buf, "POSI:%2d NOTE:%1d", data.irPosition, data.irNotice);
+    if(x==2) sprintf(buf, "PH_L:%1d PH_S:%1d", data.irValPhase[IR_LONG], data.irValPhase[IR_SHORT]);
+    if(x==3) sprintf(buf, "DIF:%1d KEY:%2d", data.irDif[IR_LONG], data.irKey);
+    Lcd.locate(0, 1);Lcd.print(buf);wait_ms(50);return 0;
+}
+uint8_t GetSns0(uint8_t x){
+    char buf[LCD_COLUMN_NUM];
+    uint8_t raw[3];
+    uint8_t held[3];
+    if(x==1){
+        LineKeeper=LINE_FIX;//line
+        
+        raw[2] = GetBit(LineRaw, 3);
+        raw[1] = GetBit(LineRaw, 2);
+        raw[0] = GetBit(LineRaw, 1);
+        
+        held[2] = GetBit(LineHold, 3);
+        held[1] = GetBit(LineHold, 2);
+        held[0] = GetBit(LineHold, 1);
+        //BusOut LineKeeper(lineInA, lineInB, lineInC);
+        //BusIn LineRaw(lineA2, lineB2, lineC2);
+        //BusIn LineHold(lineA1, lineB1, lineC1);
+        sprintf(buf, "A:%1d%1d B:%1d%1d C:%1d%1d ", raw[0],held[0],raw[1],held[1],raw[2],held[2]);
+        //sprintf(buf, "A:%1d B:%1d C:%1d ", Line[0].read(), Line[1].read(), Line[2].read());
+        Lcd.locate(0, 1);Lcd.print(buf);wait_ms(50);return 0;
+    }
+    if(x==2){
+        ReadPing2();
+        ReadPing();
+        sprintf(buf, "L%3dR%3dF%3dB%3d", data.ping[L_PING], data.ping[R_PING], data.ping[F_PING], data.ping[B_PING]);
+        Lcd.locate(0, 1);Lcd.print(buf);wait_ms(50);return 0;
+    }
+    if(x==3){
+        //ReadIr();
+        //sprintf(buf, "IR_KEY:%2d", data.irKey);
+        //sprintf(buf, "BALL:%1d", BallChecker.read());
+        sprintf(buf, "BALLA%6d", BallCheckerA.read_u16());
+        Lcd.locate(0, 1);Lcd.print(buf);wait_ms(50);return 0;
+    }
+    return 0;
+}
+uint8_t RwPid(uint8_t x){
+    char buf[LCD_COLUMN_NUM];
+    if(x==1){
+        PidUpdate();
+        sprintf(buf, "In:%03.0f Out:%+02d", cmps_set.InputPID, cmps_set.OutputPID);
+        Lcd.locate(0, 1);Lcd.print(buf);wait_ms(50);return 0;
+    }
+    if(x==2){
+        sys.jump_flag=START;
+        sprintf(buf, "FaceToFront!");
+        Lcd.locate(0, 1);Lcd.print(buf);
+        hmc_reset = HMC_RST;
+        wait_ms(100);
+        hmc_reset = HMC_RUN;
+        for(int i=0; i<5; i++){
+            ReadCmps();
+            cmps_set.CmpsInitialValue = cmps_set.cmps;
+            wait_ms(100);
+        }
+        cmps_set.CmpsDiff = REFERENCE - cmps_set.cmps;
+        cmps_set.FrontDeg=0;
+        return 1;
+    }
+    return 1;
+}
+uint8_t CalibrationEnterOrExit(uint8_t x){
+    static uint8_t state=0;
+    char buf[LCD_COLUMN_NUM];
+    
+    if(x==1){
+        if(state==0){
+            sprintf(buf, "Exit>>Enter");
+        }
+        if(state==1){
+            sprintf(buf, "Enter>>Exit");
+        }
+        Lcd.locate(0, 1);Lcd.print(buf);
+        return 0;
+    }
+    if(x==2){
+        if(state==0){
+            hmc.setCalibrationMode(HMC6352_ENTER_CALIB);
+            state=1;
+            return 1;
+        }
+        if(state==1){
+            hmc.setCalibrationMode(HMC6352_EXIT_CALIB);
+            state=0;
+            return 1;
+        }
+    }
+    return 1;
+}
+uint8_t CalibrationTurn(uint8_t x){
+    char buf[LCD_COLUMN_NUM];
+    sprintf(buf, "CalibrationTurn");
+    Lcd.locate(0, 1);Lcd.print(buf);
+    hmc.setCalibrationMode(HMC6352_ENTER_CALIB);wait_ms(20);
+    move(0,0,5);tx_motor();
+    wait(5);
+    move(0,0,0);tx_motor();
+    hmc.setCalibrationMode(HMC6352_EXIT_CALIB);wait_ms(20);
+    sys.jump_flag=GET_PID_VALUE;
+    return 1;
+}
+uint8_t SetPowerUp(uint8_t x){
+    char buf[LCD_COLUMN_NUM];
+    uint8_t i=(sys.pow_num+(-1+POW_COMBI_NUM))%POW_COMBI_NUM;
+    if(x==1){
+        sprintf(buf, "%2d:S%2d M%2d L%2d", i, ir_pow_val[i][POW_SHORT], ir_pow_val[i][POW_MIDDLE], ir_pow_val[i][POW_LONG]);
+        Lcd.locate(0, 1);Lcd.print(buf);
+        return 0;
+    }
+    else{//x==2
+        sys.pow_num = i;
+        sys.s_pow = ir_pow_val[sys.pow_num][POW_SHORT];
+        sys.m_pow = ir_pow_val[sys.pow_num][POW_MIDDLE];
+        sys.l_pow = ir_pow_val[sys.pow_num][POW_LONG];
+        return 1;
+    }
+}
+uint8_t SetPowerDown(uint8_t x){
+    char buf[LCD_COLUMN_NUM];
+    uint8_t i=(sys.pow_num+1)%POW_COMBI_NUM;
+    if(x==1){
+        sprintf(buf, "%2d:S%2d M%2d L%2d", i, ir_pow_val[i][POW_SHORT], ir_pow_val[i][POW_MIDDLE], ir_pow_val[i][POW_LONG]);
+        Lcd.locate(0, 1);Lcd.print(buf);
+        return 0;
+    }
+    else{//x==2
+        sys.pow_num = i;
+        sys.s_pow = ir_pow_val[sys.pow_num][POW_SHORT];
+        sys.m_pow = ir_pow_val[sys.pow_num][POW_MIDDLE];
+        sys.l_pow = ir_pow_val[sys.pow_num][POW_LONG];
+        return 1;
+    }
+}
+uint8_t SoftReset(uint8_t x){
+    char buf[LCD_COLUMN_NUM];
+    sprintf(buf, "SeeYouAgain!");
+    Lcd.locate(0, 1);Lcd.print(buf);wait(0.5);
+    NVIC_SystemReset();
+    return 1;
+}
+uint8_t SetStrategyUp(uint8_t x){
+    char buf[LCD_COLUMN_NUM];
+    uint8_t i=(sys.strategy+(-1+STRATEGY_NUM))%STRATEGY_NUM;
+    if(x==1){
+        sprintf(buf, "%2d:%.12s", i, act[i].LcdStr);
+        Lcd.locate(0, 1);Lcd.print(buf);
+        return 0;
+    }
+    else{//x==2
+        sys.strategy = i;
+        return 1;
+    }
+}
+uint8_t SetStrategyDown(uint8_t x){
+    char buf[LCD_COLUMN_NUM];
+    uint8_t i=(sys.strategy+1)%STRATEGY_NUM;
+    if(x==1){
+        sprintf(buf, "%2d:%.12s", i, act[i].LcdStr);
+        Lcd.locate(0, 1);Lcd.print(buf);
+        return 0;
+    }
+    else{//x==2
+        sys.strategy = i;
+        return 1;
+    }
+}
+uint8_t Start2(uint8_t x){
+    char buf[LCD_COLUMN_NUM];
+    sprintf(buf, "CatPotForDebug");
+    Lcd.locate(0, 1);Lcd.print(buf);
+    sys.TurnStartFlag=0;
+    Active();
+    return 1;
+}
+uint8_t DriveKicker(uint8_t x){
+    char buf[LCD_COLUMN_NUM];
+    sprintf(buf, "KickForDebug");
+    Lcd.locate(0, 1);Lcd.print(buf);
+    wait(2);
+    kicker = 1;
+    wait(.5);
+    kicker = 0;
+    wait(.5);
+    return 1;
+}
+uint8_t DriveDribblerAndKicker(uint8_t x){
+    char buf[LCD_COLUMN_NUM];
+    sprintf(buf, "DribbleForDebug");
+    Lcd.locate(0, 1);Lcd.print(buf);
+    sys.DribbleFlag=1;wait_ms(20);move(0,0,0);tx_motor();
+    wait(5);
+    kicker = 1;
+    wait(.5);
+    kicker = 0;
+    wait(2);
+    sys.DribbleFlag=0;wait_ms(20);move(0,0,0);tx_motor();
+    return 1;
+}
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/main_processing/setup_command_active/command_functions.h	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,26 @@
+#ifndef _COMMAND_FUNCTIONS_H_
+#define _COMMAND_FUNCTIONS_H_
+
+//information on disply, transition to modeActive and so on.
+uint8_t ZeroFunction(uint8_t x);
+uint8_t Start(uint8_t x);
+uint8_t GetIr(uint8_t x);
+uint8_t GetSns0(uint8_t x);
+uint8_t SoftReset(uint8_t x);
+uint8_t Start2(uint8_t x);
+
+uint8_t SetPowerDown(uint8_t x);
+uint8_t SetPowerUp(uint8_t x);
+
+uint8_t SetStrategyDown(uint8_t x);
+uint8_t SetStrategyUp(uint8_t x);
+
+uint8_t DriveKicker(uint8_t x);
+uint8_t DriveDribblerAndKicker(uint8_t x);
+
+uint8_t CalibrationTurn(uint8_t x);
+uint8_t RwPid(uint8_t x);
+uint8_t TurnAndStart(uint8_t x);
+uint8_t CalibrationEnterOrExit(uint8_t x);
+
+#endif //_COMMAND_FUNCTIONS_H_
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/main_processing/setup_command_active/setup.cpp	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,207 @@
+#include "mbed.h"
+#include "extern.h"
+
+
+void SetUp(void){//電源を入れた時の処理
+    //int i=1;
+    //solenoid
+    kicker=0;
+    //sw&lcd
+    Sw[0].mode(PullUp);
+    Sw[1].mode(PullUp);
+    Sw[2].mode(PullUp);
+    Sw[3].mode(PullUp);
+    Sw_ticker.attach(Sw_sample, 0.050);
+    
+    //ball
+    BallChecker.mode(PullUp);
+    
+    //system,flag
+    sys.strategy=0;
+    sys.jump_flag=JUMP_TAG_MAX;//0<=x<=JUMP_TAG_NUM
+    sys.stopflag=0;
+    sys.KickOffFlag=0;
+    sys.TurnStartFlag=0;
+    sys.DribbleFlag=0;
+    sys.MotorFlag=0;
+    sys.InfoFlag=0;
+    //sys.PidFlag=0;
+    //motor 
+    sys.pow_num = 1;
+    sys.s_pow = ir_pow_val[sys.pow_num][POW_SHORT];
+    sys.m_pow = ir_pow_val[sys.pow_num][POW_MIDDLE];
+    sys.l_pow = ir_pow_val[sys.pow_num][POW_LONG];
+    /*sys.s_pow = 30;
+    sys.m_pow = 30;
+    sys.l_pow = 30;*/
+    sys.dri_pow = 100;
+    sys.ir_pow_table = 0;
+    
+    ///////important
+    ///Blindシリーズ.1を代入であらゆるセンサーなどの値を反映させないようにする.
+    sys.IrBlind=0;
+    sys.LineBlind=0;
+    sys.PingBlind=0;
+    
+    sys.HomeBlind=1;
+    sys.DriBlind=1;
+    sys.DriMotorBlind=0;
+    sys.TurnAtkBlind=0;
+    sys.TurnDriBlind=0;
+    sys.TurnHoldBlind=0;
+    sys.KickBlind=0;
+    //defence
+    sys.DefenceFlag=0;
+    ////////important
+    
+    //ir
+    data.irNotice=IR_NONE;
+    
+    //spi
+    spi.format(16, 3);
+    spi.frequency(1000000);
+    spi_ss[0]=spi_ss[1]=spi_ss[2]=spi_ss[3]=1;
+    
+    //motor
+    motor.baud(115200);                             //ボーレート設定
+    motor.printf("1F0002F0003F0004F000\r\n");       //モータ停止
+    //compass
+    hmc_reset=HMC_RUN;
+    /*for(int i=0; i<5; i++){
+        ReadCmps();
+        cmps_set.CmpsInitialValue = cmps_set.cmps;
+        wait_ms(10);
+    }
+    cmps_set.CmpsDiff = REFERENCE - cmps_set.CmpsInitialValue;*/
+    for(int i=0; i<5; i++){
+        ReadCmps();
+        cmps_set.CmpsInitialValue = cmps_set.cmps;
+        cmps_set.CmpsInitialValue0 = cmps_set.cmps;
+        wait_ms(10);
+    }
+    cmps_set.CmpsDiff = REFERENCE - cmps_set.cmps;
+    
+    cmps_set.FrontDeg=0;
+    cmps_set.AtkDeg=0;
+    
+    pid.setInputLimits(MINIMUM,MAXIMUM);            //pid sed def
+    pid.setOutputLimits(-OUT_LIMIT, OUT_LIMIT);     //pid sed def
+    pid.setBias(PID_BIAS);                          //pid sed def
+    pid.setMode(AUTO_MODE);                         //pid sed def
+    pid.setSetPoint(REFERENCE);                     //pid sed def
+    //pidupdate.attach(&PidUpdate, PID_CYCLE);
+}
+void SetUp2(void){//スタートした時の処理
+     __enable_irq(); // 許可
+     
+    sys.KickOffFlag=1;
+    SetKick();
+    SetPidAndMotor();
+    SetInfo();
+    SetLine();
+}
+void StopProcess(void){//コマンドに戻るときの処理
+
+    sys.KickOffFlag=0;
+    SetKick();
+    SetPidAndMotor();
+    SetInfo();
+    SetLine();
+    
+    __disable_irq(); // 禁止
+    __enable_irq(); // 許可
+    Sw_ticker.attach(Sw_sample, 0.050);
+}
+
+void SetKick(void){
+    if(sys.KickOffFlag==1){
+        kicker=0;
+        ValidSolenoid();
+        BallChecker.fall(&DriveSolenoidJudge);
+    }
+    else{
+        kicker=1;
+        wait(0.25);
+        kicker=0;
+    }
+}
+void SetPidAndMotor(void){
+    if(sys.KickOffFlag==1){
+        //compass
+        ValidTurn();
+        hmc_reset=HMC_RUN;
+        if(sys.TurnStartFlag==1){
+            //正...右回転
+            //負...左回転
+            //cmps_set.FrontDeg=-180;
+            //cmps_set.FrontDeg=179;
+            //cmps_set.FrontDeg=180;
+            //cmps_set.CmpsDiff = REFERENCE - cmps_set.CmpsInitialValue;
+            
+            /*for(int i=0; i<5; i++){
+                ReadCmps();
+                cmps_set.CmpsInitialValue2 = cmps_set.cmps;
+                wait_ms(10);
+            }*/
+            //cmps_set.CmpsDiff = REFERENCE - cmps_set.CmpsInitialValue2;
+            
+            cmps_set.FrontDeg=-180;//-(cmps_set.CmpsInitialValue2-cmps_set.CmpsInitialValue0);
+        }
+        else{
+            for(int i=0; i<5; i++){
+                ReadCmps();
+                cmps_set.CmpsInitialValue = cmps_set.cmps;
+                wait_ms(10);
+            }
+            cmps_set.CmpsDiff = REFERENCE - cmps_set.cmps;
+            
+            
+            cmps_set.FrontDeg=0;
+        }
+        Motor_ticker.attach(&ValidTx_motor, 0.020);
+        //pidupdate.attach(&ValidPidUpdate, PID_CYCLE);
+    }
+    else{
+        //pidupdate.detach();
+        Motor_ticker.detach();
+        ////Hmc_ticker.detach();
+        motor.printf("1F0002F0003F0004F000\r\n");       //モータ停止
+        move(0,0,0);
+        cmps_set.OutputPID=0;
+        cmps_set.InputPID=REFERENCE;
+        HmcReset();
+    }
+}
+void SetInfo(void){
+    if(sys.KickOffFlag==1){
+        Info_ticker.attach(&ValidInfo, 0.050);
+    }
+    else{
+        Info_ticker.detach();
+    }
+}
+void SetLine(void){
+    if(sys.KickOffFlag==1){
+        //Line_ticker.attach(&ReadLine, 0.005);
+        /*Line[A_SPOT].rise(&LineCall_A);
+        Line[B_SPOT].rise(&LineCall_B);
+        Line[C_SPOT].rise(&LineCall_C);*/
+        /*
+        LineHolding[A_SPOT].rise(&LineRanking_A);
+        LineHolding[B_SPOT].rise(&LineRanking_B);
+        LineHolding[C_SPOT].rise(&LineRanking_C);
+        */
+        /*
+        Line[A_SPOT].rise(&LineRawCall_A);
+        Line[B_SPOT].rise(&LineRawCall_B);
+        Line[C_SPOT].rise(&LineRawCall_C);
+        */
+        
+        Line[A_SPOT].rise(&LineRawRanking_A);
+        Line[B_SPOT].rise(&LineRawRanking_B);
+        Line[C_SPOT].rise(&LineRawRanking_C);
+    }
+    else{
+        ////Line_ticker.detach();
+    }
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/main_processing/setup_command_active/setup.h	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,15 @@
+#ifndef _SETUP_H_
+#define _SETUP_H_
+
+void SetUp(void);//電源を入れた時の処理
+void SetUp2(void);//スタートした時の処理
+void StopProcess(void);//コマンドに戻るときの処理
+
+void SetKick(void);
+void SetPidAndMotor(void);
+void SetIr(void);
+void SetPing(void);
+void SetInfo(void);
+void SetLine(void);
+
+#endif //_SETUP_H_
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/main_processing/strategy/LineProcess.cpp	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,1201 @@
+#include "mbed.h"
+#include "extern.h"
+
+void LineJudgeSlow(double pow_x, double pow_y, double *x, double *y){
+    uint8_t LineState;
+    uint8_t LineSum;
+    
+    //line
+    LineState = 0;
+    
+    LineSum = ((data.lnHold>>2)&0x1)+((data.lnHold>>1)&0x1)+((data.lnHold>>0)&0x1);
+    if((LineSum==3)||(data.FieldSpot==LINE_OUTSIDE)){
+        LineState = 3;
+    }
+    else if(LineSum==2){
+        LineState = 2;
+    }
+    else if(LineSum==1){
+        LineState = 1;
+    }
+    else if(LineSum==0){
+        LineState = 0;
+    }
+    
+    
+    if(pow_x>=0){
+        if(data.ping[R_PING]<WhiteToWall[X_PING]) (*x)=LineDecline[LineState];
+        else *x=1;
+    }
+    else{
+        if(data.ping[L_PING]<WhiteToWall[X_PING]) (*x)=LineDecline[LineState];
+        else *x=1;
+    }
+    
+    if(pow_y>=0){
+        if(data.ping[F_PING]<WhiteToWall[Y_PING]) (*y)=LineDecline[LineState];
+        else *y=1;
+    }
+    else{
+        if(data.ping[B_PING]<WhiteToWall[Y_PING]) (*y)=LineDecline[LineState];
+        else *y=1;
+    }
+}
+void LineJudgeSlow2(double pow_x, double pow_y, double *x, double *y, uint8_t *px, uint8_t *py){
+    uint8_t LineState;
+    uint8_t LineSum;
+    
+    //line
+    LineState = 0;
+    
+    LineSum = (data.lnRawOrder[0]!=LINE_EMPTY)+(data.lnRawOrder[1]!=LINE_EMPTY)+(data.lnRawOrder[2]!=LINE_EMPTY);
+    if(LineSum==3){
+        LineState = 3;
+    }
+    else if(LineSum==2){
+        LineState = 2;
+    }
+    else if(LineSum==1){
+        LineState = 1;
+    }
+    else if(LineSum==0){
+        LineState = 0;
+    }
+    
+    if(LineSum>0){
+        if(pow_x>=0){
+            if((data.ping[R_PING]<WhiteToWall[X_PING])&&((*px)>LineDecrease[LineState])) (*px)=LineDecrease[LineState];
+        }
+        else{
+            if((data.ping[L_PING]<WhiteToWall[X_PING])&&((*px)>LineDecrease[LineState])) (*px)=LineDecrease[LineState];
+        }
+        
+        if(pow_y>=0){
+            if((data.ping[F_PING]<WhiteToWall[Y_PING])&&((*py)>LineDecrease[LineState])) (*py)=LineDecrease[LineState];
+        }
+        else{
+            if((data.ping[B_PING]<WhiteToWall[Y_PING])&&((*py)>LineDecrease[LineState])) (*py)=LineDecrease[LineState];
+        }
+    }
+    else if(LineSum==0){
+        ////超音波による減速
+        if(pow_x>=0){
+            if((data.ping[R_PING]<GoalEdgeToWall[X_PING])&&((*px)>LineDecrease[LineState])) (*px)=LineDecrease[LineState];
+        }
+        else{
+            if((data.ping[L_PING]<GoalEdgeToWall[X_PING])&&((*px)>LineDecrease[LineState])) (*px)=LineDecrease[LineState];
+        }
+        
+        if(pow_y>=0){
+            //if((data.ping[F_PING]<15)&&((*py)>LineDecrease[LineState])) (*py)=LineDecrease[LineState];
+        }
+        else{
+            if((data.ping[B_PING]<15)&&((*py)>LineDecrease[LineState])) (*py)=LineDecrease[LineState];
+        }
+    }
+    
+    if((data.lnStayNow[X_LINE]==1)&&((*px)>15)){
+        (*px)=15;
+    }
+    if((data.lnStayNow[Y_LINE]==1)&&((*py)>15)){
+        (*py)=15;
+    }
+    
+    ////超音波による減速
+    if(pow_x>=0){
+        if((data.ping[R_PING]<GoalEdgeToWall[X_PING])&&((*px)>20)){
+            (*px)=20;
+            if((*py)>30) (*py)=30;
+        }
+    }
+    else{
+        if((data.ping[L_PING]<GoalEdgeToWall[X_PING])&&((*px)>20)){
+            (*px)=20;
+            if((*py)>30) (*py)=30;
+        }
+    }
+    
+    if(pow_y>=0){
+        if((data.ping[F_PING]<WhiteToWallPlus[Y_PING])&&((*py)>25)) (*py)=25;
+    }
+    else{
+        if((data.ping[B_PING]<WhiteToWallPlus[Y_PING])&&((*py)>25)) (*py)=25;
+    }
+    
+    *x=1;
+    *y=1;
+}
+void LineJudgeReturn(double pow_x, double pow_y, double *x, double *y){
+    const int8_t static LineReturn[5] = {0, 0, 0, 0, 20};
+    uint8_t LinePingState[4];
+    //◎ボールを追う力とラインから離れる力の向きが違うならばラインから離れる力が優先される.
+    //◎ボールを追う力とラインから離れる力の向きが同じならばボールを追う力が優先される.
+    //◎ラインセンサ全てが場外になるまではボールを追う力は作用しない.ボールを追う力は場内に出るまで作用する.
+    //×ラインのほぼ場外では常時ラインから離れる力が優先される.
+    //※場外判定を行うには再び場内に戻る必要がある.
+    
+    if(data.FieldSpot==LINE_OUTSIDE){
+        
+        LinePingState[L_PING]=(data.ping[L_PING]<WhiteToWall[X_PING]);
+        LinePingState[R_PING]=(data.ping[R_PING]<WhiteToWall[X_PING]);
+        LinePingState[F_PING]=(data.ping[F_PING]<WhiteToWall[Y_PING]);
+        LinePingState[B_PING]=(data.ping[B_PING]<WhiteToWall[Y_PING]);
+        
+        //line間際の復帰力以外の力を作用させるか否か
+        data.lnStop[X_LINE]=1;
+        data.lnStop[Y_LINE]=1;
+        
+        data.ReturnDir[X_LINE]=LINE_EMPTY;
+        data.ReturnDir[Y_LINE]=LINE_EMPTY;
+        
+        //x
+        if(data.ReturnDir[X_LINE]==L_LINE){
+            if(pow_x<0){
+              *x = 0;
+              data.lnStop[X_LINE]=1;
+            }
+            else{
+              *x = -LineReturn[4];
+              data.lnStop[X_LINE]=0;
+            }
+        }
+        else if(data.ReturnDir[X_LINE]==R_LINE){
+            if(pow_x>0){
+              *x = 0;
+              data.lnStop[X_LINE]=1;
+            }
+            else{
+              *x = LineReturn[4];
+              data.lnStop[X_LINE]=0;
+            }
+        }
+        else if(data.ReturnDir[X_LINE]==LINE_EMPTY){
+            if((LinePingState[L_PING]==0)&&(LinePingState[R_PING]==0)){
+                /*if(pow_x>0){
+                  *x = -pow_x*(1-0.75);
+                }
+                else{
+                  *x = pow_x*(1-0.75);
+                }*/
+                data.lnStop[X_LINE]=1;
+            }
+            if((LinePingState[L_PING]==0)&&(LinePingState[R_PING]==1)){
+                
+                data.ReturnDir[X_LINE]=L_LINE;
+                
+                /*if(pow_x<0){
+                  *x = 0;
+                  data.lnStop[X_LINE]=1;
+                }
+                else{
+                  *x = -LineReturn[4];
+                  data.lnStop[X_LINE]=0;
+                }*/
+                *x = -LineReturn[4];
+                data.lnStop[X_LINE]=0;
+            }
+            if((LinePingState[L_PING]==1)&&(LinePingState[R_PING]==0)){
+                
+                data.ReturnDir[X_LINE]=R_LINE;
+                
+                /*if(pow_x>0){
+                  *x = 0;
+                  data.lnStop[X_LINE]=1;
+                }
+                else{
+                  *x = LineReturn[4];
+                  data.lnStop[X_LINE]=0;
+                }*/
+                *x = LineReturn[4];
+                data.lnStop[X_LINE]=0;
+            }
+            if((LinePingState[L_PING]==1)&&(LinePingState[R_PING]==1)){
+                
+                if(
+                    (data.lnOrder[0]==A_SPOT)&&(data.lnOrder[1]==C_SPOT)&&(data.lnOrder[2]==B_SPOT)
+                ){
+                    *x = -LineReturn[4];
+                    data.lnStop[X_LINE]=0;
+                }
+                else if(
+                    (data.lnOrder[0]==B_SPOT)&&(data.lnOrder[1]==C_SPOT)&&(data.lnOrder[2]==A_SPOT)
+                ){
+                    *x = LineReturn[4];
+                    data.lnStop[X_LINE]=0;
+                }
+                else{
+                    *x = 0;
+                    data.lnStop[X_LINE]=0;
+                }
+            }
+        }
+        //y
+        if(data.ReturnDir[Y_LINE]==F_LINE){
+            if(pow_y>0){
+              *y = 0;
+              data.lnStop[Y_LINE]=1;
+            }
+            else{
+              *y = LineReturn[4];
+              data.lnStop[Y_LINE]=0;
+            }
+        }
+        else if(data.ReturnDir[Y_LINE]==B_LINE){
+            if(pow_y<0){
+              *y = 0;
+              data.lnStop[Y_LINE]=1;
+            }
+            else{
+              *y = -LineReturn[4];
+              data.lnStop[Y_LINE]=0;
+            }
+        }
+        else if(data.ReturnDir[Y_LINE]==LINE_EMPTY){
+            if((LinePingState[B_PING]==0)&&(LinePingState[F_PING]==0)){
+                /*if(pow_y>0){
+                  *y = -pow_y*(1-0.75);
+                }
+                else{
+                  *y = pow_y*(1-0.75);
+                }*/
+                data.lnStop[Y_LINE]=1;
+            }
+            if((LinePingState[B_PING]==0)&&(LinePingState[F_PING]==1)){
+                
+                data.ReturnDir[Y_LINE]=B_LINE;
+                
+                if(pow_y<0){
+                  *y = 0;
+                  data.lnStop[Y_LINE]=1;
+                }
+                else{
+                  *y = -LineReturn[4];
+                  data.lnStop[Y_LINE]=0;
+                }
+            }
+            if((LinePingState[B_PING]==1)&&(LinePingState[F_PING]==0)){
+                
+                data.ReturnDir[Y_LINE]=F_LINE;
+                
+                if(pow_y>0){
+                  *y = 0;
+                  data.lnStop[Y_LINE]=1;
+                }
+                else{
+                  *y = LineReturn[4];
+                  data.lnStop[Y_LINE]=0;
+                }
+            }
+            if((LinePingState[B_PING]==1)&&(LinePingState[F_PING]==1)){
+                if(
+                    (data.lnOrder[0]==C_SPOT)&&(data.lnOrder[1]==A_SPOT)&&(data.lnOrder[2]==B_SPOT)||
+                    (data.lnOrder[0]==C_SPOT)&&(data.lnOrder[1]==B_SPOT)&&(data.lnOrder[2]==A_SPOT)
+                ){
+                    *y = LineReturn[4];
+                    data.lnStop[Y_LINE]=0;
+                }
+                else if(
+                    (data.lnOrder[0]==A_SPOT)&&(data.lnOrder[1]==B_SPOT)&&(data.lnOrder[2]==C_SPOT)||
+                    (data.lnOrder[0]==B_SPOT)&&(data.lnOrder[1]==A_SPOT)&&(data.lnOrder[2]==C_SPOT)
+                ){
+                    *y = -LineReturn[4];
+                    data.lnStop[Y_LINE]=0;
+                }
+                else{
+                    *y = 0;
+                    data.lnStop[Y_LINE]=0;
+                }
+            }
+        }
+        //none
+        if((LinePingState[L_PING]==1)&&(LinePingState[R_PING]==1)&&(LinePingState[F_PING]==1)&&(LinePingState[B_PING]==1)){
+            //turn!
+        }
+        
+    }
+    else{//data.FieldSpot==LINE_INSIDE
+    
+        data.ReturnDir[X_LINE]=LINE_EMPTY;
+        data.ReturnDir[Y_LINE]=LINE_EMPTY;
+        
+        *x = 0;
+        *y = 0;
+        
+        //line間際の復帰力以外の力を作用させるか否か
+        data.lnStop[X_LINE]=1;
+        data.lnStop[Y_LINE]=1;
+       /* 
+        if(
+            (data.lnRawMemory[A_SPOT]==1)&&
+            (data.lnRawMemory[B_SPOT]==1)&&
+            (data.lnRawMemory[C_SPOT]==0)
+        ){
+            data.lnStop[Y_LINE]=0;
+            *y = -LineReturn[4];
+        }
+        else if(
+            (data.lnRawMemory[A_SPOT]==0)&&
+            (data.lnRawMemory[B_SPOT]==0)&&
+            (data.lnRawMemory[C_SPOT]==1)
+        ){
+            data.lnStop[Y_LINE]=0;
+            *y = LineReturn[4];
+        }*/
+    }
+}
+void LineJudgeReturn2(double pow_x, double pow_y, double *x, double *y){
+    const int8_t static LineReturn[5] = {0, 0, 0, 0, 20};
+    uint8_t LinePingState[4];
+    //JSO2
+    static uint8_t lnRawReturn1 = 0;
+    //◎ボールを追う力とラインから離れる力の向きが違うならばラインから離れる力が優先される.
+    //◎ボールを追う力とラインから離れる力の向きが同じならばボールを追う力が優先される.
+    //◎ラインセンサ全てが場外になるまではボールを追う力は作用しない.ボールを追う力は場内に出るまで作用する.
+    //×ラインのほぼ場外では常時ラインから離れる力が優先される.
+    //※場外判定を行うには再び場内に戻る必要がある.
+    
+    data.FieldSpot=LINE_INSIDE;
+    
+    if(data.FieldSpot==LINE_OUTSIDE){
+    }
+    else{//data.FieldSpot==LINE_INSIDE
+    
+        data.ReturnDir[X_LINE]=LINE_EMPTY;
+        data.ReturnDir[Y_LINE]=LINE_EMPTY;
+        
+        *x = 0;
+        *y = 0;
+        
+        //line間際の復帰力以外の力を作用させるか否か
+        data.lnStop[X_LINE]=1;
+        data.lnStop[Y_LINE]=1;
+        
+        if(//y
+            ((data.lnRawOrder[0]==A_SPOT)&&(data.lnRawOrder[1]==B_SPOT)&&(1))||
+            ((data.lnRawOrder[0]==B_SPOT)&&(data.lnRawOrder[1]==A_SPOT)&&(1))
+        ){
+            data.lnStop[Y_LINE]=0;
+            *y = -LineReturn[4];
+            //JSO1
+            if(
+                (data.ping[F_PING]<45)&&
+                (data.lnRawReturn==1)//JSO2
+            ){
+                data.lnStop[X_LINE]=0;
+            }
+            //JSO2
+            if(
+                (
+                    ((Line[A_SPOT].read()==1)&&(Line[B_SPOT].read()==0))||
+                    ((LineHolding[A_SPOT].read()==1)&&(LineHolding[B_SPOT].read()==0))
+                )&&
+                (data.ping[F_PING]>45)&&
+                (data.ping[F_PING]<200)&&
+                (data.ping[R_PING]<25)&&
+                (data.ping[L_PING]>40)
+            ){
+                *x = -LineReturn[4];
+                data.lnStop[X_LINE]=0;
+            }
+            if(
+                (
+                    ((Line[A_SPOT].read()==0)&&(Line[B_SPOT].read()==1))||
+                    ((LineHolding[A_SPOT].read()==0)&&(LineHolding[B_SPOT].read()==1))
+                )&&
+                (data.ping[F_PING]>45)&&
+                (data.ping[F_PING]<200)&&
+                (data.ping[L_PING]<25)&&
+                (data.ping[R_PING]>40)
+            ){
+                *x = LineReturn[4];
+                data.lnStop[X_LINE]=0;
+            }
+        }
+        else if(
+            ((data.lnRawOrder[0]==C_SPOT)&&(1)&&(1))
+        ){
+            data.lnStop[Y_LINE]=0;
+            *y = LineReturn[4];
+            
+            //JSO1
+            if(
+                (data.ping[B_PING]<45)&&
+                (data.lnRawReturn==1)
+            ){
+                data.lnStop[X_LINE]=0;
+            }
+        }
+        else if(//x
+            ((data.lnRawOrder[0]==A_SPOT)&&(data.lnRawOrder[1]==C_SPOT)&&(1))
+        ){
+            *x = -LineReturn[4];
+            data.lnStop[X_LINE]=0;
+        }
+        else if(
+            ((data.lnRawOrder[0]==B_SPOT)&&(data.lnRawOrder[1]==C_SPOT)&&(1))
+        ){
+            *x = LineReturn[4];
+            data.lnStop[X_LINE]=0;
+        }
+        
+        if(
+            ((*x)!=0)||
+            ((*y)!=0)
+        ){
+            
+            data.lnRawReturn=1;
+            
+            LinePingState[L_PING]=(data.ping[L_PING]<WhiteToWallPlus[X_PING]);
+            LinePingState[R_PING]=(data.ping[R_PING]<WhiteToWallPlus[X_PING]);
+            LinePingState[F_PING]=(data.ping[F_PING]<WhiteToWallPlus[Y_PING]);
+            LinePingState[B_PING]=(data.ping[B_PING]<WhiteToWallPlus[Y_PING]);
+            //x
+            if(data.lnStop[X_LINE]==1){
+                if((LinePingState[L_PING]==0)&&(LinePingState[R_PING]==1)){
+                    *x = -LineReturn[4];
+                    data.lnStop[X_LINE]=0;
+                }
+                if((LinePingState[L_PING]==1)&&(LinePingState[R_PING]==0)){
+                    *x = LineReturn[4];
+                    data.lnStop[X_LINE]=0;
+                }
+                if((LinePingState[L_PING]==1)&&(LinePingState[R_PING]==1)){
+                    *x = 0;
+                    data.lnStop[X_LINE]=0;
+                }
+            }
+            //y
+            if(data.lnStop[Y_LINE]==1){
+                if((LinePingState[B_PING]==0)&&(LinePingState[F_PING]==1)){
+                    if(pow_y<0){
+                      *y = 0;
+                      data.lnStop[Y_LINE]=1;
+                    }
+                    else{
+                      *y = -LineReturn[4];
+                      data.lnStop[Y_LINE]=0;
+                    }
+                }
+                //JSO2
+                if((LineHolding[A_SPOT].read()==1)&&(LineHolding[B_SPOT].read()==1)&&(LineHolding[C_SPOT].read()==0)&&(data.lnRawReturn==1)){
+                    *y = -LineReturn[4];
+                    data.lnStop[Y_LINE]=0;
+                }
+                
+                if((LinePingState[B_PING]==1)&&(LinePingState[F_PING]==0)){
+                    if(pow_y>0){
+                      *y = 0;
+                      data.lnStop[Y_LINE]=1;
+                    }
+                    else{
+                      *y = LineReturn[4];
+                      data.lnStop[Y_LINE]=0;
+                    }
+                }
+                if((LinePingState[B_PING]==1)&&(LinePingState[F_PING]==1)){
+                    *y = 0;
+                    data.lnStop[Y_LINE]=0;
+                }
+            }
+        }
+        else{
+            data.lnRawReturn=0;
+            
+            //JSO3
+            if((data.lnOrder[0]==A_SPOT)&&(data.lnOrder[1]==LINE_EMPTY)&&(pow_x>0)){
+                data.lnStop[X_LINE]=0;
+            }
+            if((data.lnOrder[0]==B_SPOT)&&(data.lnOrder[1]==LINE_EMPTY)&&(pow_x<0)){
+                data.lnStop[X_LINE]=0;
+            }
+            //JSO3
+            if((Line[C_SPOT].read()==1)&&(1)&&(pow_y>0)){
+                data.lnStop[Y_LINE]=0;
+            }
+        }
+        //JSO3
+        if((Line[C_SPOT].read()==1)&&(1)&&(pow_y>0)){
+            data.lnStop[Y_LINE]=0;
+        }
+        //JSO1
+        if(data.lnRawReturn==1){
+            //JSO2
+            if((lnRawReturn1==0)){
+                LineLiberate();
+                lnRawReturn1=1;
+            }
+            
+            if(
+                (
+                    ((data.lnRawOrder[0]==A_SPOT)&&(data.lnRawOrder[1]==C_SPOT)&&(1))||
+                    ((data.lnRawOrder[0]==B_SPOT)&&(data.lnRawOrder[1]==C_SPOT)&&(1))
+                )&&
+                //((Line[A_SPOT].read()==1)&&(Line[B_SPOT].read()==1))&&//JSO1
+                ((LineHolding[A_SPOT].read()==1)&&(LineHolding[B_SPOT].read()==1))&&//JSO2
+                ((data.ping[F_PING]<45)&&(1))&&//JSO2
+                //(!((data.ping[B_PING]<40)&&(data.ping[B_PING]>25)))&&//JSO2
+                ((data.lnRawOrder[0]!=C_SPOT)&&(data.lnRawOrderLog1[0]!=C_SPOT)&&(data.lnRawOrderLog2[0]!=C_SPOT))
+                
+            ){
+                *y = -LineReturn[4];
+                data.lnStop[Y_LINE]=0;//JSO2
+            }
+        }
+        else{
+            lnRawReturn1=0;
+            
+            
+            if((LinePingState[L_PING]==0)&&(LinePingState[R_PING]==1)){
+                *x = -LineReturn[4];
+                data.lnStop[X_LINE]=0;
+            }
+            if((LinePingState[L_PING]==1)&&(LinePingState[R_PING]==0)){
+                *x = LineReturn[4];
+                data.lnStop[X_LINE]=0;
+            }
+            
+        }
+        
+    }
+}
+void LineJudgeReset(double pow_x, double pow_y, double *x, double *y){
+    //static uint8_t NewLineCorner[4]={LINE_EMPTY, LINE_EMPTY, LINE_EMPTY, LINE_EMPTY};
+    //static uint8_t LastLineCorner[4]={LINE_EMPTY, LINE_EMPTY, LINE_EMPTY, LINE_EMPTY};
+    static uint8_t NewLineCorner[4]={LINE_EMPTY, LINE_EMPTY, LINE_EMPTY, LINE_EMPTY};
+    static uint8_t LastLineCorner[4]={LINE_EMPTY, LINE_EMPTY, LINE_EMPTY, LINE_EMPTY};
+    
+    if((/*data.lnRaw==0*/1)&&(data.lnHold==7)){
+        if(data.FieldSpot==LINE_INSIDE){
+            
+            data.lnCorner[L_LINE] = (data.ping[L_PING]<OutToWall[X_PING]);
+            data.lnCorner[R_LINE] = (data.ping[R_PING]<OutToWall[X_PING]);
+            data.lnCorner[F_LINE] = (data.ping[F_PING]<OutToWall[Y_PING]);
+            data.lnCorner[B_LINE] = (data.ping[B_PING]<OutToWall[Y_PING]);
+            if(
+                (data.lnCorner[L_LINE])||
+                (data.lnCorner[R_LINE])||
+                (data.lnCorner[F_LINE])||
+                (data.lnCorner[B_LINE])
+            ){
+                
+                data.NonWall[L_LINE] = (data.ping[L_PING]>WhiteToWall[X_PING]);
+                data.NonWall[R_LINE] = (data.ping[R_PING]>WhiteToWall[X_PING]);
+                data.NonWall[F_LINE] = (data.ping[F_PING]>WhiteToWall[Y_PING]);
+                data.NonWall[B_LINE] = (data.ping[B_PING]>WhiteToWall[Y_PING]);
+                
+                
+                
+                ///*
+                LastLineCorner[L_LINE]=NewLineCorner[L_LINE];
+                LastLineCorner[R_LINE]=NewLineCorner[R_LINE];
+                LastLineCorner[F_LINE]=NewLineCorner[F_LINE];
+                LastLineCorner[B_LINE]=NewLineCorner[B_LINE];
+                
+                NewLineCorner[L_LINE]=data.lnCorner[L_LINE];
+                NewLineCorner[R_LINE]=data.lnCorner[R_LINE];
+                NewLineCorner[F_LINE]=data.lnCorner[F_LINE];
+                NewLineCorner[B_LINE]=data.lnCorner[B_LINE];
+                
+                if(
+                    (LastLineCorner[L_LINE]==NewLineCorner[L_LINE])&&
+                    (LastLineCorner[R_LINE]==NewLineCorner[R_LINE])&&
+                    (LastLineCorner[F_LINE]==NewLineCorner[F_LINE])&&
+                    (LastLineCorner[B_LINE]==NewLineCorner[B_LINE])
+                ){
+                    data.lnRepeat++;
+                }
+                else{
+                    data.lnRepeat=0;
+                }
+                //*/
+                
+                data.FieldSpot = LINE_OUTSIDE;
+                LineLiberate();
+            }
+        }
+        else if(data.FieldSpot==LINE_OUTSIDE){
+            if(data.lnRaw==0){
+                data.FieldSpot = LINE_INSIDE;
+                data.NonWall[L_LINE] = data.NonWall[R_LINE] = data.NonWall[F_LINE] = data.NonWall[B_LINE] = 0;
+                LineLiberate();
+                LineRankClear();
+            }
+        }
+    }
+    if(data.FieldSpot == LINE_OUTSIDE){
+        if(
+            (
+                (data.ping[L_PING]>=WhiteToWall[X_PING])||
+                (data.NonWall[L_LINE]==1)||
+                ((data.lnOrder[0]==A_SPOT)&&(data.lnOrder[1]==C_SPOT))
+                //(data.lnOrder[0]==A_SPOT)
+            )&&
+            (
+                (data.ping[R_PING]>=WhiteToWall[X_PING])||
+                (data.NonWall[R_LINE]==1)||
+                ((data.lnOrder[0]==B_SPOT)&&(data.lnOrder[1]==C_SPOT))
+                //(data.lnOrder[0]==B_SPOT)
+            )&&
+            (
+                (data.ping[F_PING]>=WhiteToWall[Y_PING])||
+                (data.NonWall[F_LINE]==1)||
+                ((data.lnOrder[0]==C_SPOT)&&(data.lnOrder[1]==A_SPOT))||
+                ((data.lnOrder[0]==C_SPOT)&&(data.lnOrder[1]==B_SPOT))
+            )&&
+                ((data.ping[B_PING]>=WhiteToWall[Y_PING])||
+                (data.NonWall[B_LINE]==1)||
+                ((data.lnOrder[0]==A_SPOT)&&(data.lnOrder[1]==B_SPOT))||
+                ((data.lnOrder[0]==B_SPOT)&&(data.lnOrder[1]==A_SPOT))
+            )
+        ){
+            data.FieldSpot = LINE_INSIDE;
+            data.NonWall[L_LINE] = data.NonWall[R_LINE] = data.NonWall[F_LINE] = data.NonWall[B_LINE] = 0;
+            LineLiberate();
+            LineRankClear();
+        }
+    }
+    if((data.FieldSpot == LINE_INSIDE)&&(0<data.lnHold)&&(data.lnHold<7)&&(data.lnRaw==0)){
+        if(
+            (
+                (
+                    (data.ping[L_PING]>=WhiteToWall[X_PING])||
+                    ((data.lnOrder[0]==A_SPOT)&&(data.lnOrder[1]==C_SPOT))
+                    //(data.lnOrder[0]==A_SPOT)
+                )&&
+                (
+                    (data.ping[R_PING]>=WhiteToWall[X_PING])||
+                    ((data.lnOrder[0]==B_SPOT)&&(data.lnOrder[1]==C_SPOT))
+                    //(data.lnOrder[0]==B_SPOT)
+                )&&
+                (
+                    (data.ping[F_PING]>=WhiteToWall[Y_PING])||
+                    ((data.lnOrder[0]==C_SPOT)&&(data.lnOrder[1]==A_SPOT))||
+                    ((data.lnOrder[0]==C_SPOT)&&(data.lnOrder[1]==B_SPOT))
+                )&&
+                (
+                    (data.ping[B_PING]>=WhiteToWall[Y_PING])||
+                    ((data.lnOrder[0]==A_SPOT)&&(data.lnOrder[1]==B_SPOT))||
+                    ((data.lnOrder[0]==B_SPOT)&&(data.lnOrder[1]==A_SPOT))
+                )
+            )
+            ||
+            (
+                (data.ping[L_PING]>=GoalEdgeToWall[X_PING])&&
+                (data.ping[R_PING]>=GoalEdgeToWall[X_PING])
+            )
+        ){
+            data.NonWall[L_LINE] = data.NonWall[R_LINE] = data.NonWall[F_LINE] = data.NonWall[B_LINE] = 0;
+            LineLiberate();
+        }
+    }
+    ///*
+    if(
+        (data.irNotice==IR_NONE)||
+        (data.irNotice==IR_FAR)||
+        (
+            (data.ping[L_PING]>=GoalEdgeToWall[X_PING])&&
+            (data.ping[R_PING]>=GoalEdgeToWall[X_PING])
+        )
+    ){
+        data.lnRepeat = 0;
+        
+        NewLineCorner[L_LINE]=LINE_EMPTY;
+        NewLineCorner[R_LINE]=LINE_EMPTY;
+        NewLineCorner[F_LINE]=LINE_EMPTY;
+        NewLineCorner[B_LINE]=LINE_EMPTY;
+        
+        LastLineCorner[L_LINE]=LINE_EMPTY;
+        LastLineCorner[R_LINE]=LINE_EMPTY;
+        LastLineCorner[F_LINE]=LINE_EMPTY;
+        LastLineCorner[B_LINE]=LINE_EMPTY;
+    }
+    //data.lnRepeat=0;
+    if((data.lnRepeat>0)&&(data.FieldSpot == LINE_INSIDE)){
+        //x
+        if(
+            ((pow_x>=0)&&(NewLineCorner[R_LINE]))||
+            ((pow_x<0)&&(NewLineCorner[L_LINE]))
+        ){
+            data.lnStay[X_LINE]=0;
+        }
+        else{
+            data.lnStay[X_LINE]=1;
+        }
+        //y
+        if(
+            ((pow_y>=0)&&(NewLineCorner[F_LINE]))||
+            ((pow_y<0)&&(NewLineCorner[B_LINE]))
+        ){
+            data.lnStay[Y_LINE]=0;
+        }
+        else{
+            data.lnStay[Y_LINE]=1;
+        }
+    }
+    else{
+        data.lnStay[X_LINE]=data.lnStay[Y_LINE]=1;
+    }
+    //*/
+    
+}
+void LineJudgeReset2(double pow_x, double pow_y, double *x, double *y){
+    
+    if(data.lnRepeat==0){
+        data.lnStayNow[X_LINE]=0;
+        data.lnStayNow[Y_LINE]=0;
+    }
+    data.lnStay[X_LINE]=1;
+    data.lnStay[Y_LINE]=1;
+    
+    if((data.irNotice==IR_FAR)&&(data.lnRepeat>1)){
+        data.lnRepeat=1;
+    }
+    
+    if(
+        (data.irNotice==IR_NONE)||
+        //(data.irNotice==IR_FAR)||
+        //(data.irLastPosition<=7)||
+        (
+            (!(
+                (data.irPosition==data.irLastPosition)||
+                (data.irPosition==(ir_posi_s[(data.irLastPosition-8+24+1)%12]))||
+                (data.irPosition==(ir_posi_s[(data.irLastPosition-8+24-1)%12]))||
+                (data.irPosition==(ir_posi_s[(data.irLastPosition-8+24+2)%12]))||
+                (data.irPosition==(ir_posi_s[(data.irLastPosition-8+24-2)%12]))
+                //((data.irPosition==(ir_posi_s[(data.irLastPosition-8+24+3)%12]))&&(cmps_set.GoalDeg==0))||
+                //((data.irPosition==(ir_posi_s[(data.irLastPosition-8+24-3)%12]))&&(cmps_set.GoalDeg==0))
+            ))&&(
+                (data.irLastNotice==IR_CLOSE)||
+                (data.irLastNotice==IR_CLOSER)
+            )
+        )
+    ){
+        data.lnRepeat = 0;
+        
+        LineRawLogReset();
+    }
+    //data.lnRepeat=0;
+    //if((data.lnRepeat==1)&&((data.lnRawOrder[0]==LINE_EMPTY)&&(data.lnRawOrder[1]==LINE_EMPTY)&&(data.lnRawOrder[2]==LINE_EMPTY))){
+    if(
+        (data.lnRepeat>=1)&&
+        (data.lnRawOrder[0]==LINE_EMPTY)/*&&
+        (
+            (
+                (data.irPosition==data.irLastPosition)||
+                (data.irPosition==(data.irLastPosition+1))||
+                (data.irPosition==(data.irLastPosition-1))||
+                (data.irPosition==(data.irLastPosition+11))||
+                (data.irPosition==(data.irLastPosition-11))
+            )&&
+            (
+                (data.irNotice==IR_CLOSE)||
+                (data.irNotice==IR_CLOSER)
+            )
+        )*/
+    ){
+        //y
+        if(
+            ((pow_y>0)&&((data.lnRawOrderLog1[0]==A_SPOT)&&(data.lnRawOrderLog1[1]==B_SPOT)&&(1)))||
+            ((pow_y>0)&&((data.lnRawOrderLog1[0]==B_SPOT)&&(data.lnRawOrderLog1[1]==A_SPOT)&&(1)))
+        ){
+            if(data.ping[F_PING]<WhiteToWallPlus[Y_PING]){
+                data.lnStay[Y_LINE]=0;
+            }
+            else{
+                data.lnStay[Y_LINE]=1;
+            }
+            data.lnStay[Y_LINE]=0;
+            data.lnStayNow[Y_LINE]=1;
+        }
+        else{
+            data.lnStay[Y_LINE]=1;
+        }
+        if(
+            ((pow_y<0)&&((data.lnRawOrderLog1[0]==C_SPOT)&&(1)&&(1)))
+        ){
+            if(data.ping[B_PING]<WhiteToWallPlus[Y_PING]){
+                data.lnStay[Y_LINE]=0;
+            }
+            else{
+                data.lnStay[Y_LINE]=1;
+            }
+            data.lnStay[Y_LINE]=0;
+            data.lnStayNow[Y_LINE]=1;
+        }
+        else{
+            data.lnStay[Y_LINE]=1;
+        }
+        //x
+        if(
+            ((pow_x>0)&&((data.lnRawOrderLog1[0]==A_SPOT)&&(data.lnRawOrderLog1[1]==C_SPOT)&&(1)))
+        ){
+            if(data.ping[R_PING]<WhiteToWallPlus[X_PING]){
+                data.lnStay[X_LINE]=0;
+            }
+            else{
+                data.lnStay[X_LINE]=1;
+            }
+            data.lnStay[X_LINE]=0;
+            data.lnStayNow[X_LINE]=1;
+        }
+        else{
+            data.lnStay[X_LINE]=1;
+        }
+        if(
+            ((pow_x<0)&&((data.lnRawOrderLog1[0]==B_SPOT)&&(data.lnRawOrderLog1[1]==C_SPOT)&&(1)))
+        ){
+            if(data.ping[L_PING]<WhiteToWallPlus[X_PING]){
+                data.lnStay[X_LINE]=0;
+            }
+            else{
+                data.lnStay[X_LINE]=1;
+            }
+            data.lnStay[X_LINE]=0;
+            data.lnStayNow[X_LINE]=1;
+        }
+        else{
+            data.lnStay[X_LINE]=1;
+        }
+        if((data.irNotice==IR_CLOSE)||(data.irNotice==IR_CLOSER)){
+            //y2
+            if((data.lnStay[X_LINE]==1)&&(data.lnStay[Y_LINE]==0)){
+                if( 
+                    ((pow_x>0)&&((data.lnRawOrderLog1[0]==A_SPOT)&&(data.lnRawOrderLog1[1]==B_SPOT))&&((data.irPosition== 9)||(data.irPosition==10)))||
+                    ((pow_x>0)&&((data.lnRawOrderLog1[0]==B_SPOT)&&(data.lnRawOrderLog1[1]==A_SPOT))&&((data.irPosition== 9)||(data.irPosition==10)))||
+                    ((pow_x>0)&&((data.lnRawOrderLog1[0]==C_SPOT)&&(1                             ))&&((data.irPosition==18)||(data.irPosition==19)))
+                ){
+                    if(data.ping[R_PING]<WhiteToWallPlus[X_PING]){
+                        data.lnStay[X_LINE]=0;
+                    }
+                    else{
+                        data.lnStay[X_LINE]=1;
+                    }
+                    if(data.lnRepeat>=LINE_REPEAT){
+                        data.lnStay[X_LINE]=0;
+                    }
+                    data.lnStayNow[X_LINE]=1;
+                }
+                else{
+                    data.lnStay[X_LINE]=1;
+                }
+            }
+            if((data.lnStay[X_LINE]==1)&&(data.lnStay[Y_LINE]==0)){
+                if( 
+                    ((pow_x<0)&&((data.lnRawOrderLog1[0]==A_SPOT)&&(data.lnRawOrderLog1[1]==B_SPOT))&&((data.irPosition==12)||(data.irPosition==13)))||
+                    ((pow_x<0)&&((data.lnRawOrderLog1[0]==B_SPOT)&&(data.lnRawOrderLog1[1]==A_SPOT))&&((data.irPosition==12)||(data.irPosition==13)))||
+                    ((pow_x<0)&&((data.lnRawOrderLog1[0]==C_SPOT)&&(1                             ))&&((data.irPosition==15)||(data.irPosition==16)))
+                ){
+                    if(data.ping[L_PING]<WhiteToWallPlus[X_PING]){
+                        data.lnStay[X_LINE]=0;
+                    }
+                    else{
+                        data.lnStay[X_LINE]=1;
+                    }
+                    if(data.lnRepeat>=LINE_REPEAT){
+                        data.lnStay[X_LINE]=0;
+                    }
+                    data.lnStayNow[X_LINE]=1;
+                }
+                else{
+                    data.lnStay[X_LINE]=1;
+                }
+            }
+            //x2
+            if((data.lnStay[X_LINE]==0)&&(data.lnStay[Y_LINE]==1)){
+                if(
+                    ((pow_y>0)&&((data.lnRawOrderLog1[0]==A_SPOT)&&(data.lnRawOrderLog1[1]==C_SPOT))&&((data.irPosition== 9)||(data.irPosition==10)))||
+                    ((pow_y>0)&&((data.lnRawOrderLog1[0]==B_SPOT)&&(data.lnRawOrderLog1[1]==C_SPOT))&&((data.irPosition==12)||(data.irPosition==13)))
+                ){
+                    if(data.ping[F_PING]<WhiteToWallPlus[Y_PING]){
+                        data.lnStay[Y_LINE]=0;
+                    }
+                    else{
+                        data.lnStay[Y_LINE]=1;
+                    }
+                    if(data.lnRepeat>=LINE_REPEAT){
+                        data.lnStay[Y_LINE]=0;
+                    }
+                    data.lnStayNow[Y_LINE]=1;
+                }
+                else{
+                    data.lnStay[Y_LINE]=1;
+                }
+                
+                if(
+                    ((pow_y<0)&&((data.lnRawOrderLog1[0]==A_SPOT)&&(data.lnRawOrderLog1[1]==C_SPOT))&&((data.irPosition==18)||(data.irPosition==19)))||
+                    ((pow_y<0)&&((data.lnRawOrderLog1[0]==B_SPOT)&&(data.lnRawOrderLog1[1]==C_SPOT))&&((data.irPosition==15)||(data.irPosition==16)))
+                ){
+                    if(data.ping[B_PING]<WhiteToWallPlus[Y_PING]){
+                        data.lnStay[Y_LINE]=0;
+                    }
+                    else{
+                        data.lnStay[Y_LINE]=1;
+                    }
+                    if(data.lnRepeat>=LINE_REPEAT){
+                        data.lnStay[Y_LINE]=0;
+                    }
+                    data.lnStayNow[Y_LINE]=1;
+                }
+                else{
+                    data.lnStay[Y_LINE]=1;
+                }
+            }
+            if(
+                (data.lnRepeat>=2)
+            ){
+                if(
+                    ((pow_y>0)&&((data.ping[F_PING]<40)&&(1)))||
+                    ((pow_y<0)&&((data.ping[B_PING]<40)&&(1)))
+                ){
+                    data.lnStay[Y_LINE]=0;
+                }
+                if(
+                    ((pow_x>0)&&((data.ping[R_PING]<40)&&(1)))||
+                    ((pow_x<0)&&((data.ping[L_PING]<40)&&(1)))
+                ){
+                    data.lnStay[X_LINE]=0;
+                }
+            }
+        }
+        
+        
+    }
+    else{
+        data.lnStay[X_LINE]=data.lnStay[Y_LINE]=1;
+    }
+    
+}
+void LineJudgeReset3(double pow_x, double pow_y, double *x, double *y){
+    
+    if(data.lnRepeat==0){
+        data.lnStayNow[X_LINE]=0;
+        data.lnStayNow[Y_LINE]=0;
+    }
+    data.lnStay[X_LINE]=1;
+    data.lnStay[Y_LINE]=1;
+    
+    if((data.irNotice==IR_FAR)&&(data.lnRepeat>1)){
+        data.lnRepeat=1;
+    }
+    
+    if(
+        (data.irNotice==IR_NONE)||
+        (data.irNotice==IR_FAR)||
+        //(data.irLastPosition<=7)||
+        (
+            (!(
+                (data.irPosition==data.irLastPosition)||
+                (data.irPosition==(ir_posi_s[(data.irLastPosition-8+24+1)%12]))||
+                (data.irPosition==(ir_posi_s[(data.irLastPosition-8+24-1)%12]))
+                //(data.irPosition==(ir_posi_s[(data.irLastPosition-8+24+2)%12]))||
+                //(data.irPosition==(ir_posi_s[(data.irLastPosition-8+24-2)%12]))
+                //((data.irPosition==(ir_posi_s[(data.irLastPosition-8+24+3)%12]))&&(cmps_set.GoalDeg==0))||
+                //((data.irPosition==(ir_posi_s[(data.irLastPosition-8+24-3)%12]))&&(cmps_set.GoalDeg==0))
+            ))&&(
+                (data.irLastNotice==IR_CLOSE)||
+                (data.irLastNotice==IR_CLOSER)
+            )
+        )
+    ){
+        data.lnRepeat = 0;
+        
+        LineRawLogReset();
+    }
+    //data.lnRepeat=0;
+    //if((data.lnRepeat==1)&&((data.lnRawOrder[0]==LINE_EMPTY)&&(data.lnRawOrder[1]==LINE_EMPTY)&&(data.lnRawOrder[2]==LINE_EMPTY))){
+    if(
+        (data.lnRepeat>=1)&&
+        (data.lnRawOrder[0]==LINE_EMPTY)/*&&
+        (
+            (
+                (data.irPosition==data.irLastPosition)||
+                (data.irPosition==(data.irLastPosition+1))||
+                (data.irPosition==(data.irLastPosition-1))||
+                (data.irPosition==(data.irLastPosition+11))||
+                (data.irPosition==(data.irLastPosition-11))
+            )&&
+            (
+                (data.irNotice==IR_CLOSE)||
+                (data.irNotice==IR_CLOSER)
+            )
+        )*/
+    ){
+        //y
+        if(
+            ((pow_y>0)&&((data.lnRawOrderLog1[0]==A_SPOT)&&(data.lnRawOrderLog1[1]==B_SPOT)&&(1)))||
+            ((pow_y>0)&&((data.lnRawOrderLog1[0]==B_SPOT)&&(data.lnRawOrderLog1[1]==A_SPOT)&&(1)))
+        ){
+            if(data.ping[F_PING]<WhiteToWallPlus[Y_PING]){
+                data.lnStay[Y_LINE]=0;
+            }
+            else{
+                data.lnStay[Y_LINE]=1;
+            }
+            data.lnStay[Y_LINE]=0;
+            data.lnStayNow[Y_LINE]=1;
+        }
+        else{
+            data.lnStay[Y_LINE]=1;
+        }
+        if(
+            ((pow_y<0)&&((data.lnRawOrderLog1[0]==C_SPOT)&&(1)&&(1)))
+        ){
+            if(data.ping[B_PING]<WhiteToWallPlus[Y_PING]){
+                data.lnStay[Y_LINE]=0;
+            }
+            else{
+                data.lnStay[Y_LINE]=1;
+            }
+            data.lnStay[Y_LINE]=0;
+            data.lnStayNow[Y_LINE]=1;
+        }
+        else{
+            data.lnStay[Y_LINE]=1;
+        }
+        //x
+        if(
+            ((pow_x>0)&&((data.lnRawOrderLog1[0]==A_SPOT)&&(data.lnRawOrderLog1[1]==C_SPOT)&&(1)))
+        ){
+            if(data.ping[R_PING]<WhiteToWallPlus[X_PING]){
+                data.lnStay[X_LINE]=0;
+            }
+            else{
+                data.lnStay[X_LINE]=1;
+            }
+            data.lnStay[X_LINE]=0;
+            data.lnStayNow[X_LINE]=1;
+        }
+        else{
+            data.lnStay[X_LINE]=1;
+        }
+        if(
+            ((pow_x<0)&&((data.lnRawOrderLog1[0]==B_SPOT)&&(data.lnRawOrderLog1[1]==C_SPOT)&&(1)))
+        ){
+            if(data.ping[L_PING]<WhiteToWallPlus[X_PING]){
+                data.lnStay[X_LINE]=0;
+            }
+            else{
+                data.lnStay[X_LINE]=1;
+            }
+            data.lnStay[X_LINE]=0;
+            data.lnStayNow[X_LINE]=1;
+        }
+        else{
+            data.lnStay[X_LINE]=1;
+        }
+        if((data.irNotice==IR_CLOSE)||(data.irNotice==IR_CLOSER)){
+            //y2
+            if((data.lnStay[X_LINE]==1)&&(data.lnStay[Y_LINE]==0)){
+                if( 
+                    ((pow_x>0)&&((data.lnRawOrderLog1[0]==A_SPOT)&&(data.lnRawOrderLog1[1]==B_SPOT))&&((data.irPosition== 9)||(data.irPosition==10)))||
+                    ((pow_x>0)&&((data.lnRawOrderLog1[0]==B_SPOT)&&(data.lnRawOrderLog1[1]==A_SPOT))&&((data.irPosition== 9)||(data.irPosition==10)))||
+                    ((pow_x>0)&&((data.lnRawOrderLog1[0]==C_SPOT)&&(1                             ))&&((data.irPosition==18)||(data.irPosition==19)))
+                ){
+                    if(data.ping[R_PING]<WhiteToWallPlus[X_PING]){
+                        data.lnStay[X_LINE]=0;
+                    }
+                    else{
+                        data.lnStay[X_LINE]=1;
+                    }
+                    if(data.lnRepeat>=LINE_REPEAT){
+                        data.lnStay[X_LINE]=0;
+                    }
+                    data.lnStayNow[X_LINE]=1;
+                }
+                else{
+                    data.lnStay[X_LINE]=1;
+                }
+            }
+            if((data.lnStay[X_LINE]==1)&&(data.lnStay[Y_LINE]==0)){
+                if( 
+                    ((pow_x<0)&&((data.lnRawOrderLog1[0]==A_SPOT)&&(data.lnRawOrderLog1[1]==B_SPOT))&&((data.irPosition==12)||(data.irPosition==13)))||
+                    ((pow_x<0)&&((data.lnRawOrderLog1[0]==B_SPOT)&&(data.lnRawOrderLog1[1]==A_SPOT))&&((data.irPosition==12)||(data.irPosition==13)))||
+                    ((pow_x<0)&&((data.lnRawOrderLog1[0]==C_SPOT)&&(1                             ))&&((data.irPosition==15)||(data.irPosition==16)))
+                ){
+                    if(data.ping[L_PING]<WhiteToWallPlus[X_PING]){
+                        data.lnStay[X_LINE]=0;
+                    }
+                    else{
+                        data.lnStay[X_LINE]=1;
+                    }
+                    if(data.lnRepeat>=LINE_REPEAT){
+                        data.lnStay[X_LINE]=0;
+                    }
+                    data.lnStayNow[X_LINE]=1;
+                }
+                else{
+                    data.lnStay[X_LINE]=1;
+                }
+            }
+            //x2
+            if((data.lnStay[X_LINE]==0)&&(data.lnStay[Y_LINE]==1)){
+                if(
+                    ((pow_y>0)&&((data.lnRawOrderLog1[0]==A_SPOT)&&(data.lnRawOrderLog1[1]==C_SPOT))&&((data.irPosition== 9)||(data.irPosition==10)))||
+                    ((pow_y>0)&&((data.lnRawOrderLog1[0]==B_SPOT)&&(data.lnRawOrderLog1[1]==C_SPOT))&&((data.irPosition==12)||(data.irPosition==13)))
+                ){
+                    if(data.ping[F_PING]<WhiteToWallPlus[Y_PING]){
+                        data.lnStay[Y_LINE]=0;
+                    }
+                    else{
+                        data.lnStay[Y_LINE]=1;
+                    }
+                    if(data.lnRepeat>=LINE_REPEAT){
+                        data.lnStay[Y_LINE]=0;
+                    }
+                    data.lnStayNow[Y_LINE]=1;
+                }
+                else{
+                    data.lnStay[Y_LINE]=1;
+                }
+                
+                if(
+                    ((pow_y<0)&&((data.lnRawOrderLog1[0]==A_SPOT)&&(data.lnRawOrderLog1[1]==C_SPOT))&&((data.irPosition==18)||(data.irPosition==19)))||
+                    ((pow_y<0)&&((data.lnRawOrderLog1[0]==B_SPOT)&&(data.lnRawOrderLog1[1]==C_SPOT))&&((data.irPosition==15)||(data.irPosition==16)))
+                ){
+                    if(data.ping[B_PING]<WhiteToWallPlus[Y_PING]){
+                        data.lnStay[Y_LINE]=0;
+                    }
+                    else{
+                        data.lnStay[Y_LINE]=1;
+                    }
+                    if(data.lnRepeat>=LINE_REPEAT){
+                        data.lnStay[Y_LINE]=0;
+                    }
+                    data.lnStayNow[Y_LINE]=1;
+                }
+                else{
+                    data.lnStay[Y_LINE]=1;
+                }
+            }
+            if(
+                (data.lnRepeat>=2)
+            ){
+                if(
+                    ((pow_y>0)&&((data.ping[F_PING]<40)&&(1)))||
+                    ((pow_y<0)&&((data.ping[B_PING]<40)&&(1)))
+                ){
+                    data.lnStay[Y_LINE]=0;
+                }
+                if(
+                    ((pow_x>0)&&((data.ping[R_PING]<40)&&(1)))||
+                    ((pow_x<0)&&((data.ping[L_PING]<40)&&(1)))
+                ){
+                    data.lnStay[X_LINE]=0;
+                }
+            }
+        }
+        
+        
+    }
+    else{
+        data.lnStay[X_LINE]=data.lnStay[Y_LINE]=1;
+    }
+    
+}
+void JudgeInSide(void){
+    data.FieldSpot = LINE_INSIDE;
+    data.NonWall[L_LINE] = data.NonWall[R_LINE] = data.NonWall[F_LINE] = data.NonWall[B_LINE] = 0;
+    LineLiberate();
+    LineRankClear();
+    //Line_home.detach();
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/main_processing/strategy/LineProcess.h	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,13 @@
+#ifndef _LINE_PROCESS_H_
+#define _LINE_PROCESS_H_
+
+void LineJudgeSlow(double pow_x, double pow_y, double *x, double *y);
+void LineJudgeSlow2(double pow_x, double pow_y, double *x, double *y, uint8_t *px, uint8_t *py);
+void LineJudgeReturn(double pow_x, double pow_y, double *x, double *y);
+void LineJudgeReturn2(double pow_x, double pow_y, double *x, double *y);
+void LineJudgeReset(double pow_x, double pow_y, double *x, double *y);
+void LineJudgeReset2(double pow_x, double pow_y, double *x, double *y);
+void LineJudgeReset3(double pow_x, double pow_y, double *x, double *y);
+void JudgeInSide(void);
+
+#endif //_LINE_PROCESS_H_
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/main_processing/strategy/old_strategy.cpp	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,226 @@
+#include "mbed.h"
+#include "extern.h"
+
+//Atk
+void modeAttack0(void){//red(NormalAtk_______)
+    ////初期値を決める等
+    if(sys.KickOffFlag==1){
+        ///Blindシリーズ.1を代入であらゆるセンサーなどの値を反映させないようにする.
+        sys.IrBlind=0;
+        sys.LineBlind=0;
+        sys.PingBlind=0;
+        
+        sys.HomeBlind=1;
+        sys.DriBlind=0;
+        sys.DriMotorBlind=0;
+        sys.TurnAtkBlind=1;
+        sys.TurnDriBlind=1;
+        sys.TurnHoldBlind=1;
+        sys.KickBlind=0;
+        //defence
+        sys.DefenceFlag=0;
+        //初期値設定の終了
+        //sys.KickOffFlag=0;
+    }
+    modeAttack4();
+}
+void modeAttack1(void){//green(Libero__________)
+    ////初期値を決める等
+    if(sys.KickOffFlag==1){
+        ///Blindシリーズ.1を代入であらゆるセンサーなどの値を反映させないようにする.
+        sys.IrBlind=0;
+        sys.LineBlind=0;
+        sys.PingBlind=0;
+        
+        sys.HomeBlind=0;
+        sys.DriBlind=0;//1;
+        sys.DriMotorBlind=0;
+        sys.TurnAtkBlind=1;
+        sys.TurnDriBlind=1;
+        sys.TurnHoldBlind=1;
+        sys.KickBlind=0;
+        //defence
+        sys.DefenceFlag=0;
+        //初期値設定の終了
+        //sys.KickOffFlag=0;
+    }
+    modeAttack4();
+}
+void modeAttack2(void){
+    ////初期値を決める等
+    if(sys.KickOffFlag==1){
+        ///Blindシリーズ.1を代入であらゆるセンサーなどの値を反映させないようにする.
+        sys.IrBlind=0;
+        sys.LineBlind=0;
+        sys.PingBlind=0;
+        
+        sys.HomeBlind=0;
+        sys.DriBlind=1;
+        sys.DriMotorBlind=1;
+        sys.TurnAtkBlind=1;
+        sys.TurnDriBlind=1;
+        sys.TurnHoldBlind=1;
+        sys.KickBlind=0;
+        //defence
+        sys.DefenceFlag=0;
+        //初期値設定の終了
+        //sys.KickOffFlag=0;
+    }
+    modeAttack4();
+}
+void modeAttack3(void){
+    ////初期値を決める等
+    if(sys.KickOffFlag==1){
+        ///Blindシリーズ.1を代入であらゆるセンサーなどの値を反映させないようにする.
+        sys.IrBlind=0;
+        sys.LineBlind=0;
+        sys.PingBlind=0;
+        
+        sys.HomeBlind=1;
+        sys.DriBlind=0;
+        sys.DriMotorBlind=1;
+        sys.TurnAtkBlind=1;
+        sys.TurnDriBlind=1;
+        sys.TurnHoldBlind=1;
+        sys.KickBlind=0;
+        //defence
+        sys.DefenceFlag=0;
+        //初期値設定の終了
+        //sys.KickOffFlag=0;
+    }
+    modeAttack4();
+}
+
+//Debug
+void modeDebug0(void){
+    ////初期値を決める等
+    if(sys.KickOffFlag==1){
+        ///Blindシリーズ.1を代入であらゆるセンサーなどの値を反映させないようにする.
+        sys.IrBlind=0;
+        sys.LineBlind=0;
+        sys.PingBlind=0;
+        
+        sys.HomeBlind=1;
+        sys.DriBlind=0;
+        sys.DriMotorBlind=0;
+        sys.TurnAtkBlind=1;
+        sys.TurnDriBlind=1;
+        sys.TurnHoldBlind=1;
+        sys.KickBlind=0;
+        //defence
+        sys.DefenceFlag=0;
+        //初期値設定の終了
+        //sys.KickOffFlag=0;
+    }
+    modeAttack4();
+}
+void modeDebug1(void){
+    ////初期値を決める等
+    if(sys.KickOffFlag==1){
+        ///Blindシリーズ.1を代入であらゆるセンサーなどの値を反映させないようにする.
+        sys.IrBlind=0;
+        sys.LineBlind=0;
+        sys.PingBlind=0;
+        
+        sys.HomeBlind=1;
+        sys.DriBlind=0;
+        sys.DriMotorBlind=0;
+        sys.TurnAtkBlind=1;
+        sys.TurnDriBlind=1;
+        sys.TurnHoldBlind=1;
+        sys.KickBlind=0;
+        //defence
+        sys.DefenceFlag=0;
+        //初期値設定の終了
+        //sys.KickOffFlag=0;
+    }
+    modeAttack4();
+}
+void modeDebug2(void){
+    ////初期値を決める等
+    if(sys.KickOffFlag==1){
+        ///Blindシリーズ.1を代入であらゆるセンサーなどの値を反映させないようにする.
+        sys.IrBlind=0;
+        sys.LineBlind=1;
+        sys.PingBlind=0;
+        
+        sys.HomeBlind=0;
+        sys.DriBlind=1;
+        sys.DriMotorBlind=0;
+        sys.TurnAtkBlind=1;
+        sys.TurnDriBlind=1;
+        sys.TurnHoldBlind=1;
+        sys.KickBlind=0;
+        //defence
+        sys.DefenceFlag=0;
+        //初期値設定の終了
+        //sys.KickOffFlag=0;
+    }
+    modeAttack4();
+}
+void modeDebug3(void){
+    ////初期値を決める等
+    if(sys.KickOffFlag==1){
+        ///Blindシリーズ.1を代入であらゆるセンサーなどの値を反映させないようにする.
+        sys.IrBlind=0;
+        sys.LineBlind=1;
+        sys.PingBlind=0;
+        
+        sys.HomeBlind=1;
+        sys.DriBlind=0;
+        sys.DriMotorBlind=0;
+        sys.TurnAtkBlind=1;
+        sys.TurnDriBlind=1;
+        sys.TurnHoldBlind=1;
+        sys.KickBlind=0;
+        //defence
+        sys.DefenceFlag=0;
+        //初期値設定の終了
+        //sys.KickOffFlag=0;
+    }
+    modeAttack4();
+}
+void modeDebug4(void){
+    ////初期値を決める等
+    if(sys.KickOffFlag==1){
+        ///Blindシリーズ.1を代入であらゆるセンサーなどの値を反映させないようにする.
+        sys.IrBlind=1;
+        sys.LineBlind=0;
+        sys.PingBlind=0;
+        
+        sys.HomeBlind=0;
+        sys.DriBlind=1;
+        sys.DriMotorBlind=0;
+        sys.TurnAtkBlind=1;
+        sys.TurnDriBlind=1;
+        sys.TurnHoldBlind=1;
+        sys.KickBlind=0;
+        //defence
+        sys.DefenceFlag=0;
+        //初期値設定の終了
+        //sys.KickOffFlag=0;
+    }
+    modeAttack4();
+}
+void modeDebug5(void){
+    ////初期値を決める等
+    if(sys.KickOffFlag==1){
+        ///Blindシリーズ.1を代入であらゆるセンサーなどの値を反映させないようにする.
+        sys.IrBlind=1;
+        sys.LineBlind=0;
+        sys.PingBlind=0;
+        
+        sys.HomeBlind=1;
+        sys.DriBlind=0;
+        sys.DriMotorBlind=0;
+        sys.TurnAtkBlind=1;
+        sys.TurnDriBlind=1;
+        sys.TurnHoldBlind=1;
+        sys.KickBlind=0;
+        //defence
+        sys.DefenceFlag=0;
+        //初期値設定の終了
+        //sys.KickOffFlag=0;
+    }
+    modeAttack4();
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/main_processing/strategy/old_strategy.h	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,21 @@
+#ifndef _OLD_STRATEGY_H_
+#define _OLD_STRATEGY_H_
+
+#include "mbed.h"
+#include "extern.h"
+
+//Atk
+void modeAttack0(void);
+void modeAttack1(void);
+void modeAttack2(void);
+void modeAttack3(void);
+
+//Debug
+void modeDebug0(void);
+void modeDebug1(void);
+void modeDebug2(void);
+void modeDebug3(void);
+void modeDebug4(void);
+void modeDebug5(void);
+
+#endif //_OLD_STRATEGY_H_
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/main_processing/strategy/strategy.cpp	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,653 @@
+#include "mbed.h"
+#include "extern.h"
+
+//Atk
+void modeAttack4(void){
+    //irの値に影響するモーター補正値
+    //uint8_t ir_pow;
+    uint8_t ir_pow_x, ir_pow_y;
+    double ir_x_dir, ir_y_dir;
+    double ir_x_turn, ir_y_turn;
+    double ir_x, ir_y;
+    //lineの値に影響するモーター補正値
+    double LineSlowPower[2];
+    double LineReturnPower[2];
+    
+    //モーターの出力値
+    int vx,vy,vs;
+    
+    ////初期値を決める等
+    if(sys.KickOffFlag==1){
+        /*
+        ///Blindシリーズ.1を代入であらゆるセンサーなどの値を反映させないようにする.
+        sys.IrBlind=0;
+        sys.LineBlind=0;
+        sys.PingBlind=0;
+        
+        sys.HomeBlind=1;
+        sys.DriBlind=1;
+        //defence
+        sys.DefenceFlag=0;
+        */
+        
+        
+        //Kick
+        sys.KickStopFlag=0;
+        //Ir
+        sys.ir_pow_table = 0;
+        //Line
+        //data.lnCorner[L_LINE]=data.lnCorner[R_LINE]=data.lnCorner[F_LINE]=data.lnCorner[B_LINE]=LINE_EMPTY;
+        data.lnRepeat = 0;
+        data.lnStay[X_LINE]=data.lnStay[Y_LINE]=1;
+        data.lnStayNow[X_LINE]=data.lnStayNow[Y_LINE]=0;
+        data.lnStop[X_LINE]=data.lnStop[Y_LINE]=1;
+        
+        //data.FieldSpot = LINE_INSIDE;
+        //LineLiberate();
+        //LineRankClear();
+        
+        //JSO2
+        LineLiberate();
+        
+        LineRawRankClear();
+        
+        //data.lnRawMemory[A_SPOT]=0;
+        //data.lnRawMemory[B_SPOT]=0;
+        //data.lnRawMemory[C_SPOT]=0;
+        
+        data.lnRawReturn=0;
+        
+        LineRawLogReset();
+        //backhome
+        sys.HomeStayFlag[X_PING]=0;
+        sys.HomeStayFlag[Y_PING]=0;
+        //pid
+        sys.TurnStopFlag=0;
+        cmps_set.AtkDeg=0;
+        cmps_set.HoldDeg=0;
+        cmps_set.GoalDeg=0;
+        //ドリブラー
+        sys.BallHoldJudgeFlag=0;
+        sys.BallHoldFlag=0;
+        
+        //初期値設定の終了
+        sys.KickOffFlag=0;
+    }
+    ////DataRetrieve
+    if(sys.InfoFlag==1){ReadInfo();sys.InfoFlag=0;}
+    data.lnRaw = LineRaw;
+    data.lnHold = LineHold;
+    data.ball = ReadBall();
+    
+    //ボールがなければ自分のゴールに戻る
+    if(data.irNotice==IR_NONE){
+        
+        cmps_set.GoalDeg=0;
+        sys.BackHomeFlag=(sys.HomeBlind==0);
+    }
+    else{
+        sys.BackHomeFlag=0;
+        sys.HomeStayFlag[X_PING]=0;
+        sys.HomeStayFlag[Y_PING]=0;
+    }
+    //回り込みの値を代入
+    if(sys.DefenceFlag==1){
+        
+        if((data.irNotice==IR_NONE)||(data.irNotice==IR_FAR)){
+            
+            if((data.ping[L_PING]>=50)&&(data.ping[R_PING]>=50)){
+                ir_x_dir = ir_move_val[5][data.irNotice][data.irPosition][IR_X_DIR];
+                ir_x_turn = ir_move_val[5][data.irNotice][data.irPosition][IR_X_TURN];
+                
+                if(data.ping[B_PING]>=10){
+                    ir_y_dir = -1;
+                    ir_y_turn = 0;
+                }
+                else{
+                    ir_y_dir = 0;
+                    ir_y_turn = 0;
+                }
+            }
+            else if((data.ping[L_PING]>=50)&&(data.ping[R_PING]<50)){
+                ir_x_dir = -1;
+                ir_x_turn = 0;
+                
+                if(data.ping[B_PING]>=45){
+                    ir_y_dir = -1;
+                    ir_y_turn = 0;
+                }
+                else{
+                    ir_y_dir = 0;
+                    ir_y_turn = 0;
+                }
+            }
+            else if((data.ping[L_PING]<50)&&(data.ping[R_PING]>=50)){
+                ir_x_dir = 1;
+                ir_x_turn = 0;
+                
+                if(data.ping[B_PING]>=45){
+                    ir_y_dir = -1;
+                    ir_y_turn = 0;
+                }
+                else{
+                    ir_y_dir = 0;
+                    ir_y_turn = 0;
+                }
+            }
+            else if((data.ping[L_PING]<50)&&(data.ping[R_PING]<50)){
+                ir_x_dir = 0;
+                ir_x_turn = 0;
+                
+                if(data.ping[B_PING]>=45){
+                    ir_y_dir = -1;
+                    ir_y_turn = 0;
+                }
+                else{
+                    ir_y_dir = 0;
+                    ir_y_turn = 0;
+                }
+            }
+        }
+        else{
+            
+            ir_x_dir = ir_move_val[5][data.irNotice][data.irPosition][IR_X_DIR];
+            ir_x_turn = ir_move_val[5][data.irNotice][data.irPosition][IR_X_TURN];
+            
+            if((data.ping[B_PING]>=5)&&(data.ping[R_PING]>=50)&&(data.ping[L_PING]>=50)){
+                ir_y_dir = -1;
+                ir_y_turn = 0;
+            }
+            else{
+                ir_y_dir = 0;
+                ir_y_turn = 0;
+            }
+        }
+        /*
+        if((data.ping[L_PING]>=50)&&(data.ping[R_PING]>=50)&&(data.ping[B_PING]>10)){
+            ir_y_dir = -1;
+            ir_y_turn = 0;
+            
+            if(data.ping[B_PING]>=10){
+                ir_y_dir = -1;
+                ir_y_turn = 0;
+            }
+            else{
+                ir_y_dir = 0;
+                ir_y_turn = 0;
+            }
+            
+            ir_x_dir = ir_move_val[2][data.irNotice][data.irPosition][IR_X_DIR];
+            ir_x_turn = ir_move_val[2][data.irNotice][data.irPosition][IR_X_TURN];
+        }
+        else{
+            
+        }
+        */
+        /*
+        if((data.ping[B_PING]>=45)&&(data.irNotice!=IR_NONE)&&(15<=data.irPosition)&&(data.irPosition<=19)){
+            //sys.ir_pow_table=1;
+            ir_x_dir = 0;
+            ir_y_dir = -1;
+            ir_x_turn = 0;
+            ir_y_turn = 0;
+        }
+        else{
+            if(data.irValPhase[IR_SHORT]>=DIS_4){
+                sys.ir_pow_table=2;//直進
+                ir_x_dir = ir_move_val[2][data.irNotice][data.irPosition][IR_X_DIR];
+                ir_y_dir = ir_move_val[2][data.irNotice][data.irPosition][IR_Y_DIR];
+                ir_x_turn = ir_move_val[2][data.irNotice][data.irPosition][IR_X_TURN];
+                ir_y_turn = ir_move_val[2][data.irNotice][data.irPosition][IR_Y_TURN];
+            }
+            else{
+                if(data.irValPhase[IR_SHORT]<=DIS_1){
+                    sys.ir_pow_table=0;//3
+                    ir_x_dir = ir_move_val[0][data.irNotice][data.irPosition][IR_X_DIR];
+                    ir_y_dir = ir_move_val[0][data.irNotice][data.irPosition][IR_Y_DIR];
+                    ir_x_turn = ir_move_val[0][data.irNotice][data.irPosition][IR_X_TURN];
+                    ir_y_turn = ir_move_val[0][data.irNotice][data.irPosition][IR_Y_TURN];
+                }
+                else{
+                    sys.ir_pow_table=0;
+                    ir_x_dir = ir_move_val[0][data.irNotice][data.irPosition][IR_X_DIR];
+                    ir_y_dir = ir_move_val[0][data.irNotice][data.irPosition][IR_Y_DIR];
+                    ir_x_turn = ir_move_val[0][data.irNotice][data.irPosition][IR_X_TURN];
+                    ir_y_turn = ir_move_val[0][data.irNotice][data.irPosition][IR_Y_TURN];
+                }
+            }
+        }*/
+    }
+    else{
+        if((data.ping[B_PING]>40)&&(0)){
+            sys.ir_pow_table=0;
+            ir_x_dir = ir_move_val[0][data.irNotice][data.irPosition][IR_X_DIR];
+            ir_y_dir = ir_move_val[0][data.irNotice][data.irPosition][IR_Y_DIR];
+            ir_x_turn = ir_move_val[0][data.irNotice][data.irPosition][IR_X_TURN];
+            ir_y_turn = ir_move_val[0][data.irNotice][data.irPosition][IR_Y_TURN];
+        }
+        else{
+            if((data.ping[B_PING]>60)&&(data.irValPhase[IR_SHORT]>=DIS_4)){
+                sys.ir_pow_table=2;//直進
+                ir_x_dir = ir_move_val[2][data.irNotice][data.irPosition][IR_X_DIR];
+                ir_y_dir = ir_move_val[2][data.irNotice][data.irPosition][IR_Y_DIR];
+                ir_x_turn = ir_move_val[2][data.irNotice][data.irPosition][IR_X_TURN];
+                ir_y_turn = ir_move_val[2][data.irNotice][data.irPosition][IR_Y_TURN];
+            }
+            else{
+                if(data.irValPhase[IR_SHORT]<=DIS_1){
+                    sys.ir_pow_table=0;//3
+                    ir_x_dir = ir_move_val[0][data.irNotice][data.irPosition][IR_X_DIR];
+                    ir_y_dir = ir_move_val[0][data.irNotice][data.irPosition][IR_Y_DIR];
+                    ir_x_turn = ir_move_val[0][data.irNotice][data.irPosition][IR_X_TURN];
+                    ir_y_turn = ir_move_val[0][data.irNotice][data.irPosition][IR_Y_TURN];
+                }
+                else{
+                    sys.ir_pow_table=0;
+                    ir_x_dir = ir_move_val[0][data.irNotice][data.irPosition][IR_X_DIR];
+                    ir_y_dir = ir_move_val[0][data.irNotice][data.irPosition][IR_Y_DIR];
+                    ir_x_turn = ir_move_val[0][data.irNotice][data.irPosition][IR_X_TURN];
+                    ir_y_turn = ir_move_val[0][data.irNotice][data.irPosition][IR_Y_TURN];
+                }
+            }
+        }
+        if((sys.HomeBlind==0)){
+            if(((data.irNotice==IR_CLOSE)||(data.irNotice==IR_CLOSER))&&(data.ping[B_PING]<60)&&
+                (
+                    (data.irPosition==11)||
+                    (data.irPosition==(ir_posi_s[(11-8+24+1)%12]))||
+                    (data.irPosition==(ir_posi_s[(11-8+24-1)%12]))||
+                    (data.irPosition==(ir_posi_s[(11-8+24+2)%12]))||
+                    (data.irPosition==(ir_posi_s[(11-8+24-2)%12]))||
+                    (data.irPosition==(ir_posi_s[(11-8+24+3)%12]))||
+                    (data.irPosition==(ir_posi_s[(11-8+24-3)%12]))
+                )
+            ){
+                sys.ir_pow_table=2;//直進
+                ir_x_dir = ir_move_val[2][data.irNotice][data.irPosition][IR_X_DIR];
+                ir_y_dir = ir_move_val[2][data.irNotice][data.irPosition][IR_Y_DIR];
+                ir_x_turn = ir_move_val[2][data.irNotice][data.irPosition][IR_X_TURN];
+                ir_y_turn = ir_move_val[2][data.irNotice][data.irPosition][IR_Y_TURN];
+            }
+        }
+    }
+    
+    //Irの検出値によって出力を調整
+    if(data.irNotice==IR_CLOSER){
+        //ir_pow = sys.s_pow;
+        ir_pow_x = ir_pow_y = sys.s_pow;
+    }
+    else if(data.irNotice==IR_CLOSE){
+        //ir_pow = sys.m_pow;
+        ir_pow_x = ir_pow_y = sys.m_pow;
+    }
+    else if(data.irNotice==IR_FAR){
+        //ir_pow = sys.l_pow;
+        ir_pow_x = ir_pow_y = sys.l_pow;
+    }
+    else{//data.irNotice==IR_NONE
+        //ir_pow = 0;
+        ir_pow_x = ir_pow_y = 0;
+    }
+    
+    if(sys.DefenceFlag==1){
+        ir_pow_x = 30;
+        ir_pow_y = 30;
+        if(data.ping[L_PING]<=60){
+            ir_pow_y = 30;
+        }
+        if(data.ping[L_PING]<=40){
+            ir_pow_y = 25;
+        }
+        if(data.ping[L_PING]<=30){
+            ir_pow_y = 20;
+        }
+        if(data.ping[L_PING]<15){
+            ir_pow_y = 15;
+        }
+        if(data.ping[L_PING]<10){
+            ir_pow_y = 10;
+        }
+    }
+    ////ドリブラーdribbler
+    //ホールド判定hold
+    JudgeBallHolding();
+    //JudgeBallHold();
+    //sys.BallHoldFlag = data.ball;
+    //ドリブラー駆動
+    /*if((sys.TurnDriBlind==0)&&(data.lnRawOrderLog1[0]!=LINE_EMPTY)&&(data.lnRawOrder[0]==LINE_EMPTY)){
+        if(sys.TurnDriBlind==0){
+            if(
+                ((data.lnRawOrderLog1[0]==A_SPOT)&&(data.lnRawOrderLog1[1]==B_SPOT))||
+                ((data.lnRawOrderLog1[0]==B_SPOT)&&(data.lnRawOrderLog1[1]==A_SPOT))
+            ){
+                cmps_set.GoalDeg=0;
+            }
+            else if((data.lnRawOrderLog1[0]==A_SPOT)&&(1)){
+                cmps_set.GoalDeg=-30;
+            }
+            else if((data.lnRawOrderLog1[0]==B_SPOT)&&(1)){
+                cmps_set.GoalDeg=30;
+            }
+            else{
+                cmps_set.GoalDeg=0;
+            }
+        }
+    }*/
+    if((sys.TurnDriBlind==0)&&(/*data.lnRaw==0*/1)&&((data.irNotice==IR_CLOSER)||(data.irNotice==IR_CLOSE))&&(/*data.ping[B_PING]>90*/1)&&
+    (
+        (data.irPosition==11)||
+        (data.irPosition==(ir_posi_s[(11-8+24+1)%12]))||
+        (data.irPosition==(ir_posi_s[(11-8+24-1)%12]))||
+        (data.irPosition==(ir_posi_s[(11-8+24+2)%12]))||
+        (data.irPosition==(ir_posi_s[(11-8+24-2)%12]))
+    )
+    
+    ){
+        if(sys.TurnDriBlind==0){
+            if(
+                ((data.ping[L_PING]<40)&&(data.ping[R_PING]>70))
+            ){
+                cmps_set.GoalDeg=60;
+            }
+            else if(
+                ((data.ping[R_PING]<40)&&(data.ping[L_PING]>70))
+            ){
+                cmps_set.GoalDeg=-60;
+            }
+            else{
+                cmps_set.GoalDeg=0;
+            }
+        }
+    }
+    if((sys.DriBlind==0)&&(data.irNotice==IR_CLOSER)&&((data.irPosition==10)||(data.irPosition==11)||(data.irPosition==12))){
+        sys.DribbleFlag=1;
+        if((sys.BallHoldFlag==1)||(data.ball==1)){
+            //ir_pow=20;
+            ir_pow_x = ir_pow_y = 20;
+        }
+    }
+    else{
+        sys.DribbleFlag=0;
+        cmps_set.HoldDeg=0;
+    }
+    
+    ////Kick
+    /*if((data.ball==1)&&(data.irNotice==IR_CLOSER)&&((data.irPosition==10)||(data.irPosition==11)||(data.irPosition==12))){
+        DriveTurn();
+    }*/
+    /*if((data.ball==1)&&(data.irNotice==IR_CLOSER)&&((data.irPosition==10)||(data.irPosition==11)||(data.irPosition==12))){
+        DriveTurn();
+        DriveSolenoid();
+    }*/
+    if(
+        /*(sys.BallHoldFlag==1)&&
+        (data.ball==1)&&
+        (data.irNotice==IR_CLOSER)&&
+        ((data.irPosition==10)||(data.irPosition==11)||(data.irPosition==12))&&
+        (data.ping[B_PING]>100)&&
+        (
+            ((data.ping[L_PING]<60)&&(data.ping[R_PING]>60))||
+            ((data.ping[L_PING]>60)&&(data.ping[R_PING]<60))||
+            (data.lnRawOrderLog1[0]==A_SPOT)||
+            (data.lnRawOrder[0]==A_SPOT)||
+            (data.lnRawOrderLog1[0]==B_SPOT)||
+            (data.lnRawOrder[0]==B_SPOT)
+        )&&
+        (data.lnRaw==0)*/
+        (sys.DriBlind==0)&&
+        (data.ping[R_PING]<30)&&
+        (data.ping[L_PING]<30)
+    ){
+        //DriveTurn();
+        //DriveSolenoid();
+    }
+    
+    //Irの細かい補正値の処理.基本的にLineの補正値を演算する処理が始まる前にIrのモーター出力値補正をすべて終わらせる.
+    //if(sys.IrBlind==1) ir_pow=0;
+    if(sys.IrBlind==1) ir_pow_x=ir_pow_y=0;
+    if((data.ping[R_PING]<data.ping[L_PING])&&(data.irPosition==17)&&(data.irNotice==IR_CLOSER)){
+        ir_x_turn = -ir_x_turn;
+        ir_y_turn = -ir_y_turn;
+    }
+    
+    if((sys.BackHomeFlag==1)&&(sys.HomeBlind==0)){
+        ir_pow_x = ir_pow_y = 25;
+        //x
+        if((abs(data.ping[L_PING]-data.ping[R_PING])>20)&&(sys.HomeStayFlag[X_PING]==0)){
+            if(data.ping[L_PING]>data.ping[R_PING]){
+                ir_x = -1;
+            }
+            else{
+                ir_x = 1;
+            }
+            if((data.ping[L_PING]<WhiteToWallPlus[X_PING])&&(data.ping[R_PING]<WhiteToWallPlus[X_PING])){
+                ir_x = 0;
+            }
+        }
+        else{
+            ir_x = 0;
+            //
+            sys.HomeStayFlag[X_PING]=1;
+        }
+        //y
+        if((data.ping[B_PING]>60)&&(1)&&(sys.HomeStayFlag[Y_PING]==0)){
+            ir_y = -1;
+            /*if((abs(data.ping[L_PING]-data.ping[R_PING])>30)&&(1)){
+                ir_pow_y = 15;
+            }*/
+        }
+        else{
+            ir_y = 0;
+            /*
+            if((1)&&(data.ping[B_PING]>60)&&(data.ping[R_PING]>55)&&(data.ping[L_PING]>55)){
+                ir_y = -1;
+                ir_pow_y = 15;
+            }
+            else{
+                ir_y = 0;
+            }
+            */
+            //
+            sys.HomeStayFlag[Y_PING]=1;
+        }
+    }
+    else{
+        ir_x = (ir_x_dir + ir_x_turn);
+        ir_y = (ir_y_dir + ir_y_turn);
+    }
+    if((sys.HomeBlind==0)&&(data.irNotice==IR_FAR)){
+        if(ir_y>0){
+            ir_y=0;
+            ir_pow_x = ir_pow_y = 25;
+            
+            if((data.ping[B_PING]>50)&&(1)){
+                ir_y = -1;
+                //ir_pow_y = 15;
+            }
+            
+        }
+        //ir_pow_x = ir_pow_y = 25;
+        //if(ir_y>0) ir_y=0;
+        /*if((data.ping[B_PING]>40)&&(1)){
+            ir_y = -1;
+            //ir_pow_y = 15;
+        }*/
+    }
+    if(
+        (sys.DefenceFlag==1)&&
+        (ir_y>0)&&
+        (data.ping[B_PING]>60)&&
+        (data.ping[B_PING]<225)&&
+        (sys.BackHomeFlag==0)
+    ){
+        ir_pow_y=0;
+    }
+    ///dribbler
+    if((sys.DriBlind==0)&&(data.irNotice==IR_CLOSER)&&(/*sys.BallHoldFlag==1*/data.ball==1)&&((data.irPosition==10)||(data.irPosition==11)||(data.irPosition==12))){
+        
+        if((1/*data.ping[L_PING]<60*/)&&(data.ping[R_PING]>90)){
+            //ir_x = 1;
+        }
+        else{
+            if(data.lnRawOrderLog1[0]==B_SPOT){
+                 //ir_x = 1;
+            }
+        }
+        if((1/*data.ping[R_PING]<60*/)&&(data.ping[L_PING]>90)){
+            //ir_x = -1;
+        }
+        else{
+            if(data.lnRawOrderLog1[0]==A_SPOT){
+                 //ir_x = -1;
+            }
+        }
+        if((data.ping[F_PING]<50)&&(data.ping[B_PING]>100)){
+            //ir_y = -1;
+        }
+        if(
+            ((data.ping[L_PING]<55)&&(data.ping[R_PING]<55))||
+            ((data.ping[L_PING]>55)&&(data.ping[R_PING]>55))
+        ){
+            //DriveSolenoid();
+        }
+        //x
+        if((abs(data.ping[L_PING]-data.ping[R_PING])>40)&&(data.lnRawOrderLog1[0]==A_SPOT)){
+            ir_x = -1;
+        }
+        else if((abs(data.ping[L_PING]-data.ping[R_PING])>40)&&(data.lnRawOrderLog1[0]==B_SPOT)){
+            ir_x = 1;
+        }
+        else if((abs(data.ping[L_PING]-data.ping[R_PING])>10)&&((data.ping[L_PING]+data.ping[R_PING])>80)){
+            if(data.ping[L_PING]>data.ping[R_PING]){
+                ir_x = -1;
+            }
+            else{
+                ir_x = 1;
+            }
+        }
+        else{
+            if((abs(data.ping[L_PING]-data.ping[R_PING])>10)&&(1)){
+                if(data.ping[L_PING]>data.ping[R_PING]){
+                    ir_x = -1;
+                }
+                else{
+                    ir_x = 1;
+                }
+            }
+            else{
+                ir_x = 0;
+            }
+            
+            //ir_x = 0;
+            DriveSolenoid();
+        }
+        //y
+        if((data.ping[F_PING]<45)&&(abs(data.ping[L_PING]-data.ping[R_PING])>50)){
+            //ir_y = 0.75;
+        }
+        //kick
+        if((abs(data.ping[L_PING]-data.ping[R_PING])<30)&&(1)){
+            DriveSolenoid();
+        }
+    }
+    ////Lineセンサーの値を評価しモーターの出力補正値を演算
+    if(sys.LineBlind==1){
+        
+        LineSlowPower[X_LINE] = 1.0;
+        LineSlowPower[Y_LINE] = 1.0;
+        
+        LineReturnPower[X_LINE] = 0.0;
+        LineReturnPower[Y_LINE] = 0.0;
+        
+        data.lnStop[X_LINE] = 1;
+        data.lnStop[Y_LINE] = 1;
+        
+        data.FieldSpot = LINE_INSIDE;
+    }
+    else{
+        /*
+        LineJudgeReset(ir_x, ir_y, &LineSlowPower[X_LINE], &LineSlowPower[Y_LINE]);
+        LineJudgeSlow(ir_x, ir_y, &LineSlowPower[X_LINE], &LineSlowPower[Y_LINE]);
+        LineJudgeReturn(ir_x*LineSlowPower[X_LINE], ir_y*LineSlowPower[Y_LINE], &LineReturnPower[X_LINE], &LineReturnPower[Y_LINE]);
+        */
+        LineJudgeReset3(ir_x, ir_y, &LineSlowPower[X_LINE], &LineSlowPower[Y_LINE]);
+        LineJudgeSlow2(ir_x, ir_y, &LineSlowPower[X_LINE], &LineSlowPower[Y_LINE], &ir_pow_x, &ir_pow_y);
+        LineJudgeReturn2(ir_x*LineSlowPower[X_LINE], ir_y*LineSlowPower[Y_LINE], &LineReturnPower[X_LINE], &LineReturnPower[Y_LINE]);
+    }
+    ////LEDデバッグ
+    //if(data.FieldSpot==LINE_OUTSIDE) LED = 0x9;
+    //if(data.FieldSpot==LINE_INSIDE) LED = 0x6;
+    //LED = ((data.lnRawMemory[0]!=0)<<2) | ((data.lnRawMemory[1]!=0)<<1) | ((data.lnRawMemory[2]!=0)<<0);
+    //LED = ((data.lnRawOrder[0]!=LINE_EMPTY)<<2) | ((data.lnRawOrder[1]!=LINE_EMPTY)<<1) | ((data.lnRawOrder[2]!=LINE_EMPTY)<<0);
+    //LED = ((data.lnOrder[0]!=LINE_EMPTY)<<2) | ((data.lnOrder[1]!=LINE_EMPTY)<<1) | ((data.lnOrder[2]!=LINE_EMPTY)<<0);
+    
+    //LED = sys.BallHoldFlag*15;
+    if(sys.BallHoldFlag==0) LED=15;
+    else LED=10;
+    /*
+    if((abs(data.ping[L_PING]-data.ping[R_PING])>10)&&((data.ping[L_PING]+data.ping[R_PING])>80)){
+        if(data.ping[L_PING]>data.ping[R_PING]){
+            LED=9;
+        }
+        else{
+            LED=6;
+        }
+    }
+    else{
+        LED=15;
+    }*/
+    
+    //if(data.ball==1) LED=15;
+    //else LED=10;
+    
+    //if(data.lnRepeat>=1) LED=15;
+    //else LED=10;
+    
+    //LED = 0xFF*(data.ping[B_PING]<30);
+    
+    //LED = ((data.lnOrder[0]!=LINE_EMPTY)<<2) | ((data.lnOrder[1]!=LINE_EMPTY)<<1) | ((data.lnOrder[2]!=LINE_EMPTY)<<0);
+    
+    //else LED = 0xA;
+    //LED = LineHold;
+    
+    
+    ////最終的なモーターの出力を演算
+    vx = (ir_pow_x*ir_x)*data.lnStop[X_LINE]*(data.lnStay[X_LINE])*LineSlowPower[X_LINE]*(sys.TurnStopFlag==0) + LineReturnPower[X_LINE];
+    vy = (ir_pow_y*ir_y)*data.lnStop[Y_LINE]*(data.lnStay[Y_LINE])*LineSlowPower[Y_LINE]*(sys.TurnStopFlag==0) + LineReturnPower[Y_LINE];
+    vs = cmps_set.OutputPID;
+    move(
+        vx,
+        vy,
+        vs
+    );
+    //モーターに信号を出力
+    if(sys.MotorFlag==1){tx_motor();sys.MotorFlag=0;}
+    
+    if(sys.stopflag==1){
+        //コマンドモードに戻る際の処理
+    }
+    return;
+}
+
+void modeAttack5(void){
+    ////初期値を決める等
+    if(sys.KickOffFlag==1){
+        ///Blindシリーズ.1を代入であらゆるセンサーなどの値を反映させないようにする.
+        sys.IrBlind=0;
+        sys.LineBlind=0;
+        sys.PingBlind=0;
+        
+        sys.HomeBlind=1;
+        sys.DriBlind=0;
+        sys.DriMotorBlind=0;
+        sys.TurnAtkBlind=1;
+        sys.TurnDriBlind=1;
+        sys.TurnHoldBlind=1;
+        sys.KickBlind=0;
+        //defence
+        sys.DefenceFlag=0;
+        //初期値設定の終了
+        //sys.KickOffFlag=0;
+    }
+    modeAttack4();
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/main_processing/strategy/strategy.h	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,7 @@
+#ifndef _STRATEGY_H_
+#define _STRATEGY_H_
+//Atk
+void modeAttack4(void);
+void modeAttack5(void);
+
+#endif //_STRATEGY_H_
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/main_processing/strategy/strategy2.cpp	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,4 @@
+#include "mbed.h"
+#include "extern.h"
+
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/main_processing/strategy/strategy2.h	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,5 @@
+#ifndef _STRATEGY2_H_
+#define _STRATEGY2_H_
+//Debug
+
+#endif //_STRATEGY2_H_
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/main_processing/strategy_parts/input.cpp	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,439 @@
+#include "mbed.h"
+#include "extern.h"
+
+//line
+void ReadLine(void){
+    static uint8_t line_buf[3]={0,0,0};
+    wait_us(100);
+    if(Line[0].read()==1) line_buf[0] = 100;
+    if(line_buf[0]==0)  data.lnFlag[0]=0;
+    else                data.lnFlag[0]=1;
+    if(line_buf[0]>0) line_buf[0]--;
+    
+    if(Line[1].read()==1) line_buf[1] = 100;
+    if(line_buf[1]==0)  data.lnFlag[1]=0;
+    else                data.lnFlag[1]=1;
+    if(line_buf[1]>0) line_buf[1]--;
+    
+    if(Line[2].read()==1) line_buf[2] = 100;
+    if(line_buf[2]==0)  data.lnFlag[2]=0;
+    else                data.lnFlag[2]=1;
+    if(line_buf[2]>0) line_buf[2]--;
+}
+//line_hold
+void LineRanking_A(void){
+    if(data.lnOrder[0]==LINE_EMPTY){
+        data.lnOrder[0]=A_SPOT;
+    }
+    else if(data.lnOrder[1]==LINE_EMPTY){
+        data.lnOrder[1]=A_SPOT;
+    }
+    else if(data.lnOrder[2]==LINE_EMPTY){
+        data.lnOrder[2]=A_SPOT;
+    }
+}
+void LineRanking_B(void){
+    if(data.lnOrder[0]==LINE_EMPTY){
+        data.lnOrder[0]=B_SPOT;
+    }
+    else if(data.lnOrder[1]==LINE_EMPTY){
+        data.lnOrder[1]=B_SPOT;
+    }
+    else if(data.lnOrder[2]==LINE_EMPTY){
+        data.lnOrder[2]=B_SPOT;
+    }
+}
+void LineRanking_C(void){
+    if(data.lnOrder[0]==LINE_EMPTY){
+        data.lnOrder[0]=C_SPOT;
+    }
+    else if(data.lnOrder[1]==LINE_EMPTY){
+        data.lnOrder[1]=C_SPOT;
+    }
+    else if(data.lnOrder[2]==LINE_EMPTY){
+        data.lnOrder[2]=C_SPOT;
+    }
+}
+void LineRankClear(void){
+    data.lnOrder[0]=LINE_EMPTY;
+    data.lnOrder[1]=LINE_EMPTY;
+    data.lnOrder[2]=LINE_EMPTY;
+    
+    if((0<LineHold)&&(LineHold<7)){
+        if((LineHolding[A_SPOT].read()==0)&&(LineHolding[B_SPOT].read()==0)&&(LineHolding[C_SPOT].read()==1)){
+            data.lnOrder[0] = C_SPOT;
+            data.lnOrder[1] = LINE_EMPTY;
+        }
+        else if((LineHolding[A_SPOT].read()==0)&&(LineHolding[B_SPOT].read()==1)&&(LineHolding[C_SPOT].read()==0)){
+            data.lnOrder[0] = B_SPOT;
+            data.lnOrder[1] = LINE_EMPTY;
+        }
+        else if((LineHolding[A_SPOT].read()==0)&&(LineHolding[B_SPOT].read()==1)&&(LineHolding[C_SPOT].read()==1)){
+            data.lnOrder[0] = C_SPOT;
+            data.lnOrder[1] = B_SPOT;
+        }
+        else if((LineHolding[A_SPOT].read()==1)&&(LineHolding[B_SPOT].read()==0)&&(LineHolding[C_SPOT].read()==0)){
+            data.lnOrder[0] = A_SPOT;
+            data.lnOrder[1] = LINE_EMPTY;
+        }
+        else if((LineHolding[A_SPOT].read()==1)&&(LineHolding[B_SPOT].read()==0)&&(LineHolding[C_SPOT].read()==1)){
+            data.lnOrder[0] = C_SPOT;
+            data.lnOrder[1] = A_SPOT;
+        }
+        else if((LineHolding[A_SPOT].read()==1)&&(LineHolding[B_SPOT].read()==1)&&(LineHolding[C_SPOT].read()==0)){
+            data.lnOrder[0] = A_SPOT;
+            data.lnOrder[1] = B_SPOT;
+        }
+    }
+}
+//line raw
+/*
+void LineRawCall_A(void){data.lnRawMemory[A_SPOT]=1;Line_timeout[A_SPOT].attach(&LineRawClear_A, LINE_DELAY);}
+void LineRawCall_B(void){data.lnRawMemory[B_SPOT]=1;Line_timeout[B_SPOT].attach(&LineRawClear_B, LINE_DELAY);}
+void LineRawCall_C(void){data.lnRawMemory[C_SPOT]=1;Line_timeout[C_SPOT].attach(&LineRawClear_C, LINE_DELAY);}
+void LineRawClear_A(void){if(Line[A_SPOT].read()==1){LineRawCall_A();}else{data.lnRawMemory[A_SPOT]=0;}}
+void LineRawClear_B(void){if(Line[B_SPOT].read()==1){LineRawCall_B();}else{data.lnRawMemory[B_SPOT]=0;}}
+void LineRawClear_C(void){if(Line[C_SPOT].read()==1){LineRawCall_C();}else{data.lnRawMemory[C_SPOT]=0;}}
+*/
+void LineRawCall_ALL(void){
+    if(data.lnRawReturn==1){
+        if(
+            (data.lnRawOrder[0]==A_SPOT)||
+            (data.lnRawOrder[0]==B_SPOT)||
+            (data.lnRawOrder[0]==C_SPOT)
+        ){
+            if(
+                (
+                    (data.lnRawOrder[0]!=LINE_EMPTY)&&
+                    (data.lnRawOrder[1]!=LINE_EMPTY)&&
+                    ((Line[data.lnRawOrder[0]].read()==1)||(data.lnRawOrder[0]==data.lnRawLastRise))
+                )||
+                (data.lnRawOrder[0]==C_SPOT)
+            ){
+                Line_reset.attach(&LineRawClear_ALL, LINE_DELAY_3);
+            }
+            else{
+                Line_reset.attach(&LineRawClear_ALL, LINE_DELAY_2);
+            }
+        }
+        else{
+            Line_reset.attach(&LineRawClear_ALL, LINE_DELAY_2);
+        }
+    }
+    else{
+        Line_reset.attach(&LineRawClear_ALL, LINE_DELAY_1);
+    }
+}
+void LineRawClear_ALL(void){
+    if(LineRaw>0){
+        LineRawCall_ALL();
+    }
+    else if(LineRaw==0){
+        LineRawRankClear();
+    }
+}
+void LineRawRankClear(void){
+    
+    //JSO2
+    LineLiberate();
+    
+    data.lnRawOrderLog2[0]=data.lnRawOrderLog1[0];
+    data.lnRawOrderLog2[1]=data.lnRawOrderLog1[1];
+    data.lnRawOrderLog2[2]=data.lnRawOrderLog1[2];
+    
+    data.lnRawOrderLog1[0]=data.lnRawOrder[0];
+    data.lnRawOrderLog1[1]=data.lnRawOrder[1];
+    data.lnRawOrderLog1[2]=data.lnRawOrder[2];
+    
+    data.lnRawOrder[0]=LINE_EMPTY;
+    data.lnRawOrder[1]=LINE_EMPTY;
+    data.lnRawOrder[2]=LINE_EMPTY;
+    
+    if(
+        (data.lnRawOrderLog2[0]==data.lnRawOrderLog1[0])&&
+        //(data.lnRawOrderLog2[1]==data.lnRawOrderLog1[1])&&
+        //(data.lnRawOrderLog2[2]==data.lnRawOrderLog1[2])
+        (data.lnRawOrderLog2[0]!=LINE_EMPTY)
+        //(data.lnRawOrderLog2[1]!=LINE_EMPTY)
+    ){
+        if(data.lnRepeat>100) data.lnRepeat=100;
+        data.lnRepeat++;
+        
+        data.irLastNotice = data.irNotice;
+        data.irLastPosition = data.irPosition;
+    }
+    else{
+        data.lnRepeat=0;
+    }
+    
+    
+    data.lnRawRise[A_SPOT]=0;
+    data.lnRawRise[B_SPOT]=0;
+    data.lnRawRise[C_SPOT]=0;
+}
+void LineRawLogReset(void){
+    /*
+    if(
+        (!(
+            (data.irPosition==data.irLastPosition)||
+            (data.irPosition==(data.irLastPosition+1))||
+            (data.irPosition==(data.irLastPosition-1))||
+            (data.irPosition==(data.irLastPosition+11))||
+            (data.irPosition==(data.irLastPosition-11))
+        ))&&
+        (
+            (data.irNotice==IR_CLOSE)||
+            (data.irNotice==IR_CLOSER)
+        )&&
+        (
+            (data.irLastPosition>7)
+        )
+    ){
+        data.lnRawOrderLog2[0]=LINE_EMPTY;
+        data.lnRawOrderLog2[1]=LINE_EMPTY;
+        data.lnRawOrderLog2[2]=LINE_EMPTY;
+    }
+    else{
+        data.lnRawOrderLog2[0]=LINE_EMPTY;
+        data.lnRawOrderLog2[1]=LINE_EMPTY;
+        data.lnRawOrderLog2[2]=LINE_EMPTY;
+        
+        data.lnRawOrderLog1[0]=LINE_EMPTY;
+        data.lnRawOrderLog1[1]=LINE_EMPTY;
+        data.lnRawOrderLog1[2]=LINE_EMPTY;
+    }*/
+    if(data.irNotice==IR_NONE){
+        data.lnRawOrderLog2[0]=LINE_EMPTY;
+        data.lnRawOrderLog2[1]=LINE_EMPTY;
+        data.lnRawOrderLog2[2]=LINE_EMPTY;
+        
+        data.lnRawOrderLog1[0]=LINE_EMPTY;
+        data.lnRawOrderLog1[1]=LINE_EMPTY;
+        data.lnRawOrderLog1[2]=LINE_EMPTY;
+    }
+    else{
+        data.lnRawOrderLog2[0]=LINE_EMPTY;
+        data.lnRawOrderLog2[1]=LINE_EMPTY;
+        data.lnRawOrderLog2[2]=LINE_EMPTY;
+    }
+    
+}
+void LineRawRanking_A(void){
+    data.lnRawLastRise=A_SPOT;
+    LineRawCall_ALL();
+    if(data.lnRawRise[A_SPOT]==1) return;
+    
+    if((data.lnRawOrder[0]==LINE_EMPTY)||(data.lnRawOrder[0]==A_SPOT)){
+        data.lnRawOrder[0]=A_SPOT;
+        if((sys.DefenceFlag==1)&&(data.lnRawOrder[1]==LINE_EMPTY)){
+            data.lnRawOrder[1]=C_SPOT;
+        }
+    }
+    else if((data.lnRawOrder[1]==LINE_EMPTY)||(data.lnRawOrder[1]==A_SPOT)){
+        data.lnRawOrder[1]=A_SPOT;
+    }
+    else if((data.lnRawOrder[2]==LINE_EMPTY)||(data.lnRawOrder[2]==A_SPOT)){
+        data.lnRawOrder[2]=A_SPOT;
+    }
+    data.lnRawRise[A_SPOT]=1;
+}
+void LineRawRanking_B(void){
+    data.lnRawLastRise=B_SPOT;
+    LineRawCall_ALL();
+    if(data.lnRawRise[B_SPOT]==1) return;
+    
+    if((data.lnRawOrder[0]==LINE_EMPTY)||(data.lnRawOrder[0]==B_SPOT)){
+        data.lnRawOrder[0]=B_SPOT;
+        if((sys.DefenceFlag==1)&&(data.lnRawOrder[1]==LINE_EMPTY)){
+            data.lnRawOrder[1]=C_SPOT;
+        }
+    }
+    else if((data.lnRawOrder[1]==LINE_EMPTY)||(data.lnRawOrder[1]==B_SPOT)){
+        data.lnRawOrder[1]=B_SPOT;
+    }
+    else if((data.lnRawOrder[2]==LINE_EMPTY)||(data.lnRawOrder[2]==B_SPOT)){
+        data.lnRawOrder[2]=B_SPOT;
+    }
+    data.lnRawRise[B_SPOT]=1;
+}
+void LineRawRanking_C(void){
+    data.lnRawLastRise=C_SPOT;
+    LineRawCall_ALL();
+    if(data.lnRawRise[C_SPOT]==1) return;
+    
+    if((data.lnRawOrder[0]==LINE_EMPTY)||(data.lnRawOrder[0]==C_SPOT)){
+        data.lnRawOrder[0]=C_SPOT;
+    }
+    else if((data.lnRawOrder[1]==LINE_EMPTY)||(data.lnRawOrder[1]==C_SPOT)){
+        data.lnRawOrder[1]=C_SPOT;
+    }
+    else if((data.lnRawOrder[2]==LINE_EMPTY)||(data.lnRawOrder[2]==C_SPOT)){
+        data.lnRawOrder[2]=C_SPOT;
+    }
+    data.lnRawRise[C_SPOT]=1;
+}
+//ball
+uint8_t ReadBall(void){//1or0
+    return (BallChecker.read()==0);
+    //return (BallCheckerA.read_u16()<40000); 
+}
+void JudgeBallHolding(void){
+    //ホールド判定
+    if(sys.DriBlind==0){
+        if(
+            ((data.ball==0)&&(sys.BallHoldFlag==0))||
+            ((data.ball==1)&&(sys.BallHoldFlag==1))
+        ){
+            sys.BallHoldJudgeFlag=0;
+            Ball_judge.detach();
+        }
+        if(
+            ((data.ball==0)&&(sys.BallHoldFlag==1))||
+            ((data.ball==1)&&(sys.BallHoldFlag==0))
+        ){
+            if(sys.BallHoldJudgeFlag==0){
+                sys.BallHoldJudgeFlag=1;
+                Ball_judge.attach(&JudgeBallHold, .25);
+            }
+        }
+        /*
+        if(
+            !(
+                (data.irNotice==IR_CLOSER)&&
+                ((data.irPosition==10)||(data.irPosition==11)||(data.irPosition==12))
+            )
+        ){
+            sys.BallHoldJudgeFlag=0;
+            sys.BallHoldFlag=0;
+            Ball_judge.detach();
+        }
+        */
+    }
+    else{
+        sys.BallHoldFlag=0;
+    }
+}
+//readsensor
+void ReadCmps(void){
+    cmps_set.cmps = hmc.sample()/10.0;
+}
+void ReadPing(void){
+    uint16_t spi_data;
+    //Ultra Sonic Wave
+    spi_ss[1]=0;
+    wait_us(200);
+    
+    spi_data = spi.write(0xABCD);
+    
+    wait_us(200);
+    spi_ss[1]=1;
+    
+    data.ping[0] = (spi_data&0x00FF)>>0;
+    data.ping[1] = (spi_data&0xFF00)>>8;
+}
+void ReadPing2(void){
+    uint16_t spi_data;
+    //Ultra Sonic Wave
+    spi_ss[0]=0;
+    wait_us(200);
+    
+    spi_data = spi.write(0xABCD);
+    
+    wait_us(200);
+    spi_ss[0]=1;
+    
+    data.ping[2] = (spi_data&0x00FF)>>0;
+    data.ping[3] = (spi_data&0xFF00)>>8;
+}
+void ReadIr(void){
+    uint16_t spi_data;
+    
+    //Ir
+    spi_ss[3]=0;
+    wait_us(200);
+    
+    spi_data = spi.write(0xABCD);
+    
+    wait_us(200);
+    spi_ss[3]=1;
+    /*
+    //key/phaseL/phaseS/long/short/
+    // 2/     3/     3/   4/    4/
+    data.irKey                  = (spi_data&0xC000)>>14;//1100000000000000
+    data.irValPhase[IR_LONG]    = (spi_data&0x3800)>>11;//0011100000000000
+    data.irValPhase[IR_SHORT]   = (spi_data&0x0700)>>8;///0000011100000000
+    data.irSpot[IR_LONG]        = (spi_data&0x00F0)>>4;///0000000011110000
+    data.irSpot[IR_SHORT]       = (spi_data&0x000F)>>0;///0000000000001111
+    */
+    
+    //key/phaseL/phaseS/diffL/position/
+    // 2/     3/     3/    3/       5/
+    data.irKey                  = (spi_data&0xC000)>>14;//1100000000000000
+    data.irValPhase[IR_LONG]    = (spi_data&0x3800)>>11;//0011100000000000
+    data.irValPhase[IR_SHORT]   = (spi_data&0x0700)>>8;///0000011100000000
+    data.irDif[IR_LONG]         = (spi_data&0x00E0)>>5;///0000000011100000
+    data.irPosition             = (spi_data&0x001F)>>0;///0000000000011111
+    
+    if(data.irKey!=0x2) data.irNotice=IR_NONE;
+    
+    
+    if(data.irValPhase[IR_SHORT]>=DIS_7){
+        if(data.irValPhase[IR_LONG]>=DIS_7){
+            data.irNotice=IR_NONE;
+        }
+        else{
+            if(data.irDif[IR_LONG]<=DIS_0){
+                data.irNotice=IR_NONE;
+            }
+            else{
+                data.irNotice=IR_FAR;
+            }
+        }
+    }
+    else{
+        if(data.irValPhase[IR_SHORT]>=DIS_3){
+            data.irNotice = IR_CLOSE;
+        }
+        else{
+            data.irNotice = IR_CLOSER;
+        }
+    }
+    
+    /*if(data.irValPhase[IR_LONG]>=DIS_7){
+        data.irNotice=IR_NONE;
+    }
+    else{
+        if(data.irValPhase[IR_SHORT]>=DIS_7){
+            data.irNotice=IR_FAR;
+        }
+        else{
+            if(data.irValPhase[IR_LONG]>=DIS_4){
+                data.irNotice = IR_CLOSE;
+            }
+            else{
+                data.irNotice = IR_CLOSER;
+            }
+        }
+    }*/
+    /*
+    if(data.irNotice == IR_NONE) data.irPosition=11;
+    if(data.irNotice == IR_FAR) data.irPosition=data.irSpot[IR_LONG]-1;
+    if(data.irNotice == IR_CLOSE) data.irPosition=data.irSpot[IR_SHORT]+7;
+    if(data.irNotice == IR_CLOSER) data.irPosition=data.irSpot[IR_SHORT]+7;
+    */
+    //LED[1] = LED[0];
+    //LED[0] = !LED[0];
+}
+//info
+void ValidInfo(void){
+    //LED=0xA;
+    if(sys.InfoFlag==0){
+        sys.InfoFlag=1;
+    }
+}
+void ReadInfo(void){
+    ReadIr();
+    PidUpdate();
+    ReadPing();
+    ReadPing2();
+}
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/main_processing/strategy_parts/input.h	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,39 @@
+#ifndef _INPUT_H_
+#define _INPUT_H_
+
+//line
+void ReadLine(void);
+//line_hold
+void LineRanking_A(void);
+void LineRanking_B(void);
+void LineRanking_C(void);
+void LineRankClear(void);
+//line raw
+void LineRawCall_A(void);
+void LineRawCall_B(void);
+void LineRawCall_C(void);
+void LineRawClear_A(void);
+void LineRawClear_B(void);
+void LineRawClear_C(void);
+
+void LineRawCall_ALL(void);
+void LineRawClear_ALL(void);
+void LineRawRankClear(void);
+void LineRawLogReset(void);
+void LineRawRanking_A(void);
+void LineRawRanking_B(void);
+void LineRawRanking_C(void);
+//ball
+uint8_t ReadBall(void);
+void JudgeBallHolding(void);
+//other
+void ReadCmps(void);
+void ReadPing(void);
+void ReadPing2(void);
+void ReadIr(void);
+//info
+void ValidInfo(void);
+void ReadInfo(void);
+
+#endif /*_INPUT_H_*/
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/main_processing/strategy_parts/output.cpp	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,159 @@
+#include "mbed.h"
+#include "extern.h"
+
+//pid&cmps
+void PidUpdate(void)
+{
+    cmps_set.cmps = hmc.sample()/10.0;
+    cmps_set.InputPID = 
+    fmod(
+        (
+            cmps_set.cmps+
+            (cmps_set.CmpsDiff
+                -cmps_set.FrontDeg
+                -cmps_set.AtkDeg*(sys.TurnAtkBlind==0)
+                -cmps_set.HoldDeg*(sys.TurnHoldBlind==0)
+                -cmps_set.GoalDeg*(sys.TurnDriBlind==0)
+            )+
+            7200.0
+        ),
+        360.0
+    );//0<cmps_set.cmps<359.0
+    pid.setProcessValue(cmps_set.InputPID);
+    cmps_set.OutputPID = -pid.compute();
+    /*if((abs(cmps_set.OutputPID)<PID_OUT_MIN)&&(cmps_set.OutputPID!=0)){
+        if(cmps_set.OutputPID>0) cmps_set.OutputPID=PID_OUT_MIN;
+        else cmps_set.OutputPID=-PID_OUT_MIN;
+    }*/
+}
+void HmcReset(void){
+    hmc_reset=HMC_RST;
+    wait_us(100);
+    hmc_reset=HMC_RUN;
+}
+void TurnAttack(void){
+    cmps_set.AtkDeg = 30;
+}
+void DriveTurn(void){
+    if(sys.TurnAtkBlind==1) return;
+    if(sys.TurnStopFlag==1) return;
+    
+    if(
+        //(data.ping[L_PING]<data.ping[R_PING])||
+        ((data.lnRawOrderLog1[0]==B_SPOT)&&(data.lnRawOrderLog1[1]!=A_SPOT)&&(data.lnRawOrder[0]==LINE_EMPTY))
+    ){
+        cmps_set.AtkDeg = 150;
+        if((sys.TurnDriBlind==0)&&(cmps_set.GoalDeg>0)){
+            cmps_set.AtkDeg = -cmps_set.GoalDeg*2;
+        }
+    }
+    else if(
+        //(data.ping[L_PING]>data.ping[R_PING])||
+         ((data.lnRawOrderLog1[0]==A_SPOT)&&(data.lnRawOrderLog1[1]!=B_SPOT)&&(data.lnRawOrder[0]==LINE_EMPTY))
+    ){
+        cmps_set.AtkDeg = -150;
+        if((sys.TurnDriBlind==0)&&(cmps_set.GoalDeg<0)){
+            cmps_set.AtkDeg = cmps_set.GoalDeg*2;
+        }
+    }
+    else{
+        cmps_set.AtkDeg = 0;
+    }
+    if((sys.TurnDriBlind==0)&&(cmps_set.GoalDeg!=0)){
+        Turn_timeout.attach(&TurnSignal, .25);
+        Turn_stop.attach(&ValidTurn, .5);
+    }
+    else{
+        Turn_timeout.attach(&TurnSignal, .25);
+        Turn_stop.attach(&ValidTurn, .5);
+    }
+    sys.TurnStopFlag=1;
+    
+}
+void TurnSignal(void){
+    cmps_set.AtkDeg = 0;
+}
+void ValidTurn(void){
+    sys.TurnStopFlag=0;
+}
+/*void ValidPidUpdate(void){
+    if(sys.PidFlag==0){
+        sys.PidFlag=1;
+    }
+}*/
+void FaceToFront(void){
+    cmps_set.AtkDeg=0;
+}
+//motor
+void ValidTx_motor(void){
+    if(sys.MotorFlag==0){
+        sys.MotorFlag=1;
+    }
+}
+void tx_motor(){//モーターへの送信
+    array2(MD_1CH*speed[1],MD_2CH*speed[0],MD_3CH*speed[2],MD_4CH*speed[3]);//右後左ド
+    //array2((1)*speed[1],(1)*speed[0],(-1)*speed[2],(1)*speed[3]);//右後左ドgreen
+    //array2((1)*speed[1],(1)*speed[0],(1)*speed[2],(-1)*speed[3]);//右後左ドred
+    motor.printf("%s",StringFIN.c_str());
+}
+void move(int vx, int vy, int vs){//三輪オムニの移動(基本の形)
+    uint8_t i;
+    double pwm[4] = {0};
+    
+    pwm[0] = (double)((vx) + vs);
+    pwm[1] = (double)((-0.5 * vx) + ((sqrt(3.0) / 2.0)  * vy) + vs);
+    pwm[2] = (double)((-0.5 * vx) + ((-sqrt(3.0) / 2.0) * vy) + vs);
+    pwm[3] = (sys.dri_pow)*(sys.DribbleFlag)*(sys.DriMotorBlind==0);
+
+    for(i = 0; i < 4; i++){
+        if(pwm[i] > 100){
+            pwm[i] = 100;
+        } else if(pwm[i] < -100){
+            pwm[i] = -100;
+        }
+        speed[i] = pwm[i];
+    }
+}
+//solenoid
+void DriveSolenoid(void){
+    if(sys.KickBlind==1) return;
+    if(sys.KickStopFlag==1) return;
+    
+    kicker=1;
+    sys.KickStopFlag=1;
+    Solenoid_timeout.attach(&SolenoidSignal, .5);
+    Kick_stop.attach(&ValidSolenoid, 2.0);
+}
+void DriveSolenoidJudge(void){
+    if(sys.DriBlind==0) return;
+    if((data.irNotice==IR_CLOSER)&&((data.irPosition==10)||(data.irPosition==11)||(data.irPosition==12))){
+        DriveTurn();
+        DriveSolenoid();
+    }
+}
+void SolenoidSignal(void){
+    kicker=0;
+}
+void ValidSolenoid(void){
+    sys.KickStopFlag=0;
+}
+//ball
+void JudgeBallHold(void){
+    if(data.ball==1){
+        sys.BallHoldFlag=1;
+    }
+    else if(data.ball==0){
+        sys.BallHoldFlag=0;
+    }
+    sys.BallHoldJudgeFlag=0;
+}
+//line
+void LineLiberate(void){
+    LineKeeper = LINE_FREE;
+    wait_us(10);
+    LineKeeper = LINE_FIX;
+}
+//math
+uint8_t GetBit(uint8_t n, uint8_t bit){
+    return (n>>(bit-1))%2;
+}
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/main_processing/strategy_parts/output.h	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,30 @@
+#ifndef _OUTPUT_H_
+#define _OUTPUT_H_
+
+//pid&cmps
+void PidUpdate(void);
+void HmcReset(void);
+void TurnAttack(void);
+void DriveTurn(void);
+void TurnSignal(void);
+void ValidTurn(void);
+
+void ValidPidUpdate(void);
+void FaceToFront(void);
+//motor
+void ValidTx_motor(void);
+void tx_motor();
+void move(int vx, int vy, int vs);
+//solenoid
+void DriveSolenoid(void);
+void DriveSolenoidJudge(void);
+void SolenoidSignal(void);
+void ValidSolenoid(void);
+//ball
+void JudgeBallHold(void);
+//line
+void LineLiberate(void);
+//math
+uint8_t GetBit(uint8_t n, uint8_t bit);
+
+#endif /*_OUTPUT_H_*/
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed.bld	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,1 @@
+http://mbed.org/users/mbed_official/code/mbed/builds/6c34061e7c34
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/minilib/MathTable.h	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,729 @@
+#ifndef _MATH_TABLE_H_
+#define _MATH_TABLE_H_
+/*
+const double SinTable[3600]={
+0.00000 ,   0.00175 ,   0.00349 ,   0.00524 ,   0.00698 ,   0.00873 ,   0.01047 ,   0.01222 ,   0.01396 ,   0.01571 ,   
+0.01745 ,   0.01920 ,   0.02094 ,   0.02269 ,   0.02443 ,   0.02618 ,   0.02792 ,   0.02967 ,   0.03141 ,   0.03316 ,   
+0.03490 ,   0.03664 ,   0.03839 ,   0.04013 ,   0.04188 ,   0.04362 ,   0.04536 ,   0.04711 ,   0.04885 ,   0.05059 ,   
+0.05234 ,   0.05408 ,   0.05582 ,   0.05756 ,   0.05931 ,   0.06105 ,   0.06279 ,   0.06453 ,   0.06627 ,   0.06802 ,   
+0.06976 ,   0.07150 ,   0.07324 ,   0.07498 ,   0.07672 ,   0.07846 ,   0.08020 ,   0.08194 ,   0.08368 ,   0.08542 ,   
+0.08716 ,   0.08889 ,   0.09063 ,   0.09237 ,   0.09411 ,   0.09585 ,   0.09758 ,   0.09932 ,   0.10106 ,   0.10279 ,   
+0.10453 ,   0.10626 ,   0.10800 ,   0.10973 ,   0.11147 ,   0.11320 ,   0.11494 ,   0.11667 ,   0.11840 ,   0.12014 ,   
+0.12187 ,   0.12360 ,   0.12533 ,   0.12706 ,   0.12880 ,   0.13053 ,   0.13226 ,   0.13399 ,   0.13572 ,   0.13744 ,   
+0.13917 ,   0.14090 ,   0.14263 ,   0.14436 ,   0.14608 ,   0.14781 ,   0.14954 ,   0.15126 ,   0.15299 ,   0.15471 ,   
+0.15643 ,   0.15816 ,   0.15988 ,   0.16160 ,   0.16333 ,   0.16505 ,   0.16677 ,   0.16849 ,   0.17021 ,   0.17193 ,   
+0.17365 ,   0.17537 ,   0.17708 ,   0.17880 ,   0.18052 ,   0.18224 ,   0.18395 ,   0.18567 ,   0.18738 ,   0.18910 ,   
+0.19081 ,   0.19252 ,   0.19423 ,   0.19595 ,   0.19766 ,   0.19937 ,   0.20108 ,   0.20279 ,   0.20450 ,   0.20620 ,   
+0.20791 ,   0.20962 ,   0.21132 ,   0.21303 ,   0.21474 ,   0.21644 ,   0.21814 ,   0.21985 ,   0.22155 ,   0.22325 ,   
+0.22495 ,   0.22665 ,   0.22835 ,   0.23005 ,   0.23175 ,   0.23345 ,   0.23514 ,   0.23684 ,   0.23853 ,   0.24023 ,   
+0.24192 ,   0.24362 ,   0.24531 ,   0.24700 ,   0.24869 ,   0.25038 ,   0.25207 ,   0.25376 ,   0.25545 ,   0.25713 ,   
+0.25882 ,   0.26050 ,   0.26219 ,   0.26387 ,   0.26556 ,   0.26724 ,   0.26892 ,   0.27060 ,   0.27228 ,   0.27396 ,   
+0.27564 ,   0.27731 ,   0.27899 ,   0.28067 ,   0.28234 ,   0.28402 ,   0.28569 ,   0.28736 ,   0.28903 ,   0.29070 ,   
+0.29237 ,   0.29404 ,   0.29571 ,   0.29737 ,   0.29904 ,   0.30071 ,   0.30237 ,   0.30403 ,   0.30570 ,   0.30736 ,   
+0.30902 ,   0.31068 ,   0.31233 ,   0.31399 ,   0.31565 ,   0.31730 ,   0.31896 ,   0.32061 ,   0.32227 ,   0.32392 ,   
+0.32557 ,   0.32722 ,   0.32887 ,   0.33051 ,   0.33216 ,   0.33381 ,   0.33545 ,   0.33710 ,   0.33874 ,   0.34038 ,   
+0.34202 ,   0.34366 ,   0.34530 ,   0.34694 ,   0.34857 ,   0.35021 ,   0.35184 ,   0.35347 ,   0.35511 ,   0.35674 ,   
+0.35837 ,   0.36000 ,   0.36162 ,   0.36325 ,   0.36488 ,   0.36650 ,   0.36812 ,   0.36975 ,   0.37137 ,   0.37299 ,   
+0.37461 ,   0.37622 ,   0.37784 ,   0.37946 ,   0.38107 ,   0.38268 ,   0.38430 ,   0.38591 ,   0.38752 ,   0.38912 ,   
+0.39073 ,   0.39234 ,   0.39394 ,   0.39555 ,   0.39715 ,   0.39875 ,   0.40035 ,   0.40195 ,   0.40355 ,   0.40514 ,   
+0.40674 ,   0.40833 ,   0.40992 ,   0.41151 ,   0.41310 ,   0.41469 ,   0.41628 ,   0.41787 ,   0.41945 ,   0.42104 ,   
+0.42262 ,   0.42420 ,   0.42578 ,   0.42736 ,   0.42894 ,   0.43051 ,   0.43209 ,   0.43366 ,   0.43523 ,   0.43680 ,   
+0.43837 ,   0.43994 ,   0.44151 ,   0.44307 ,   0.44464 ,   0.44620 ,   0.44776 ,   0.44932 ,   0.45088 ,   0.45243 ,   
+0.45399 ,   0.45554 ,   0.45710 ,   0.45865 ,   0.46020 ,   0.46175 ,   0.46330 ,   0.46484 ,   0.46639 ,   0.46793 ,   
+0.46947 ,   0.47101 ,   0.47255 ,   0.47409 ,   0.47562 ,   0.47716 ,   0.47869 ,   0.48022 ,   0.48175 ,   0.48328 ,   
+0.48481 ,   0.48634 ,   0.48786 ,   0.48938 ,   0.49090 ,   0.49242 ,   0.49394 ,   0.49546 ,   0.49697 ,   0.49849 ,   
+0.50000 ,   0.50151 ,   0.50302 ,   0.50453 ,   0.50603 ,   0.50754 ,   0.50904 ,   0.51054 ,   0.51204 ,   0.51354 ,   
+0.51504 ,   0.51653 ,   0.51803 ,   0.51952 ,   0.52101 ,   0.52250 ,   0.52399 ,   0.52547 ,   0.52696 ,   0.52844 ,   
+0.52992 ,   0.53140 ,   0.53288 ,   0.53435 ,   0.53583 ,   0.53730 ,   0.53877 ,   0.54024 ,   0.54171 ,   0.54317 ,   
+0.54464 ,   0.54610 ,   0.54756 ,   0.54902 ,   0.55048 ,   0.55194 ,   0.55339 ,   0.55484 ,   0.55630 ,   0.55775 ,   
+0.55919 ,   0.56064 ,   0.56208 ,   0.56353 ,   0.56497 ,   0.56641 ,   0.56784 ,   0.56928 ,   0.57071 ,   0.57215 ,   
+0.57358 ,   0.57501 ,   0.57643 ,   0.57786 ,   0.57928 ,   0.58070 ,   0.58212 ,   0.58354 ,   0.58496 ,   0.58637 ,   
+0.58779 ,   0.58920 ,   0.59061 ,   0.59201 ,   0.59342 ,   0.59482 ,   0.59622 ,   0.59763 ,   0.59902 ,   0.60042 ,   
+0.60182 ,   0.60321 ,   0.60460 ,   0.60599 ,   0.60738 ,   0.60876 ,   0.61015 ,   0.61153 ,   0.61291 ,   0.61429 ,   
+0.61566 ,   0.61704 ,   0.61841 ,   0.61978 ,   0.62115 ,   0.62251 ,   0.62388 ,   0.62524 ,   0.62660 ,   0.62796 ,   
+0.62932 ,   0.63068 ,   0.63203 ,   0.63338 ,   0.63473 ,   0.63608 ,   0.63742 ,   0.63877 ,   0.64011 ,   0.64145 ,   
+0.64279 ,   0.64412 ,   0.64546 ,   0.64679 ,   0.64812 ,   0.64945 ,   0.65077 ,   0.65210 ,   0.65342 ,   0.65474 ,   
+0.65606 ,   0.65738 ,   0.65869 ,   0.66000 ,   0.66131 ,   0.66262 ,   0.66393 ,   0.66523 ,   0.66653 ,   0.66783 ,   
+0.66913 ,   0.67043 ,   0.67172 ,   0.67301 ,   0.67430 ,   0.67559 ,   0.67688 ,   0.67816 ,   0.67944 ,   0.68072 ,   
+0.68200 ,   0.68327 ,   0.68455 ,   0.68582 ,   0.68709 ,   0.68835 ,   0.68962 ,   0.69088 ,   0.69214 ,   0.69340 ,   
+0.69466 ,   0.69591 ,   0.69717 ,   0.69842 ,   0.69966 ,   0.70091 ,   0.70215 ,   0.70339 ,   0.70463 ,   0.70587 ,   
+0.70711 ,   0.70834 ,   0.70957 ,   0.71080 ,   0.71203 ,   0.71325 ,   0.71447 ,   0.71569 ,   0.71691 ,   0.71813 ,   
+0.71934 ,   0.72055 ,   0.72176 ,   0.72297 ,   0.72417 ,   0.72537 ,   0.72657 ,   0.72777 ,   0.72897 ,   0.73016 ,   
+0.73135 ,   0.73254 ,   0.73373 ,   0.73491 ,   0.73610 ,   0.73728 ,   0.73846 ,   0.73963 ,   0.74080 ,   0.74198 ,   
+0.74314 ,   0.74431 ,   0.74548 ,   0.74664 ,   0.74780 ,   0.74896 ,   0.75011 ,   0.75126 ,   0.75241 ,   0.75356 ,   
+0.75471 ,   0.75585 ,   0.75700 ,   0.75813 ,   0.75927 ,   0.76041 ,   0.76154 ,   0.76267 ,   0.76380 ,   0.76492 ,   
+0.76604 ,   0.76717 ,   0.76828 ,   0.76940 ,   0.77051 ,   0.77162 ,   0.77273 ,   0.77384 ,   0.77494 ,   0.77605 ,   
+0.77715 ,   0.77824 ,   0.77934 ,   0.78043 ,   0.78152 ,   0.78261 ,   0.78369 ,   0.78478 ,   0.78586 ,   0.78694 ,   
+0.78801 ,   0.78908 ,   0.79016 ,   0.79122 ,   0.79229 ,   0.79335 ,   0.79441 ,   0.79547 ,   0.79653 ,   0.79758 ,   
+0.79864 ,   0.79968 ,   0.80073 ,   0.80178 ,   0.80282 ,   0.80386 ,   0.80489 ,   0.80593 ,   0.80696 ,   0.80799 ,   
+0.80902 ,   0.81004 ,   0.81106 ,   0.81208 ,   0.81310 ,   0.81412 ,   0.81513 ,   0.81614 ,   0.81714 ,   0.81815 ,   
+0.81915 ,   0.82015 ,   0.82115 ,   0.82214 ,   0.82314 ,   0.82413 ,   0.82511 ,   0.82610 ,   0.82708 ,   0.82806 ,   
+0.82904 ,   0.83001 ,   0.83098 ,   0.83195 ,   0.83292 ,   0.83389 ,   0.83485 ,   0.83581 ,   0.83676 ,   0.83772 ,   
+0.83867 ,   0.83962 ,   0.84057 ,   0.84151 ,   0.84245 ,   0.84339 ,   0.84433 ,   0.84526 ,   0.84619 ,   0.84712 ,   
+0.84805 ,   0.84897 ,   0.84989 ,   0.85081 ,   0.85173 ,   0.85264 ,   0.85355 ,   0.85446 ,   0.85536 ,   0.85627 ,   
+0.85717 ,   0.85806 ,   0.85896 ,   0.85985 ,   0.86074 ,   0.86163 ,   0.86251 ,   0.86340 ,   0.86427 ,   0.86515 ,   
+0.86603 ,   0.86690 ,   0.86777 ,   0.86863 ,   0.86949 ,   0.87036 ,   0.87121 ,   0.87207 ,   0.87292 ,   0.87377 ,   
+0.87462 ,   0.87546 ,   0.87631 ,   0.87715 ,   0.87798 ,   0.87882 ,   0.87965 ,   0.88048 ,   0.88130 ,   0.88213 ,   
+0.88295 ,   0.88377 ,   0.88458 ,   0.88539 ,   0.88620 ,   0.88701 ,   0.88782 ,   0.88862 ,   0.88942 ,   0.89021 ,   
+0.89101 ,   0.89180 ,   0.89259 ,   0.89337 ,   0.89415 ,   0.89493 ,   0.89571 ,   0.89649 ,   0.89726 ,   0.89803 ,   
+0.89879 ,   0.89956 ,   0.90032 ,   0.90108 ,   0.90183 ,   0.90259 ,   0.90334 ,   0.90408 ,   0.90483 ,   0.90557 ,   
+0.90631 ,   0.90704 ,   0.90778 ,   0.90851 ,   0.90924 ,   0.90996 ,   0.91068 ,   0.91140 ,   0.91212 ,   0.91283 ,   
+0.91355 ,   0.91425 ,   0.91496 ,   0.91566 ,   0.91636 ,   0.91706 ,   0.91775 ,   0.91845 ,   0.91914 ,   0.91982 ,   
+0.92050 ,   0.92119 ,   0.92186 ,   0.92254 ,   0.92321 ,   0.92388 ,   0.92455 ,   0.92521 ,   0.92587 ,   0.92653 ,   
+0.92718 ,   0.92784 ,   0.92849 ,   0.92913 ,   0.92978 ,   0.93042 ,   0.93106 ,   0.93169 ,   0.93232 ,   0.93295 ,   
+0.93358 ,   0.93420 ,   0.93483 ,   0.93544 ,   0.93606 ,   0.93667 ,   0.93728 ,   0.93789 ,   0.93849 ,   0.93909 ,   
+0.93969 ,   0.94029 ,   0.94088 ,   0.94147 ,   0.94206 ,   0.94264 ,   0.94322 ,   0.94380 ,   0.94438 ,   0.94495 ,   
+0.94552 ,   0.94609 ,   0.94665 ,   0.94721 ,   0.94777 ,   0.94832 ,   0.94888 ,   0.94943 ,   0.94997 ,   0.95052 ,   
+0.95106 ,   0.95159 ,   0.95213 ,   0.95266 ,   0.95319 ,   0.95372 ,   0.95424 ,   0.95476 ,   0.95528 ,   0.95579 ,   
+0.95630 ,   0.95681 ,   0.95732 ,   0.95782 ,   0.95832 ,   0.95882 ,   0.95931 ,   0.95981 ,   0.96029 ,   0.96078 ,   
+0.96126 ,   0.96174 ,   0.96222 ,   0.96269 ,   0.96316 ,   0.96363 ,   0.96410 ,   0.96456 ,   0.96502 ,   0.96547 ,   
+0.96593 ,   0.96638 ,   0.96682 ,   0.96727 ,   0.96771 ,   0.96815 ,   0.96858 ,   0.96902 ,   0.96945 ,   0.96987 ,   
+0.97030 ,   0.97072 ,   0.97113 ,   0.97155 ,   0.97196 ,   0.97237 ,   0.97278 ,   0.97318 ,   0.97358 ,   0.97398 ,   
+0.97437 ,   0.97476 ,   0.97515 ,   0.97553 ,   0.97592 ,   0.97630 ,   0.97667 ,   0.97705 ,   0.97742 ,   0.97778 ,   
+0.97815 ,   0.97851 ,   0.97887 ,   0.97922 ,   0.97958 ,   0.97992 ,   0.98027 ,   0.98061 ,   0.98096 ,   0.98129 ,   
+0.98163 ,   0.98196 ,   0.98229 ,   0.98261 ,   0.98294 ,   0.98325 ,   0.98357 ,   0.98389 ,   0.98420 ,   0.98450 ,   
+0.98481 ,   0.98511 ,   0.98541 ,   0.98570 ,   0.98600 ,   0.98629 ,   0.98657 ,   0.98686 ,   0.98714 ,   0.98741 ,   
+0.98769 ,   0.98796 ,   0.98823 ,   0.98849 ,   0.98876 ,   0.98902 ,   0.98927 ,   0.98953 ,   0.98978 ,   0.99002 ,   
+0.99027 ,   0.99051 ,   0.99075 ,   0.99098 ,   0.99122 ,   0.99144 ,   0.99167 ,   0.99189 ,   0.99211 ,   0.99233 ,   
+0.99255 ,   0.99276 ,   0.99297 ,   0.99317 ,   0.99337 ,   0.99357 ,   0.99377 ,   0.99396 ,   0.99415 ,   0.99434 ,   
+0.99452 ,   0.99470 ,   0.99488 ,   0.99506 ,   0.99523 ,   0.99540 ,   0.99556 ,   0.99572 ,   0.99588 ,   0.99604 ,   
+0.99619 ,   0.99635 ,   0.99649 ,   0.99664 ,   0.99678 ,   0.99692 ,   0.99705 ,   0.99719 ,   0.99731 ,   0.99744 ,   
+0.99756 ,   0.99768 ,   0.99780 ,   0.99792 ,   0.99803 ,   0.99813 ,   0.99824 ,   0.99834 ,   0.99844 ,   0.99854 ,   
+0.99863 ,   0.99872 ,   0.99881 ,   0.99889 ,   0.99897 ,   0.99905 ,   0.99912 ,   0.99919 ,   0.99926 ,   0.99933 ,   
+0.99939 ,   0.99945 ,   0.99951 ,   0.99956 ,   0.99961 ,   0.99966 ,   0.99970 ,   0.99974 ,   0.99978 ,   0.99982 ,   
+0.99985 ,   0.99988 ,   0.99990 ,   0.99993 ,   0.99995 ,   0.99996 ,   0.99998 ,   0.99999 ,   0.99999 ,   1.00000 ,   
+1.00000 ,   1.00000 ,   0.99999 ,   0.99999 ,   0.99998 ,   0.99996 ,   0.99995 ,   0.99993 ,   0.99990 ,   0.99988 ,   
+0.99985 ,   0.99982 ,   0.99978 ,   0.99974 ,   0.99970 ,   0.99966 ,   0.99961 ,   0.99956 ,   0.99951 ,   0.99945 ,   
+0.99939 ,   0.99933 ,   0.99926 ,   0.99919 ,   0.99912 ,   0.99905 ,   0.99897 ,   0.99889 ,   0.99881 ,   0.99872 ,   
+0.99863 ,   0.99854 ,   0.99844 ,   0.99834 ,   0.99824 ,   0.99813 ,   0.99803 ,   0.99792 ,   0.99780 ,   0.99768 ,   
+0.99756 ,   0.99744 ,   0.99731 ,   0.99719 ,   0.99705 ,   0.99692 ,   0.99678 ,   0.99664 ,   0.99649 ,   0.99635 ,   
+0.99619 ,   0.99604 ,   0.99588 ,   0.99572 ,   0.99556 ,   0.99540 ,   0.99523 ,   0.99506 ,   0.99488 ,   0.99470 ,   
+0.99452 ,   0.99434 ,   0.99415 ,   0.99396 ,   0.99377 ,   0.99357 ,   0.99337 ,   0.99317 ,   0.99297 ,   0.99276 ,   
+0.99255 ,   0.99233 ,   0.99211 ,   0.99189 ,   0.99167 ,   0.99144 ,   0.99122 ,   0.99098 ,   0.99075 ,   0.99051 ,   
+0.99027 ,   0.99002 ,   0.98978 ,   0.98953 ,   0.98927 ,   0.98902 ,   0.98876 ,   0.98849 ,   0.98823 ,   0.98796 ,   
+0.98769 ,   0.98741 ,   0.98714 ,   0.98686 ,   0.98657 ,   0.98629 ,   0.98600 ,   0.98570 ,   0.98541 ,   0.98511 ,   
+0.98481 ,   0.98450 ,   0.98420 ,   0.98389 ,   0.98357 ,   0.98325 ,   0.98294 ,   0.98261 ,   0.98229 ,   0.98196 ,   
+0.98163 ,   0.98129 ,   0.98096 ,   0.98061 ,   0.98027 ,   0.97992 ,   0.97958 ,   0.97922 ,   0.97887 ,   0.97851 ,   
+0.97815 ,   0.97778 ,   0.97742 ,   0.97705 ,   0.97667 ,   0.97630 ,   0.97592 ,   0.97553 ,   0.97515 ,   0.97476 ,   
+0.97437 ,   0.97398 ,   0.97358 ,   0.97318 ,   0.97278 ,   0.97237 ,   0.97196 ,   0.97155 ,   0.97113 ,   0.97072 ,   
+0.97030 ,   0.96987 ,   0.96945 ,   0.96902 ,   0.96858 ,   0.96815 ,   0.96771 ,   0.96727 ,   0.96682 ,   0.96638 ,   
+0.96593 ,   0.96547 ,   0.96502 ,   0.96456 ,   0.96410 ,   0.96363 ,   0.96316 ,   0.96269 ,   0.96222 ,   0.96174 ,   
+0.96126 ,   0.96078 ,   0.96029 ,   0.95981 ,   0.95931 ,   0.95882 ,   0.95832 ,   0.95782 ,   0.95732 ,   0.95681 ,   
+0.95630 ,   0.95579 ,   0.95528 ,   0.95476 ,   0.95424 ,   0.95372 ,   0.95319 ,   0.95266 ,   0.95213 ,   0.95159 ,   
+0.95106 ,   0.95052 ,   0.94997 ,   0.94943 ,   0.94888 ,   0.94832 ,   0.94777 ,   0.94721 ,   0.94665 ,   0.94609 ,   
+0.94552 ,   0.94495 ,   0.94438 ,   0.94380 ,   0.94322 ,   0.94264 ,   0.94206 ,   0.94147 ,   0.94088 ,   0.94029 ,   
+0.93969 ,   0.93909 ,   0.93849 ,   0.93789 ,   0.93728 ,   0.93667 ,   0.93606 ,   0.93544 ,   0.93483 ,   0.93420 ,   
+0.93358 ,   0.93295 ,   0.93232 ,   0.93169 ,   0.93106 ,   0.93042 ,   0.92978 ,   0.92913 ,   0.92849 ,   0.92784 ,   
+0.92718 ,   0.92653 ,   0.92587 ,   0.92521 ,   0.92455 ,   0.92388 ,   0.92321 ,   0.92254 ,   0.92186 ,   0.92119 ,   
+0.92050 ,   0.91982 ,   0.91914 ,   0.91845 ,   0.91775 ,   0.91706 ,   0.91636 ,   0.91566 ,   0.91496 ,   0.91425 ,   
+0.91355 ,   0.91283 ,   0.91212 ,   0.91140 ,   0.91068 ,   0.90996 ,   0.90924 ,   0.90851 ,   0.90778 ,   0.90704 ,   
+0.90631 ,   0.90557 ,   0.90483 ,   0.90408 ,   0.90334 ,   0.90259 ,   0.90183 ,   0.90108 ,   0.90032 ,   0.89956 ,   
+0.89879 ,   0.89803 ,   0.89726 ,   0.89649 ,   0.89571 ,   0.89493 ,   0.89415 ,   0.89337 ,   0.89259 ,   0.89180 ,   
+0.89101 ,   0.89021 ,   0.88942 ,   0.88862 ,   0.88782 ,   0.88701 ,   0.88620 ,   0.88539 ,   0.88458 ,   0.88377 ,   
+0.88295 ,   0.88213 ,   0.88130 ,   0.88048 ,   0.87965 ,   0.87882 ,   0.87798 ,   0.87715 ,   0.87631 ,   0.87546 ,   
+0.87462 ,   0.87377 ,   0.87292 ,   0.87207 ,   0.87121 ,   0.87036 ,   0.86949 ,   0.86863 ,   0.86777 ,   0.86690 ,   
+0.86603 ,   0.86515 ,   0.86427 ,   0.86340 ,   0.86251 ,   0.86163 ,   0.86074 ,   0.85985 ,   0.85896 ,   0.85806 ,   
+0.85717 ,   0.85627 ,   0.85536 ,   0.85446 ,   0.85355 ,   0.85264 ,   0.85173 ,   0.85081 ,   0.84989 ,   0.84897 ,   
+0.84805 ,   0.84712 ,   0.84619 ,   0.84526 ,   0.84433 ,   0.84339 ,   0.84245 ,   0.84151 ,   0.84057 ,   0.83962 ,   
+0.83867 ,   0.83772 ,   0.83676 ,   0.83581 ,   0.83485 ,   0.83389 ,   0.83292 ,   0.83195 ,   0.83098 ,   0.83001 ,   
+0.82904 ,   0.82806 ,   0.82708 ,   0.82610 ,   0.82511 ,   0.82413 ,   0.82314 ,   0.82214 ,   0.82115 ,   0.82015 ,   
+0.81915 ,   0.81815 ,   0.81714 ,   0.81614 ,   0.81513 ,   0.81412 ,   0.81310 ,   0.81208 ,   0.81106 ,   0.81004 ,   
+0.80902 ,   0.80799 ,   0.80696 ,   0.80593 ,   0.80489 ,   0.80386 ,   0.80282 ,   0.80178 ,   0.80073 ,   0.79968 ,   
+0.79864 ,   0.79758 ,   0.79653 ,   0.79547 ,   0.79441 ,   0.79335 ,   0.79229 ,   0.79122 ,   0.79016 ,   0.78908 ,   
+0.78801 ,   0.78694 ,   0.78586 ,   0.78478 ,   0.78369 ,   0.78261 ,   0.78152 ,   0.78043 ,   0.77934 ,   0.77824 ,   
+0.77715 ,   0.77605 ,   0.77494 ,   0.77384 ,   0.77273 ,   0.77162 ,   0.77051 ,   0.76940 ,   0.76828 ,   0.76717 ,   
+0.76604 ,   0.76492 ,   0.76380 ,   0.76267 ,   0.76154 ,   0.76041 ,   0.75927 ,   0.75813 ,   0.75700 ,   0.75585 ,   
+0.75471 ,   0.75356 ,   0.75241 ,   0.75126 ,   0.75011 ,   0.74896 ,   0.74780 ,   0.74664 ,   0.74548 ,   0.74431 ,   
+0.74314 ,   0.74198 ,   0.74080 ,   0.73963 ,   0.73846 ,   0.73728 ,   0.73610 ,   0.73491 ,   0.73373 ,   0.73254 ,   
+0.73135 ,   0.73016 ,   0.72897 ,   0.72777 ,   0.72657 ,   0.72537 ,   0.72417 ,   0.72297 ,   0.72176 ,   0.72055 ,   
+0.71934 ,   0.71813 ,   0.71691 ,   0.71569 ,   0.71447 ,   0.71325 ,   0.71203 ,   0.71080 ,   0.70957 ,   0.70834 ,   
+0.70711 ,   0.70587 ,   0.70463 ,   0.70339 ,   0.70215 ,   0.70091 ,   0.69966 ,   0.69842 ,   0.69717 ,   0.69591 ,   
+0.69466 ,   0.69340 ,   0.69214 ,   0.69088 ,   0.68962 ,   0.68835 ,   0.68709 ,   0.68582 ,   0.68455 ,   0.68327 ,   
+0.68200 ,   0.68072 ,   0.67944 ,   0.67816 ,   0.67688 ,   0.67559 ,   0.67430 ,   0.67301 ,   0.67172 ,   0.67043 ,   
+0.66913 ,   0.66783 ,   0.66653 ,   0.66523 ,   0.66393 ,   0.66262 ,   0.66131 ,   0.66000 ,   0.65869 ,   0.65738 ,   
+0.65606 ,   0.65474 ,   0.65342 ,   0.65210 ,   0.65077 ,   0.64945 ,   0.64812 ,   0.64679 ,   0.64546 ,   0.64412 ,   
+0.64279 ,   0.64145 ,   0.64011 ,   0.63877 ,   0.63742 ,   0.63608 ,   0.63473 ,   0.63338 ,   0.63203 ,   0.63068 ,   
+0.62932 ,   0.62796 ,   0.62660 ,   0.62524 ,   0.62388 ,   0.62251 ,   0.62115 ,   0.61978 ,   0.61841 ,   0.61704 ,   
+0.61566 ,   0.61429 ,   0.61291 ,   0.61153 ,   0.61015 ,   0.60876 ,   0.60738 ,   0.60599 ,   0.60460 ,   0.60321 ,   
+0.60182 ,   0.60042 ,   0.59902 ,   0.59763 ,   0.59622 ,   0.59482 ,   0.59342 ,   0.59201 ,   0.59061 ,   0.58920 ,   
+0.58779 ,   0.58637 ,   0.58496 ,   0.58354 ,   0.58212 ,   0.58070 ,   0.57928 ,   0.57786 ,   0.57643 ,   0.57501 ,   
+0.57358 ,   0.57215 ,   0.57071 ,   0.56928 ,   0.56784 ,   0.56641 ,   0.56497 ,   0.56353 ,   0.56208 ,   0.56064 ,   
+0.55919 ,   0.55775 ,   0.55630 ,   0.55484 ,   0.55339 ,   0.55194 ,   0.55048 ,   0.54902 ,   0.54756 ,   0.54610 ,   
+0.54464 ,   0.54317 ,   0.54171 ,   0.54024 ,   0.53877 ,   0.53730 ,   0.53583 ,   0.53435 ,   0.53288 ,   0.53140 ,   
+0.52992 ,   0.52844 ,   0.52696 ,   0.52547 ,   0.52399 ,   0.52250 ,   0.52101 ,   0.51952 ,   0.51803 ,   0.51653 ,   
+0.51504 ,   0.51354 ,   0.51204 ,   0.51054 ,   0.50904 ,   0.50754 ,   0.50603 ,   0.50453 ,   0.50302 ,   0.50151 ,   
+0.50000 ,   0.49849 ,   0.49697 ,   0.49546 ,   0.49394 ,   0.49242 ,   0.49090 ,   0.48938 ,   0.48786 ,   0.48634 ,   
+0.48481 ,   0.48328 ,   0.48175 ,   0.48022 ,   0.47869 ,   0.47716 ,   0.47562 ,   0.47409 ,   0.47255 ,   0.47101 ,   
+0.46947 ,   0.46793 ,   0.46639 ,   0.46484 ,   0.46330 ,   0.46175 ,   0.46020 ,   0.45865 ,   0.45710 ,   0.45554 ,   
+0.45399 ,   0.45243 ,   0.45088 ,   0.44932 ,   0.44776 ,   0.44620 ,   0.44464 ,   0.44307 ,   0.44151 ,   0.43994 ,   
+0.43837 ,   0.43680 ,   0.43523 ,   0.43366 ,   0.43209 ,   0.43051 ,   0.42894 ,   0.42736 ,   0.42578 ,   0.42420 ,   
+0.42262 ,   0.42104 ,   0.41945 ,   0.41787 ,   0.41628 ,   0.41469 ,   0.41310 ,   0.41151 ,   0.40992 ,   0.40833 ,   
+0.40674 ,   0.40514 ,   0.40355 ,   0.40195 ,   0.40035 ,   0.39875 ,   0.39715 ,   0.39555 ,   0.39394 ,   0.39234 ,   
+0.39073 ,   0.38912 ,   0.38752 ,   0.38591 ,   0.38430 ,   0.38268 ,   0.38107 ,   0.37946 ,   0.37784 ,   0.37622 ,   
+0.37461 ,   0.37299 ,   0.37137 ,   0.36975 ,   0.36812 ,   0.36650 ,   0.36488 ,   0.36325 ,   0.36162 ,   0.36000 ,   
+0.35837 ,   0.35674 ,   0.35511 ,   0.35347 ,   0.35184 ,   0.35021 ,   0.34857 ,   0.34694 ,   0.34530 ,   0.34366 ,   
+0.34202 ,   0.34038 ,   0.33874 ,   0.33710 ,   0.33545 ,   0.33381 ,   0.33216 ,   0.33051 ,   0.32887 ,   0.32722 ,   
+0.32557 ,   0.32392 ,   0.32227 ,   0.32061 ,   0.31896 ,   0.31730 ,   0.31565 ,   0.31399 ,   0.31233 ,   0.31068 ,   
+0.30902 ,   0.30736 ,   0.30570 ,   0.30403 ,   0.30237 ,   0.30071 ,   0.29904 ,   0.29737 ,   0.29571 ,   0.29404 ,   
+0.29237 ,   0.29070 ,   0.28903 ,   0.28736 ,   0.28569 ,   0.28402 ,   0.28234 ,   0.28067 ,   0.27899 ,   0.27731 ,   
+0.27564 ,   0.27396 ,   0.27228 ,   0.27060 ,   0.26892 ,   0.26724 ,   0.26556 ,   0.26387 ,   0.26219 ,   0.26050 ,   
+0.25882 ,   0.25713 ,   0.25545 ,   0.25376 ,   0.25207 ,   0.25038 ,   0.24869 ,   0.24700 ,   0.24531 ,   0.24362 ,   
+0.24192 ,   0.24023 ,   0.23853 ,   0.23684 ,   0.23514 ,   0.23345 ,   0.23175 ,   0.23005 ,   0.22835 ,   0.22665 ,   
+0.22495 ,   0.22325 ,   0.22155 ,   0.21985 ,   0.21814 ,   0.21644 ,   0.21474 ,   0.21303 ,   0.21132 ,   0.20962 ,   
+0.20791 ,   0.20620 ,   0.20450 ,   0.20279 ,   0.20108 ,   0.19937 ,   0.19766 ,   0.19595 ,   0.19423 ,   0.19252 ,   
+0.19081 ,   0.18910 ,   0.18738 ,   0.18567 ,   0.18395 ,   0.18224 ,   0.18052 ,   0.17880 ,   0.17708 ,   0.17537 ,   
+0.17365 ,   0.17193 ,   0.17021 ,   0.16849 ,   0.16677 ,   0.16505 ,   0.16333 ,   0.16160 ,   0.15988 ,   0.15816 ,   
+0.15643 ,   0.15471 ,   0.15299 ,   0.15126 ,   0.14954 ,   0.14781 ,   0.14608 ,   0.14436 ,   0.14263 ,   0.14090 ,   
+0.13917 ,   0.13744 ,   0.13572 ,   0.13399 ,   0.13226 ,   0.13053 ,   0.12880 ,   0.12706 ,   0.12533 ,   0.12360 ,   
+0.12187 ,   0.12014 ,   0.11840 ,   0.11667 ,   0.11494 ,   0.11320 ,   0.11147 ,   0.10973 ,   0.10800 ,   0.10626 ,   
+0.10453 ,   0.10279 ,   0.10106 ,   0.09932 ,   0.09758 ,   0.09585 ,   0.09411 ,   0.09237 ,   0.09063 ,   0.08889 ,   
+0.08716 ,   0.08542 ,   0.08368 ,   0.08194 ,   0.08020 ,   0.07846 ,   0.07672 ,   0.07498 ,   0.07324 ,   0.07150 ,   
+0.06976 ,   0.06802 ,   0.06627 ,   0.06453 ,   0.06279 ,   0.06105 ,   0.05931 ,   0.05756 ,   0.05582 ,   0.05408 ,   
+0.05234 ,   0.05059 ,   0.04885 ,   0.04711 ,   0.04536 ,   0.04362 ,   0.04188 ,   0.04013 ,   0.03839 ,   0.03664 ,   
+0.03490 ,   0.03316 ,   0.03141 ,   0.02967 ,   0.02792 ,   0.02618 ,   0.02443 ,   0.02269 ,   0.02094 ,   0.01920 ,   
+0.01745 ,   0.01571 ,   0.01396 ,   0.01222 ,   0.01047 ,   0.00873 ,   0.00698 ,   0.00524 ,   0.00349 ,   0.00175 ,   
+0.00000 ,   -0.00175 ,  -0.00349 ,  -0.00524 ,  -0.00698 ,  -0.00873 ,  -0.01047 ,  -0.01222 ,  -0.01396 ,  -0.01571 ,  
+-0.01745 ,  -0.01920 ,  -0.02094 ,  -0.02269 ,  -0.02443 ,  -0.02618 ,  -0.02792 ,  -0.02967 ,  -0.03141 ,  -0.03316 ,  
+-0.03490 ,  -0.03664 ,  -0.03839 ,  -0.04013 ,  -0.04188 ,  -0.04362 ,  -0.04536 ,  -0.04711 ,  -0.04885 ,  -0.05059 ,  
+-0.05234 ,  -0.05408 ,  -0.05582 ,  -0.05756 ,  -0.05931 ,  -0.06105 ,  -0.06279 ,  -0.06453 ,  -0.06627 ,  -0.06802 ,  
+-0.06976 ,  -0.07150 ,  -0.07324 ,  -0.07498 ,  -0.07672 ,  -0.07846 ,  -0.08020 ,  -0.08194 ,  -0.08368 ,  -0.08542 ,  
+-0.08716 ,  -0.08889 ,  -0.09063 ,  -0.09237 ,  -0.09411 ,  -0.09585 ,  -0.09758 ,  -0.09932 ,  -0.10106 ,  -0.10279 ,  
+-0.10453 ,  -0.10626 ,  -0.10800 ,  -0.10973 ,  -0.11147 ,  -0.11320 ,  -0.11494 ,  -0.11667 ,  -0.11840 ,  -0.12014 ,  
+-0.12187 ,  -0.12360 ,  -0.12533 ,  -0.12706 ,  -0.12880 ,  -0.13053 ,  -0.13226 ,  -0.13399 ,  -0.13572 ,  -0.13744 ,  
+-0.13917 ,  -0.14090 ,  -0.14263 ,  -0.14436 ,  -0.14608 ,  -0.14781 ,  -0.14954 ,  -0.15126 ,  -0.15299 ,  -0.15471 ,  
+-0.15643 ,  -0.15816 ,  -0.15988 ,  -0.16160 ,  -0.16333 ,  -0.16505 ,  -0.16677 ,  -0.16849 ,  -0.17021 ,  -0.17193 ,  
+-0.17365 ,  -0.17537 ,  -0.17708 ,  -0.17880 ,  -0.18052 ,  -0.18224 ,  -0.18395 ,  -0.18567 ,  -0.18738 ,  -0.18910 ,  
+-0.19081 ,  -0.19252 ,  -0.19423 ,  -0.19595 ,  -0.19766 ,  -0.19937 ,  -0.20108 ,  -0.20279 ,  -0.20450 ,  -0.20620 ,  
+-0.20791 ,  -0.20962 ,  -0.21132 ,  -0.21303 ,  -0.21474 ,  -0.21644 ,  -0.21814 ,  -0.21985 ,  -0.22155 ,  -0.22325 ,  
+-0.22495 ,  -0.22665 ,  -0.22835 ,  -0.23005 ,  -0.23175 ,  -0.23345 ,  -0.23514 ,  -0.23684 ,  -0.23853 ,  -0.24023 ,  
+-0.24192 ,  -0.24362 ,  -0.24531 ,  -0.24700 ,  -0.24869 ,  -0.25038 ,  -0.25207 ,  -0.25376 ,  -0.25545 ,  -0.25713 ,  
+-0.25882 ,  -0.26050 ,  -0.26219 ,  -0.26387 ,  -0.26556 ,  -0.26724 ,  -0.26892 ,  -0.27060 ,  -0.27228 ,  -0.27396 ,  
+-0.27564 ,  -0.27731 ,  -0.27899 ,  -0.28067 ,  -0.28234 ,  -0.28402 ,  -0.28569 ,  -0.28736 ,  -0.28903 ,  -0.29070 ,  
+-0.29237 ,  -0.29404 ,  -0.29571 ,  -0.29737 ,  -0.29904 ,  -0.30071 ,  -0.30237 ,  -0.30403 ,  -0.30570 ,  -0.30736 ,  
+-0.30902 ,  -0.31068 ,  -0.31233 ,  -0.31399 ,  -0.31565 ,  -0.31730 ,  -0.31896 ,  -0.32061 ,  -0.32227 ,  -0.32392 ,  
+-0.32557 ,  -0.32722 ,  -0.32887 ,  -0.33051 ,  -0.33216 ,  -0.33381 ,  -0.33545 ,  -0.33710 ,  -0.33874 ,  -0.34038 ,  
+-0.34202 ,  -0.34366 ,  -0.34530 ,  -0.34694 ,  -0.34857 ,  -0.35021 ,  -0.35184 ,  -0.35347 ,  -0.35511 ,  -0.35674 ,  
+-0.35837 ,  -0.36000 ,  -0.36162 ,  -0.36325 ,  -0.36488 ,  -0.36650 ,  -0.36812 ,  -0.36975 ,  -0.37137 ,  -0.37299 ,  
+-0.37461 ,  -0.37622 ,  -0.37784 ,  -0.37946 ,  -0.38107 ,  -0.38268 ,  -0.38430 ,  -0.38591 ,  -0.38752 ,  -0.38912 ,  
+-0.39073 ,  -0.39234 ,  -0.39394 ,  -0.39555 ,  -0.39715 ,  -0.39875 ,  -0.40035 ,  -0.40195 ,  -0.40355 ,  -0.40514 ,  
+-0.40674 ,  -0.40833 ,  -0.40992 ,  -0.41151 ,  -0.41310 ,  -0.41469 ,  -0.41628 ,  -0.41787 ,  -0.41945 ,  -0.42104 ,  
+-0.42262 ,  -0.42420 ,  -0.42578 ,  -0.42736 ,  -0.42894 ,  -0.43051 ,  -0.43209 ,  -0.43366 ,  -0.43523 ,  -0.43680 ,  
+-0.43837 ,  -0.43994 ,  -0.44151 ,  -0.44307 ,  -0.44464 ,  -0.44620 ,  -0.44776 ,  -0.44932 ,  -0.45088 ,  -0.45243 ,  
+-0.45399 ,  -0.45554 ,  -0.45710 ,  -0.45865 ,  -0.46020 ,  -0.46175 ,  -0.46330 ,  -0.46484 ,  -0.46639 ,  -0.46793 ,  
+-0.46947 ,  -0.47101 ,  -0.47255 ,  -0.47409 ,  -0.47562 ,  -0.47716 ,  -0.47869 ,  -0.48022 ,  -0.48175 ,  -0.48328 ,  
+-0.48481 ,  -0.48634 ,  -0.48786 ,  -0.48938 ,  -0.49090 ,  -0.49242 ,  -0.49394 ,  -0.49546 ,  -0.49697 ,  -0.49849 ,  
+-0.50000 ,  -0.50151 ,  -0.50302 ,  -0.50453 ,  -0.50603 ,  -0.50754 ,  -0.50904 ,  -0.51054 ,  -0.51204 ,  -0.51354 ,  
+-0.51504 ,  -0.51653 ,  -0.51803 ,  -0.51952 ,  -0.52101 ,  -0.52250 ,  -0.52399 ,  -0.52547 ,  -0.52696 ,  -0.52844 ,  
+-0.52992 ,  -0.53140 ,  -0.53288 ,  -0.53435 ,  -0.53583 ,  -0.53730 ,  -0.53877 ,  -0.54024 ,  -0.54171 ,  -0.54317 ,  
+-0.54464 ,  -0.54610 ,  -0.54756 ,  -0.54902 ,  -0.55048 ,  -0.55194 ,  -0.55339 ,  -0.55484 ,  -0.55630 ,  -0.55775 ,  
+-0.55919 ,  -0.56064 ,  -0.56208 ,  -0.56353 ,  -0.56497 ,  -0.56641 ,  -0.56784 ,  -0.56928 ,  -0.57071 ,  -0.57215 ,  
+-0.57358 ,  -0.57501 ,  -0.57643 ,  -0.57786 ,  -0.57928 ,  -0.58070 ,  -0.58212 ,  -0.58354 ,  -0.58496 ,  -0.58637 ,  
+-0.58779 ,  -0.58920 ,  -0.59061 ,  -0.59201 ,  -0.59342 ,  -0.59482 ,  -0.59622 ,  -0.59763 ,  -0.59902 ,  -0.60042 ,  
+-0.60182 ,  -0.60321 ,  -0.60460 ,  -0.60599 ,  -0.60738 ,  -0.60876 ,  -0.61015 ,  -0.61153 ,  -0.61291 ,  -0.61429 ,  
+-0.61566 ,  -0.61704 ,  -0.61841 ,  -0.61978 ,  -0.62115 ,  -0.62251 ,  -0.62388 ,  -0.62524 ,  -0.62660 ,  -0.62796 ,  
+-0.62932 ,  -0.63068 ,  -0.63203 ,  -0.63338 ,  -0.63473 ,  -0.63608 ,  -0.63742 ,  -0.63877 ,  -0.64011 ,  -0.64145 ,  
+-0.64279 ,  -0.64412 ,  -0.64546 ,  -0.64679 ,  -0.64812 ,  -0.64945 ,  -0.65077 ,  -0.65210 ,  -0.65342 ,  -0.65474 ,  
+-0.65606 ,  -0.65738 ,  -0.65869 ,  -0.66000 ,  -0.66131 ,  -0.66262 ,  -0.66393 ,  -0.66523 ,  -0.66653 ,  -0.66783 ,  
+-0.66913 ,  -0.67043 ,  -0.67172 ,  -0.67301 ,  -0.67430 ,  -0.67559 ,  -0.67688 ,  -0.67816 ,  -0.67944 ,  -0.68072 ,  
+-0.68200 ,  -0.68327 ,  -0.68455 ,  -0.68582 ,  -0.68709 ,  -0.68835 ,  -0.68962 ,  -0.69088 ,  -0.69214 ,  -0.69340 ,  
+-0.69466 ,  -0.69591 ,  -0.69717 ,  -0.69842 ,  -0.69966 ,  -0.70091 ,  -0.70215 ,  -0.70339 ,  -0.70463 ,  -0.70587 ,  
+-0.70711 ,  -0.70834 ,  -0.70957 ,  -0.71080 ,  -0.71203 ,  -0.71325 ,  -0.71447 ,  -0.71569 ,  -0.71691 ,  -0.71813 ,  
+-0.71934 ,  -0.72055 ,  -0.72176 ,  -0.72297 ,  -0.72417 ,  -0.72537 ,  -0.72657 ,  -0.72777 ,  -0.72897 ,  -0.73016 ,  
+-0.73135 ,  -0.73254 ,  -0.73373 ,  -0.73491 ,  -0.73610 ,  -0.73728 ,  -0.73846 ,  -0.73963 ,  -0.74080 ,  -0.74198 ,  
+-0.74314 ,  -0.74431 ,  -0.74548 ,  -0.74664 ,  -0.74780 ,  -0.74896 ,  -0.75011 ,  -0.75126 ,  -0.75241 ,  -0.75356 ,  
+-0.75471 ,  -0.75585 ,  -0.75700 ,  -0.75813 ,  -0.75927 ,  -0.76041 ,  -0.76154 ,  -0.76267 ,  -0.76380 ,  -0.76492 ,  
+-0.76604 ,  -0.76717 ,  -0.76828 ,  -0.76940 ,  -0.77051 ,  -0.77162 ,  -0.77273 ,  -0.77384 ,  -0.77494 ,  -0.77605 ,  
+-0.77715 ,  -0.77824 ,  -0.77934 ,  -0.78043 ,  -0.78152 ,  -0.78261 ,  -0.78369 ,  -0.78478 ,  -0.78586 ,  -0.78694 ,  
+-0.78801 ,  -0.78908 ,  -0.79016 ,  -0.79122 ,  -0.79229 ,  -0.79335 ,  -0.79441 ,  -0.79547 ,  -0.79653 ,  -0.79758 ,  
+-0.79864 ,  -0.79968 ,  -0.80073 ,  -0.80178 ,  -0.80282 ,  -0.80386 ,  -0.80489 ,  -0.80593 ,  -0.80696 ,  -0.80799 ,  
+-0.80902 ,  -0.81004 ,  -0.81106 ,  -0.81208 ,  -0.81310 ,  -0.81412 ,  -0.81513 ,  -0.81614 ,  -0.81714 ,  -0.81815 ,  
+-0.81915 ,  -0.82015 ,  -0.82115 ,  -0.82214 ,  -0.82314 ,  -0.82413 ,  -0.82511 ,  -0.82610 ,  -0.82708 ,  -0.82806 ,  
+-0.82904 ,  -0.83001 ,  -0.83098 ,  -0.83195 ,  -0.83292 ,  -0.83389 ,  -0.83485 ,  -0.83581 ,  -0.83676 ,  -0.83772 ,  
+-0.83867 ,  -0.83962 ,  -0.84057 ,  -0.84151 ,  -0.84245 ,  -0.84339 ,  -0.84433 ,  -0.84526 ,  -0.84619 ,  -0.84712 ,  
+-0.84805 ,  -0.84897 ,  -0.84989 ,  -0.85081 ,  -0.85173 ,  -0.85264 ,  -0.85355 ,  -0.85446 ,  -0.85536 ,  -0.85627 ,  
+-0.85717 ,  -0.85806 ,  -0.85896 ,  -0.85985 ,  -0.86074 ,  -0.86163 ,  -0.86251 ,  -0.86340 ,  -0.86427 ,  -0.86515 ,  
+-0.86603 ,  -0.86690 ,  -0.86777 ,  -0.86863 ,  -0.86949 ,  -0.87036 ,  -0.87121 ,  -0.87207 ,  -0.87292 ,  -0.87377 ,  
+-0.87462 ,  -0.87546 ,  -0.87631 ,  -0.87715 ,  -0.87798 ,  -0.87882 ,  -0.87965 ,  -0.88048 ,  -0.88130 ,  -0.88213 ,  
+-0.88295 ,  -0.88377 ,  -0.88458 ,  -0.88539 ,  -0.88620 ,  -0.88701 ,  -0.88782 ,  -0.88862 ,  -0.88942 ,  -0.89021 ,  
+-0.89101 ,  -0.89180 ,  -0.89259 ,  -0.89337 ,  -0.89415 ,  -0.89493 ,  -0.89571 ,  -0.89649 ,  -0.89726 ,  -0.89803 ,  
+-0.89879 ,  -0.89956 ,  -0.90032 ,  -0.90108 ,  -0.90183 ,  -0.90259 ,  -0.90334 ,  -0.90408 ,  -0.90483 ,  -0.90557 ,  
+-0.90631 ,  -0.90704 ,  -0.90778 ,  -0.90851 ,  -0.90924 ,  -0.90996 ,  -0.91068 ,  -0.91140 ,  -0.91212 ,  -0.91283 ,  
+-0.91355 ,  -0.91425 ,  -0.91496 ,  -0.91566 ,  -0.91636 ,  -0.91706 ,  -0.91775 ,  -0.91845 ,  -0.91914 ,  -0.91982 ,  
+-0.92050 ,  -0.92119 ,  -0.92186 ,  -0.92254 ,  -0.92321 ,  -0.92388 ,  -0.92455 ,  -0.92521 ,  -0.92587 ,  -0.92653 ,  
+-0.92718 ,  -0.92784 ,  -0.92849 ,  -0.92913 ,  -0.92978 ,  -0.93042 ,  -0.93106 ,  -0.93169 ,  -0.93232 ,  -0.93295 ,  
+-0.93358 ,  -0.93420 ,  -0.93483 ,  -0.93544 ,  -0.93606 ,  -0.93667 ,  -0.93728 ,  -0.93789 ,  -0.93849 ,  -0.93909 ,  
+-0.93969 ,  -0.94029 ,  -0.94088 ,  -0.94147 ,  -0.94206 ,  -0.94264 ,  -0.94322 ,  -0.94380 ,  -0.94438 ,  -0.94495 ,  
+-0.94552 ,  -0.94609 ,  -0.94665 ,  -0.94721 ,  -0.94777 ,  -0.94832 ,  -0.94888 ,  -0.94943 ,  -0.94997 ,  -0.95052 ,  
+-0.95106 ,  -0.95159 ,  -0.95213 ,  -0.95266 ,  -0.95319 ,  -0.95372 ,  -0.95424 ,  -0.95476 ,  -0.95528 ,  -0.95579 ,  
+-0.95630 ,  -0.95681 ,  -0.95732 ,  -0.95782 ,  -0.95832 ,  -0.95882 ,  -0.95931 ,  -0.95981 ,  -0.96029 ,  -0.96078 ,  
+-0.96126 ,  -0.96174 ,  -0.96222 ,  -0.96269 ,  -0.96316 ,  -0.96363 ,  -0.96410 ,  -0.96456 ,  -0.96502 ,  -0.96547 ,  
+-0.96593 ,  -0.96638 ,  -0.96682 ,  -0.96727 ,  -0.96771 ,  -0.96815 ,  -0.96858 ,  -0.96902 ,  -0.96945 ,  -0.96987 ,  
+-0.97030 ,  -0.97072 ,  -0.97113 ,  -0.97155 ,  -0.97196 ,  -0.97237 ,  -0.97278 ,  -0.97318 ,  -0.97358 ,  -0.97398 ,  
+-0.97437 ,  -0.97476 ,  -0.97515 ,  -0.97553 ,  -0.97592 ,  -0.97630 ,  -0.97667 ,  -0.97705 ,  -0.97742 ,  -0.97778 ,  
+-0.97815 ,  -0.97851 ,  -0.97887 ,  -0.97922 ,  -0.97958 ,  -0.97992 ,  -0.98027 ,  -0.98061 ,  -0.98096 ,  -0.98129 ,  
+-0.98163 ,  -0.98196 ,  -0.98229 ,  -0.98261 ,  -0.98294 ,  -0.98325 ,  -0.98357 ,  -0.98389 ,  -0.98420 ,  -0.98450 ,  
+-0.98481 ,  -0.98511 ,  -0.98541 ,  -0.98570 ,  -0.98600 ,  -0.98629 ,  -0.98657 ,  -0.98686 ,  -0.98714 ,  -0.98741 ,  
+-0.98769 ,  -0.98796 ,  -0.98823 ,  -0.98849 ,  -0.98876 ,  -0.98902 ,  -0.98927 ,  -0.98953 ,  -0.98978 ,  -0.99002 ,  
+-0.99027 ,  -0.99051 ,  -0.99075 ,  -0.99098 ,  -0.99122 ,  -0.99144 ,  -0.99167 ,  -0.99189 ,  -0.99211 ,  -0.99233 ,  
+-0.99255 ,  -0.99276 ,  -0.99297 ,  -0.99317 ,  -0.99337 ,  -0.99357 ,  -0.99377 ,  -0.99396 ,  -0.99415 ,  -0.99434 ,  
+-0.99452 ,  -0.99470 ,  -0.99488 ,  -0.99506 ,  -0.99523 ,  -0.99540 ,  -0.99556 ,  -0.99572 ,  -0.99588 ,  -0.99604 ,  
+-0.99619 ,  -0.99635 ,  -0.99649 ,  -0.99664 ,  -0.99678 ,  -0.99692 ,  -0.99705 ,  -0.99719 ,  -0.99731 ,  -0.99744 ,  
+-0.99756 ,  -0.99768 ,  -0.99780 ,  -0.99792 ,  -0.99803 ,  -0.99813 ,  -0.99824 ,  -0.99834 ,  -0.99844 ,  -0.99854 ,  
+-0.99863 ,  -0.99872 ,  -0.99881 ,  -0.99889 ,  -0.99897 ,  -0.99905 ,  -0.99912 ,  -0.99919 ,  -0.99926 ,  -0.99933 ,  
+-0.99939 ,  -0.99945 ,  -0.99951 ,  -0.99956 ,  -0.99961 ,  -0.99966 ,  -0.99970 ,  -0.99974 ,  -0.99978 ,  -0.99982 ,  
+-0.99985 ,  -0.99988 ,  -0.99990 ,  -0.99993 ,  -0.99995 ,  -0.99996 ,  -0.99998 ,  -0.99999 ,  -0.99999 ,  -1.00000 ,  
+-1.00000 ,  -1.00000 ,  -0.99999 ,  -0.99999 ,  -0.99998 ,  -0.99996 ,  -0.99995 ,  -0.99993 ,  -0.99990 ,  -0.99988 ,  
+-0.99985 ,  -0.99982 ,  -0.99978 ,  -0.99974 ,  -0.99970 ,  -0.99966 ,  -0.99961 ,  -0.99956 ,  -0.99951 ,  -0.99945 ,  
+-0.99939 ,  -0.99933 ,  -0.99926 ,  -0.99919 ,  -0.99912 ,  -0.99905 ,  -0.99897 ,  -0.99889 ,  -0.99881 ,  -0.99872 ,  
+-0.99863 ,  -0.99854 ,  -0.99844 ,  -0.99834 ,  -0.99824 ,  -0.99813 ,  -0.99803 ,  -0.99792 ,  -0.99780 ,  -0.99768 ,  
+-0.99756 ,  -0.99744 ,  -0.99731 ,  -0.99719 ,  -0.99705 ,  -0.99692 ,  -0.99678 ,  -0.99664 ,  -0.99649 ,  -0.99635 ,  
+-0.99619 ,  -0.99604 ,  -0.99588 ,  -0.99572 ,  -0.99556 ,  -0.99540 ,  -0.99523 ,  -0.99506 ,  -0.99488 ,  -0.99470 ,  
+-0.99452 ,  -0.99434 ,  -0.99415 ,  -0.99396 ,  -0.99377 ,  -0.99357 ,  -0.99337 ,  -0.99317 ,  -0.99297 ,  -0.99276 ,  
+-0.99255 ,  -0.99233 ,  -0.99211 ,  -0.99189 ,  -0.99167 ,  -0.99144 ,  -0.99122 ,  -0.99098 ,  -0.99075 ,  -0.99051 ,  
+-0.99027 ,  -0.99002 ,  -0.98978 ,  -0.98953 ,  -0.98927 ,  -0.98902 ,  -0.98876 ,  -0.98849 ,  -0.98823 ,  -0.98796 ,  
+-0.98769 ,  -0.98741 ,  -0.98714 ,  -0.98686 ,  -0.98657 ,  -0.98629 ,  -0.98600 ,  -0.98570 ,  -0.98541 ,  -0.98511 ,  
+-0.98481 ,  -0.98450 ,  -0.98420 ,  -0.98389 ,  -0.98357 ,  -0.98325 ,  -0.98294 ,  -0.98261 ,  -0.98229 ,  -0.98196 ,  
+-0.98163 ,  -0.98129 ,  -0.98096 ,  -0.98061 ,  -0.98027 ,  -0.97992 ,  -0.97958 ,  -0.97922 ,  -0.97887 ,  -0.97851 ,  
+-0.97815 ,  -0.97778 ,  -0.97742 ,  -0.97705 ,  -0.97667 ,  -0.97630 ,  -0.97592 ,  -0.97553 ,  -0.97515 ,  -0.97476 ,  
+-0.97437 ,  -0.97398 ,  -0.97358 ,  -0.97318 ,  -0.97278 ,  -0.97237 ,  -0.97196 ,  -0.97155 ,  -0.97113 ,  -0.97072 ,  
+-0.97030 ,  -0.96987 ,  -0.96945 ,  -0.96902 ,  -0.96858 ,  -0.96815 ,  -0.96771 ,  -0.96727 ,  -0.96682 ,  -0.96638 ,  
+-0.96593 ,  -0.96547 ,  -0.96502 ,  -0.96456 ,  -0.96410 ,  -0.96363 ,  -0.96316 ,  -0.96269 ,  -0.96222 ,  -0.96174 ,  
+-0.96126 ,  -0.96078 ,  -0.96029 ,  -0.95981 ,  -0.95931 ,  -0.95882 ,  -0.95832 ,  -0.95782 ,  -0.95732 ,  -0.95681 ,  
+-0.95630 ,  -0.95579 ,  -0.95528 ,  -0.95476 ,  -0.95424 ,  -0.95372 ,  -0.95319 ,  -0.95266 ,  -0.95213 ,  -0.95159 ,  
+-0.95106 ,  -0.95052 ,  -0.94997 ,  -0.94943 ,  -0.94888 ,  -0.94832 ,  -0.94777 ,  -0.94721 ,  -0.94665 ,  -0.94609 ,  
+-0.94552 ,  -0.94495 ,  -0.94438 ,  -0.94380 ,  -0.94322 ,  -0.94264 ,  -0.94206 ,  -0.94147 ,  -0.94088 ,  -0.94029 ,  
+-0.93969 ,  -0.93909 ,  -0.93849 ,  -0.93789 ,  -0.93728 ,  -0.93667 ,  -0.93606 ,  -0.93544 ,  -0.93483 ,  -0.93420 ,  
+-0.93358 ,  -0.93295 ,  -0.93232 ,  -0.93169 ,  -0.93106 ,  -0.93042 ,  -0.92978 ,  -0.92913 ,  -0.92849 ,  -0.92784 ,  
+-0.92718 ,  -0.92653 ,  -0.92587 ,  -0.92521 ,  -0.92455 ,  -0.92388 ,  -0.92321 ,  -0.92254 ,  -0.92186 ,  -0.92119 ,  
+-0.92050 ,  -0.91982 ,  -0.91914 ,  -0.91845 ,  -0.91775 ,  -0.91706 ,  -0.91636 ,  -0.91566 ,  -0.91496 ,  -0.91425 ,  
+-0.91355 ,  -0.91283 ,  -0.91212 ,  -0.91140 ,  -0.91068 ,  -0.90996 ,  -0.90924 ,  -0.90851 ,  -0.90778 ,  -0.90704 ,  
+-0.90631 ,  -0.90557 ,  -0.90483 ,  -0.90408 ,  -0.90334 ,  -0.90259 ,  -0.90183 ,  -0.90108 ,  -0.90032 ,  -0.89956 ,  
+-0.89879 ,  -0.89803 ,  -0.89726 ,  -0.89649 ,  -0.89571 ,  -0.89493 ,  -0.89415 ,  -0.89337 ,  -0.89259 ,  -0.89180 ,  
+-0.89101 ,  -0.89021 ,  -0.88942 ,  -0.88862 ,  -0.88782 ,  -0.88701 ,  -0.88620 ,  -0.88539 ,  -0.88458 ,  -0.88377 ,  
+-0.88295 ,  -0.88213 ,  -0.88130 ,  -0.88048 ,  -0.87965 ,  -0.87882 ,  -0.87798 ,  -0.87715 ,  -0.87631 ,  -0.87546 ,  
+-0.87462 ,  -0.87377 ,  -0.87292 ,  -0.87207 ,  -0.87121 ,  -0.87036 ,  -0.86949 ,  -0.86863 ,  -0.86777 ,  -0.86690 ,  
+-0.86603 ,  -0.86515 ,  -0.86427 ,  -0.86340 ,  -0.86251 ,  -0.86163 ,  -0.86074 ,  -0.85985 ,  -0.85896 ,  -0.85806 ,  
+-0.85717 ,  -0.85627 ,  -0.85536 ,  -0.85446 ,  -0.85355 ,  -0.85264 ,  -0.85173 ,  -0.85081 ,  -0.84989 ,  -0.84897 ,  
+-0.84805 ,  -0.84712 ,  -0.84619 ,  -0.84526 ,  -0.84433 ,  -0.84339 ,  -0.84245 ,  -0.84151 ,  -0.84057 ,  -0.83962 ,  
+-0.83867 ,  -0.83772 ,  -0.83676 ,  -0.83581 ,  -0.83485 ,  -0.83389 ,  -0.83292 ,  -0.83195 ,  -0.83098 ,  -0.83001 ,  
+-0.82904 ,  -0.82806 ,  -0.82708 ,  -0.82610 ,  -0.82511 ,  -0.82413 ,  -0.82314 ,  -0.82214 ,  -0.82115 ,  -0.82015 ,  
+-0.81915 ,  -0.81815 ,  -0.81714 ,  -0.81614 ,  -0.81513 ,  -0.81412 ,  -0.81310 ,  -0.81208 ,  -0.81106 ,  -0.81004 ,  
+-0.80902 ,  -0.80799 ,  -0.80696 ,  -0.80593 ,  -0.80489 ,  -0.80386 ,  -0.80282 ,  -0.80178 ,  -0.80073 ,  -0.79968 ,  
+-0.79864 ,  -0.79758 ,  -0.79653 ,  -0.79547 ,  -0.79441 ,  -0.79335 ,  -0.79229 ,  -0.79122 ,  -0.79016 ,  -0.78908 ,  
+-0.78801 ,  -0.78694 ,  -0.78586 ,  -0.78478 ,  -0.78369 ,  -0.78261 ,  -0.78152 ,  -0.78043 ,  -0.77934 ,  -0.77824 ,  
+-0.77715 ,  -0.77605 ,  -0.77494 ,  -0.77384 ,  -0.77273 ,  -0.77162 ,  -0.77051 ,  -0.76940 ,  -0.76828 ,  -0.76717 ,  
+-0.76604 ,  -0.76492 ,  -0.76380 ,  -0.76267 ,  -0.76154 ,  -0.76041 ,  -0.75927 ,  -0.75813 ,  -0.75700 ,  -0.75585 ,  
+-0.75471 ,  -0.75356 ,  -0.75241 ,  -0.75126 ,  -0.75011 ,  -0.74896 ,  -0.74780 ,  -0.74664 ,  -0.74548 ,  -0.74431 ,  
+-0.74314 ,  -0.74198 ,  -0.74080 ,  -0.73963 ,  -0.73846 ,  -0.73728 ,  -0.73610 ,  -0.73491 ,  -0.73373 ,  -0.73254 ,  
+-0.73135 ,  -0.73016 ,  -0.72897 ,  -0.72777 ,  -0.72657 ,  -0.72537 ,  -0.72417 ,  -0.72297 ,  -0.72176 ,  -0.72055 ,  
+-0.71934 ,  -0.71813 ,  -0.71691 ,  -0.71569 ,  -0.71447 ,  -0.71325 ,  -0.71203 ,  -0.71080 ,  -0.70957 ,  -0.70834 ,  
+-0.70711 ,  -0.70587 ,  -0.70463 ,  -0.70339 ,  -0.70215 ,  -0.70091 ,  -0.69966 ,  -0.69842 ,  -0.69717 ,  -0.69591 ,  
+-0.69466 ,  -0.69340 ,  -0.69214 ,  -0.69088 ,  -0.68962 ,  -0.68835 ,  -0.68709 ,  -0.68582 ,  -0.68455 ,  -0.68327 ,  
+-0.68200 ,  -0.68072 ,  -0.67944 ,  -0.67816 ,  -0.67688 ,  -0.67559 ,  -0.67430 ,  -0.67301 ,  -0.67172 ,  -0.67043 ,  
+-0.66913 ,  -0.66783 ,  -0.66653 ,  -0.66523 ,  -0.66393 ,  -0.66262 ,  -0.66131 ,  -0.66000 ,  -0.65869 ,  -0.65738 ,  
+-0.65606 ,  -0.65474 ,  -0.65342 ,  -0.65210 ,  -0.65077 ,  -0.64945 ,  -0.64812 ,  -0.64679 ,  -0.64546 ,  -0.64412 ,  
+-0.64279 ,  -0.64145 ,  -0.64011 ,  -0.63877 ,  -0.63742 ,  -0.63608 ,  -0.63473 ,  -0.63338 ,  -0.63203 ,  -0.63068 ,  
+-0.62932 ,  -0.62796 ,  -0.62660 ,  -0.62524 ,  -0.62388 ,  -0.62251 ,  -0.62115 ,  -0.61978 ,  -0.61841 ,  -0.61704 ,  
+-0.61566 ,  -0.61429 ,  -0.61291 ,  -0.61153 ,  -0.61015 ,  -0.60876 ,  -0.60738 ,  -0.60599 ,  -0.60460 ,  -0.60321 ,  
+-0.60182 ,  -0.60042 ,  -0.59902 ,  -0.59763 ,  -0.59622 ,  -0.59482 ,  -0.59342 ,  -0.59201 ,  -0.59061 ,  -0.58920 ,  
+-0.58779 ,  -0.58637 ,  -0.58496 ,  -0.58354 ,  -0.58212 ,  -0.58070 ,  -0.57928 ,  -0.57786 ,  -0.57643 ,  -0.57501 ,  
+-0.57358 ,  -0.57215 ,  -0.57071 ,  -0.56928 ,  -0.56784 ,  -0.56641 ,  -0.56497 ,  -0.56353 ,  -0.56208 ,  -0.56064 ,  
+-0.55919 ,  -0.55775 ,  -0.55630 ,  -0.55484 ,  -0.55339 ,  -0.55194 ,  -0.55048 ,  -0.54902 ,  -0.54756 ,  -0.54610 ,  
+-0.54464 ,  -0.54317 ,  -0.54171 ,  -0.54024 ,  -0.53877 ,  -0.53730 ,  -0.53583 ,  -0.53435 ,  -0.53288 ,  -0.53140 ,  
+-0.52992 ,  -0.52844 ,  -0.52696 ,  -0.52547 ,  -0.52399 ,  -0.52250 ,  -0.52101 ,  -0.51952 ,  -0.51803 ,  -0.51653 ,  
+-0.51504 ,  -0.51354 ,  -0.51204 ,  -0.51054 ,  -0.50904 ,  -0.50754 ,  -0.50603 ,  -0.50453 ,  -0.50302 ,  -0.50151 ,  
+-0.50000 ,  -0.49849 ,  -0.49697 ,  -0.49546 ,  -0.49394 ,  -0.49242 ,  -0.49090 ,  -0.48938 ,  -0.48786 ,  -0.48634 ,  
+-0.48481 ,  -0.48328 ,  -0.48175 ,  -0.48022 ,  -0.47869 ,  -0.47716 ,  -0.47562 ,  -0.47409 ,  -0.47255 ,  -0.47101 ,  
+-0.46947 ,  -0.46793 ,  -0.46639 ,  -0.46484 ,  -0.46330 ,  -0.46175 ,  -0.46020 ,  -0.45865 ,  -0.45710 ,  -0.45554 ,  
+-0.45399 ,  -0.45243 ,  -0.45088 ,  -0.44932 ,  -0.44776 ,  -0.44620 ,  -0.44464 ,  -0.44307 ,  -0.44151 ,  -0.43994 ,  
+-0.43837 ,  -0.43680 ,  -0.43523 ,  -0.43366 ,  -0.43209 ,  -0.43051 ,  -0.42894 ,  -0.42736 ,  -0.42578 ,  -0.42420 ,  
+-0.42262 ,  -0.42104 ,  -0.41945 ,  -0.41787 ,  -0.41628 ,  -0.41469 ,  -0.41310 ,  -0.41151 ,  -0.40992 ,  -0.40833 ,  
+-0.40674 ,  -0.40514 ,  -0.40355 ,  -0.40195 ,  -0.40035 ,  -0.39875 ,  -0.39715 ,  -0.39555 ,  -0.39394 ,  -0.39234 ,  
+-0.39073 ,  -0.38912 ,  -0.38752 ,  -0.38591 ,  -0.38430 ,  -0.38268 ,  -0.38107 ,  -0.37946 ,  -0.37784 ,  -0.37622 ,  
+-0.37461 ,  -0.37299 ,  -0.37137 ,  -0.36975 ,  -0.36812 ,  -0.36650 ,  -0.36488 ,  -0.36325 ,  -0.36162 ,  -0.36000 ,  
+-0.35837 ,  -0.35674 ,  -0.35511 ,  -0.35347 ,  -0.35184 ,  -0.35021 ,  -0.34857 ,  -0.34694 ,  -0.34530 ,  -0.34366 ,  
+-0.34202 ,  -0.34038 ,  -0.33874 ,  -0.33710 ,  -0.33545 ,  -0.33381 ,  -0.33216 ,  -0.33051 ,  -0.32887 ,  -0.32722 ,  
+-0.32557 ,  -0.32392 ,  -0.32227 ,  -0.32061 ,  -0.31896 ,  -0.31730 ,  -0.31565 ,  -0.31399 ,  -0.31233 ,  -0.31068 ,  
+-0.30902 ,  -0.30736 ,  -0.30570 ,  -0.30403 ,  -0.30237 ,  -0.30071 ,  -0.29904 ,  -0.29737 ,  -0.29571 ,  -0.29404 ,  
+-0.29237 ,  -0.29070 ,  -0.28903 ,  -0.28736 ,  -0.28569 ,  -0.28402 ,  -0.28234 ,  -0.28067 ,  -0.27899 ,  -0.27731 ,  
+-0.27564 ,  -0.27396 ,  -0.27228 ,  -0.27060 ,  -0.26892 ,  -0.26724 ,  -0.26556 ,  -0.26387 ,  -0.26219 ,  -0.26050 ,  
+-0.25882 ,  -0.25713 ,  -0.25545 ,  -0.25376 ,  -0.25207 ,  -0.25038 ,  -0.24869 ,  -0.24700 ,  -0.24531 ,  -0.24362 ,  
+-0.24192 ,  -0.24023 ,  -0.23853 ,  -0.23684 ,  -0.23514 ,  -0.23345 ,  -0.23175 ,  -0.23005 ,  -0.22835 ,  -0.22665 ,  
+-0.22495 ,  -0.22325 ,  -0.22155 ,  -0.21985 ,  -0.21814 ,  -0.21644 ,  -0.21474 ,  -0.21303 ,  -0.21132 ,  -0.20962 ,  
+-0.20791 ,  -0.20620 ,  -0.20450 ,  -0.20279 ,  -0.20108 ,  -0.19937 ,  -0.19766 ,  -0.19595 ,  -0.19423 ,  -0.19252 ,  
+-0.19081 ,  -0.18910 ,  -0.18738 ,  -0.18567 ,  -0.18395 ,  -0.18224 ,  -0.18052 ,  -0.17880 ,  -0.17708 ,  -0.17537 ,  
+-0.17365 ,  -0.17193 ,  -0.17021 ,  -0.16849 ,  -0.16677 ,  -0.16505 ,  -0.16333 ,  -0.16160 ,  -0.15988 ,  -0.15816 ,  
+-0.15643 ,  -0.15471 ,  -0.15299 ,  -0.15126 ,  -0.14954 ,  -0.14781 ,  -0.14608 ,  -0.14436 ,  -0.14263 ,  -0.14090 ,  
+-0.13917 ,  -0.13744 ,  -0.13572 ,  -0.13399 ,  -0.13226 ,  -0.13053 ,  -0.12880 ,  -0.12706 ,  -0.12533 ,  -0.12360 ,  
+-0.12187 ,  -0.12014 ,  -0.11840 ,  -0.11667 ,  -0.11494 ,  -0.11320 ,  -0.11147 ,  -0.10973 ,  -0.10800 ,  -0.10626 ,  
+-0.10453 ,  -0.10279 ,  -0.10106 ,  -0.09932 ,  -0.09758 ,  -0.09585 ,  -0.09411 ,  -0.09237 ,  -0.09063 ,  -0.08889 ,  
+-0.08716 ,  -0.08542 ,  -0.08368 ,  -0.08194 ,  -0.08020 ,  -0.07846 ,  -0.07672 ,  -0.07498 ,  -0.07324 ,  -0.07150 ,  
+-0.06976 ,  -0.06802 ,  -0.06627 ,  -0.06453 ,  -0.06279 ,  -0.06105 ,  -0.05931 ,  -0.05756 ,  -0.05582 ,  -0.05408 ,  
+-0.05234 ,  -0.05059 ,  -0.04885 ,  -0.04711 ,  -0.04536 ,  -0.04362 ,  -0.04188 ,  -0.04013 ,  -0.03839 ,  -0.03664 ,  
+-0.03490 ,  -0.03316 ,  -0.03141 ,  -0.02967 ,  -0.02792 ,  -0.02618 ,  -0.02443 ,  -0.02269 ,  -0.02094 ,  -0.01920 ,  
+-0.01745 ,  -0.01571 ,  -0.01396 ,  -0.01222 ,  -0.01047 ,  -0.00873 ,  -0.00698 ,  -0.00524 ,  -0.00349 ,  -0.00175 ,  
+};
+const double CosTable[3600]={
+1.00000 ,   1.00000 ,   0.99999 ,   0.99999 ,   0.99998 ,   0.99996 ,   0.99995 ,   0.99993 ,   0.99990 ,   0.99988 ,   
+0.99985 ,   0.99982 ,   0.99978 ,   0.99974 ,   0.99970 ,   0.99966 ,   0.99961 ,   0.99956 ,   0.99951 ,   0.99945 ,   
+0.99939 ,   0.99933 ,   0.99926 ,   0.99919 ,   0.99912 ,   0.99905 ,   0.99897 ,   0.99889 ,   0.99881 ,   0.99872 ,   
+0.99863 ,   0.99854 ,   0.99844 ,   0.99834 ,   0.99824 ,   0.99813 ,   0.99803 ,   0.99792 ,   0.99780 ,   0.99768 ,   
+0.99756 ,   0.99744 ,   0.99731 ,   0.99719 ,   0.99705 ,   0.99692 ,   0.99678 ,   0.99664 ,   0.99649 ,   0.99635 ,   
+0.99619 ,   0.99604 ,   0.99588 ,   0.99572 ,   0.99556 ,   0.99540 ,   0.99523 ,   0.99506 ,   0.99488 ,   0.99470 ,   
+0.99452 ,   0.99434 ,   0.99415 ,   0.99396 ,   0.99377 ,   0.99357 ,   0.99337 ,   0.99317 ,   0.99297 ,   0.99276 ,   
+0.99255 ,   0.99233 ,   0.99211 ,   0.99189 ,   0.99167 ,   0.99144 ,   0.99122 ,   0.99098 ,   0.99075 ,   0.99051 ,   
+0.99027 ,   0.99002 ,   0.98978 ,   0.98953 ,   0.98927 ,   0.98902 ,   0.98876 ,   0.98849 ,   0.98823 ,   0.98796 ,   
+0.98769 ,   0.98741 ,   0.98714 ,   0.98686 ,   0.98657 ,   0.98629 ,   0.98600 ,   0.98570 ,   0.98541 ,   0.98511 ,   
+0.98481 ,   0.98450 ,   0.98420 ,   0.98389 ,   0.98357 ,   0.98325 ,   0.98294 ,   0.98261 ,   0.98229 ,   0.98196 ,   
+0.98163 ,   0.98129 ,   0.98096 ,   0.98061 ,   0.98027 ,   0.97992 ,   0.97958 ,   0.97922 ,   0.97887 ,   0.97851 ,   
+0.97815 ,   0.97778 ,   0.97742 ,   0.97705 ,   0.97667 ,   0.97630 ,   0.97592 ,   0.97553 ,   0.97515 ,   0.97476 ,   
+0.97437 ,   0.97398 ,   0.97358 ,   0.97318 ,   0.97278 ,   0.97237 ,   0.97196 ,   0.97155 ,   0.97113 ,   0.97072 ,   
+0.97030 ,   0.96987 ,   0.96945 ,   0.96902 ,   0.96858 ,   0.96815 ,   0.96771 ,   0.96727 ,   0.96682 ,   0.96638 ,   
+0.96593 ,   0.96547 ,   0.96502 ,   0.96456 ,   0.96410 ,   0.96363 ,   0.96316 ,   0.96269 ,   0.96222 ,   0.96174 ,   
+0.96126 ,   0.96078 ,   0.96029 ,   0.95981 ,   0.95931 ,   0.95882 ,   0.95832 ,   0.95782 ,   0.95732 ,   0.95681 ,   
+0.95630 ,   0.95579 ,   0.95528 ,   0.95476 ,   0.95424 ,   0.95372 ,   0.95319 ,   0.95266 ,   0.95213 ,   0.95159 ,   
+0.95106 ,   0.95052 ,   0.94997 ,   0.94943 ,   0.94888 ,   0.94832 ,   0.94777 ,   0.94721 ,   0.94665 ,   0.94609 ,   
+0.94552 ,   0.94495 ,   0.94438 ,   0.94380 ,   0.94322 ,   0.94264 ,   0.94206 ,   0.94147 ,   0.94088 ,   0.94029 ,   
+0.93969 ,   0.93909 ,   0.93849 ,   0.93789 ,   0.93728 ,   0.93667 ,   0.93606 ,   0.93544 ,   0.93483 ,   0.93420 ,   
+0.93358 ,   0.93295 ,   0.93232 ,   0.93169 ,   0.93106 ,   0.93042 ,   0.92978 ,   0.92913 ,   0.92849 ,   0.92784 ,   
+0.92718 ,   0.92653 ,   0.92587 ,   0.92521 ,   0.92455 ,   0.92388 ,   0.92321 ,   0.92254 ,   0.92186 ,   0.92119 ,   
+0.92050 ,   0.91982 ,   0.91914 ,   0.91845 ,   0.91775 ,   0.91706 ,   0.91636 ,   0.91566 ,   0.91496 ,   0.91425 ,   
+0.91355 ,   0.91283 ,   0.91212 ,   0.91140 ,   0.91068 ,   0.90996 ,   0.90924 ,   0.90851 ,   0.90778 ,   0.90704 ,   
+0.90631 ,   0.90557 ,   0.90483 ,   0.90408 ,   0.90334 ,   0.90259 ,   0.90183 ,   0.90108 ,   0.90032 ,   0.89956 ,   
+0.89879 ,   0.89803 ,   0.89726 ,   0.89649 ,   0.89571 ,   0.89493 ,   0.89415 ,   0.89337 ,   0.89259 ,   0.89180 ,   
+0.89101 ,   0.89021 ,   0.88942 ,   0.88862 ,   0.88782 ,   0.88701 ,   0.88620 ,   0.88539 ,   0.88458 ,   0.88377 ,   
+0.88295 ,   0.88213 ,   0.88130 ,   0.88048 ,   0.87965 ,   0.87882 ,   0.87798 ,   0.87715 ,   0.87631 ,   0.87546 ,   
+0.87462 ,   0.87377 ,   0.87292 ,   0.87207 ,   0.87121 ,   0.87036 ,   0.86949 ,   0.86863 ,   0.86777 ,   0.86690 ,   
+0.86603 ,   0.86515 ,   0.86427 ,   0.86340 ,   0.86251 ,   0.86163 ,   0.86074 ,   0.85985 ,   0.85896 ,   0.85806 ,   
+0.85717 ,   0.85627 ,   0.85536 ,   0.85446 ,   0.85355 ,   0.85264 ,   0.85173 ,   0.85081 ,   0.84989 ,   0.84897 ,   
+0.84805 ,   0.84712 ,   0.84619 ,   0.84526 ,   0.84433 ,   0.84339 ,   0.84245 ,   0.84151 ,   0.84057 ,   0.83962 ,   
+0.83867 ,   0.83772 ,   0.83676 ,   0.83581 ,   0.83485 ,   0.83389 ,   0.83292 ,   0.83195 ,   0.83098 ,   0.83001 ,   
+0.82904 ,   0.82806 ,   0.82708 ,   0.82610 ,   0.82511 ,   0.82413 ,   0.82314 ,   0.82214 ,   0.82115 ,   0.82015 ,   
+0.81915 ,   0.81815 ,   0.81714 ,   0.81614 ,   0.81513 ,   0.81412 ,   0.81310 ,   0.81208 ,   0.81106 ,   0.81004 ,   
+0.80902 ,   0.80799 ,   0.80696 ,   0.80593 ,   0.80489 ,   0.80386 ,   0.80282 ,   0.80178 ,   0.80073 ,   0.79968 ,   
+0.79864 ,   0.79758 ,   0.79653 ,   0.79547 ,   0.79441 ,   0.79335 ,   0.79229 ,   0.79122 ,   0.79016 ,   0.78908 ,   
+0.78801 ,   0.78694 ,   0.78586 ,   0.78478 ,   0.78369 ,   0.78261 ,   0.78152 ,   0.78043 ,   0.77934 ,   0.77824 ,   
+0.77715 ,   0.77605 ,   0.77494 ,   0.77384 ,   0.77273 ,   0.77162 ,   0.77051 ,   0.76940 ,   0.76828 ,   0.76717 ,   
+0.76604 ,   0.76492 ,   0.76380 ,   0.76267 ,   0.76154 ,   0.76041 ,   0.75927 ,   0.75813 ,   0.75700 ,   0.75585 ,   
+0.75471 ,   0.75356 ,   0.75241 ,   0.75126 ,   0.75011 ,   0.74896 ,   0.74780 ,   0.74664 ,   0.74548 ,   0.74431 ,   
+0.74314 ,   0.74198 ,   0.74080 ,   0.73963 ,   0.73846 ,   0.73728 ,   0.73610 ,   0.73491 ,   0.73373 ,   0.73254 ,   
+0.73135 ,   0.73016 ,   0.72897 ,   0.72777 ,   0.72657 ,   0.72537 ,   0.72417 ,   0.72297 ,   0.72176 ,   0.72055 ,   
+0.71934 ,   0.71813 ,   0.71691 ,   0.71569 ,   0.71447 ,   0.71325 ,   0.71203 ,   0.71080 ,   0.70957 ,   0.70834 ,   
+0.70711 ,   0.70587 ,   0.70463 ,   0.70339 ,   0.70215 ,   0.70091 ,   0.69966 ,   0.69842 ,   0.69717 ,   0.69591 ,   
+0.69466 ,   0.69340 ,   0.69214 ,   0.69088 ,   0.68962 ,   0.68835 ,   0.68709 ,   0.68582 ,   0.68455 ,   0.68327 ,   
+0.68200 ,   0.68072 ,   0.67944 ,   0.67816 ,   0.67688 ,   0.67559 ,   0.67430 ,   0.67301 ,   0.67172 ,   0.67043 ,   
+0.66913 ,   0.66783 ,   0.66653 ,   0.66523 ,   0.66393 ,   0.66262 ,   0.66131 ,   0.66000 ,   0.65869 ,   0.65738 ,   
+0.65606 ,   0.65474 ,   0.65342 ,   0.65210 ,   0.65077 ,   0.64945 ,   0.64812 ,   0.64679 ,   0.64546 ,   0.64412 ,   
+0.64279 ,   0.64145 ,   0.64011 ,   0.63877 ,   0.63742 ,   0.63608 ,   0.63473 ,   0.63338 ,   0.63203 ,   0.63068 ,   
+0.62932 ,   0.62796 ,   0.62660 ,   0.62524 ,   0.62388 ,   0.62251 ,   0.62115 ,   0.61978 ,   0.61841 ,   0.61704 ,   
+0.61566 ,   0.61429 ,   0.61291 ,   0.61153 ,   0.61015 ,   0.60876 ,   0.60738 ,   0.60599 ,   0.60460 ,   0.60321 ,   
+0.60182 ,   0.60042 ,   0.59902 ,   0.59763 ,   0.59622 ,   0.59482 ,   0.59342 ,   0.59201 ,   0.59061 ,   0.58920 ,   
+0.58779 ,   0.58637 ,   0.58496 ,   0.58354 ,   0.58212 ,   0.58070 ,   0.57928 ,   0.57786 ,   0.57643 ,   0.57501 ,   
+0.57358 ,   0.57215 ,   0.57071 ,   0.56928 ,   0.56784 ,   0.56641 ,   0.56497 ,   0.56353 ,   0.56208 ,   0.56064 ,   
+0.55919 ,   0.55775 ,   0.55630 ,   0.55484 ,   0.55339 ,   0.55194 ,   0.55048 ,   0.54902 ,   0.54756 ,   0.54610 ,   
+0.54464 ,   0.54317 ,   0.54171 ,   0.54024 ,   0.53877 ,   0.53730 ,   0.53583 ,   0.53435 ,   0.53288 ,   0.53140 ,   
+0.52992 ,   0.52844 ,   0.52696 ,   0.52547 ,   0.52399 ,   0.52250 ,   0.52101 ,   0.51952 ,   0.51803 ,   0.51653 ,   
+0.51504 ,   0.51354 ,   0.51204 ,   0.51054 ,   0.50904 ,   0.50754 ,   0.50603 ,   0.50453 ,   0.50302 ,   0.50151 ,   
+0.50000 ,   0.49849 ,   0.49697 ,   0.49546 ,   0.49394 ,   0.49242 ,   0.49090 ,   0.48938 ,   0.48786 ,   0.48634 ,   
+0.48481 ,   0.48328 ,   0.48175 ,   0.48022 ,   0.47869 ,   0.47716 ,   0.47562 ,   0.47409 ,   0.47255 ,   0.47101 ,   
+0.46947 ,   0.46793 ,   0.46639 ,   0.46484 ,   0.46330 ,   0.46175 ,   0.46020 ,   0.45865 ,   0.45710 ,   0.45554 ,   
+0.45399 ,   0.45243 ,   0.45088 ,   0.44932 ,   0.44776 ,   0.44620 ,   0.44464 ,   0.44307 ,   0.44151 ,   0.43994 ,   
+0.43837 ,   0.43680 ,   0.43523 ,   0.43366 ,   0.43209 ,   0.43051 ,   0.42894 ,   0.42736 ,   0.42578 ,   0.42420 ,   
+0.42262 ,   0.42104 ,   0.41945 ,   0.41787 ,   0.41628 ,   0.41469 ,   0.41310 ,   0.41151 ,   0.40992 ,   0.40833 ,   
+0.40674 ,   0.40514 ,   0.40355 ,   0.40195 ,   0.40035 ,   0.39875 ,   0.39715 ,   0.39555 ,   0.39394 ,   0.39234 ,   
+0.39073 ,   0.38912 ,   0.38752 ,   0.38591 ,   0.38430 ,   0.38268 ,   0.38107 ,   0.37946 ,   0.37784 ,   0.37622 ,   
+0.37461 ,   0.37299 ,   0.37137 ,   0.36975 ,   0.36812 ,   0.36650 ,   0.36488 ,   0.36325 ,   0.36162 ,   0.36000 ,   
+0.35837 ,   0.35674 ,   0.35511 ,   0.35347 ,   0.35184 ,   0.35021 ,   0.34857 ,   0.34694 ,   0.34530 ,   0.34366 ,   
+0.34202 ,   0.34038 ,   0.33874 ,   0.33710 ,   0.33545 ,   0.33381 ,   0.33216 ,   0.33051 ,   0.32887 ,   0.32722 ,   
+0.32557 ,   0.32392 ,   0.32227 ,   0.32061 ,   0.31896 ,   0.31730 ,   0.31565 ,   0.31399 ,   0.31233 ,   0.31068 ,   
+0.30902 ,   0.30736 ,   0.30570 ,   0.30403 ,   0.30237 ,   0.30071 ,   0.29904 ,   0.29737 ,   0.29571 ,   0.29404 ,   
+0.29237 ,   0.29070 ,   0.28903 ,   0.28736 ,   0.28569 ,   0.28402 ,   0.28234 ,   0.28067 ,   0.27899 ,   0.27731 ,   
+0.27564 ,   0.27396 ,   0.27228 ,   0.27060 ,   0.26892 ,   0.26724 ,   0.26556 ,   0.26387 ,   0.26219 ,   0.26050 ,   
+0.25882 ,   0.25713 ,   0.25545 ,   0.25376 ,   0.25207 ,   0.25038 ,   0.24869 ,   0.24700 ,   0.24531 ,   0.24362 ,   
+0.24192 ,   0.24023 ,   0.23853 ,   0.23684 ,   0.23514 ,   0.23345 ,   0.23175 ,   0.23005 ,   0.22835 ,   0.22665 ,   
+0.22495 ,   0.22325 ,   0.22155 ,   0.21985 ,   0.21814 ,   0.21644 ,   0.21474 ,   0.21303 ,   0.21132 ,   0.20962 ,   
+0.20791 ,   0.20620 ,   0.20450 ,   0.20279 ,   0.20108 ,   0.19937 ,   0.19766 ,   0.19595 ,   0.19423 ,   0.19252 ,   
+0.19081 ,   0.18910 ,   0.18738 ,   0.18567 ,   0.18395 ,   0.18224 ,   0.18052 ,   0.17880 ,   0.17708 ,   0.17537 ,   
+0.17365 ,   0.17193 ,   0.17021 ,   0.16849 ,   0.16677 ,   0.16505 ,   0.16333 ,   0.16160 ,   0.15988 ,   0.15816 ,   
+0.15643 ,   0.15471 ,   0.15299 ,   0.15126 ,   0.14954 ,   0.14781 ,   0.14608 ,   0.14436 ,   0.14263 ,   0.14090 ,   
+0.13917 ,   0.13744 ,   0.13572 ,   0.13399 ,   0.13226 ,   0.13053 ,   0.12880 ,   0.12706 ,   0.12533 ,   0.12360 ,   
+0.12187 ,   0.12014 ,   0.11840 ,   0.11667 ,   0.11494 ,   0.11320 ,   0.11147 ,   0.10973 ,   0.10800 ,   0.10626 ,   
+0.10453 ,   0.10279 ,   0.10106 ,   0.09932 ,   0.09758 ,   0.09585 ,   0.09411 ,   0.09237 ,   0.09063 ,   0.08889 ,   
+0.08716 ,   0.08542 ,   0.08368 ,   0.08194 ,   0.08020 ,   0.07846 ,   0.07672 ,   0.07498 ,   0.07324 ,   0.07150 ,   
+0.06976 ,   0.06802 ,   0.06627 ,   0.06453 ,   0.06279 ,   0.06105 ,   0.05931 ,   0.05756 ,   0.05582 ,   0.05408 ,   
+0.05234 ,   0.05059 ,   0.04885 ,   0.04711 ,   0.04536 ,   0.04362 ,   0.04188 ,   0.04013 ,   0.03839 ,   0.03664 ,   
+0.03490 ,   0.03316 ,   0.03141 ,   0.02967 ,   0.02792 ,   0.02618 ,   0.02443 ,   0.02269 ,   0.02094 ,   0.01920 ,   
+0.01745 ,   0.01571 ,   0.01396 ,   0.01222 ,   0.01047 ,   0.00873 ,   0.00698 ,   0.00524 ,   0.00349 ,   0.00175 ,   
+0.00000 ,   -0.00175 ,  -0.00349 ,  -0.00524 ,  -0.00698 ,  -0.00873 ,  -0.01047 ,  -0.01222 ,  -0.01396 ,  -0.01571 ,  
+-0.01745 ,  -0.01920 ,  -0.02094 ,  -0.02269 ,  -0.02443 ,  -0.02618 ,  -0.02792 ,  -0.02967 ,  -0.03141 ,  -0.03316 ,  
+-0.03490 ,  -0.03664 ,  -0.03839 ,  -0.04013 ,  -0.04188 ,  -0.04362 ,  -0.04536 ,  -0.04711 ,  -0.04885 ,  -0.05059 ,  
+-0.05234 ,  -0.05408 ,  -0.05582 ,  -0.05756 ,  -0.05931 ,  -0.06105 ,  -0.06279 ,  -0.06453 ,  -0.06627 ,  -0.06802 ,  
+-0.06976 ,  -0.07150 ,  -0.07324 ,  -0.07498 ,  -0.07672 ,  -0.07846 ,  -0.08020 ,  -0.08194 ,  -0.08368 ,  -0.08542 ,  
+-0.08716 ,  -0.08889 ,  -0.09063 ,  -0.09237 ,  -0.09411 ,  -0.09585 ,  -0.09758 ,  -0.09932 ,  -0.10106 ,  -0.10279 ,  
+-0.10453 ,  -0.10626 ,  -0.10800 ,  -0.10973 ,  -0.11147 ,  -0.11320 ,  -0.11494 ,  -0.11667 ,  -0.11840 ,  -0.12014 ,  
+-0.12187 ,  -0.12360 ,  -0.12533 ,  -0.12706 ,  -0.12880 ,  -0.13053 ,  -0.13226 ,  -0.13399 ,  -0.13572 ,  -0.13744 ,  
+-0.13917 ,  -0.14090 ,  -0.14263 ,  -0.14436 ,  -0.14608 ,  -0.14781 ,  -0.14954 ,  -0.15126 ,  -0.15299 ,  -0.15471 ,  
+-0.15643 ,  -0.15816 ,  -0.15988 ,  -0.16160 ,  -0.16333 ,  -0.16505 ,  -0.16677 ,  -0.16849 ,  -0.17021 ,  -0.17193 ,  
+-0.17365 ,  -0.17537 ,  -0.17708 ,  -0.17880 ,  -0.18052 ,  -0.18224 ,  -0.18395 ,  -0.18567 ,  -0.18738 ,  -0.18910 ,  
+-0.19081 ,  -0.19252 ,  -0.19423 ,  -0.19595 ,  -0.19766 ,  -0.19937 ,  -0.20108 ,  -0.20279 ,  -0.20450 ,  -0.20620 ,  
+-0.20791 ,  -0.20962 ,  -0.21132 ,  -0.21303 ,  -0.21474 ,  -0.21644 ,  -0.21814 ,  -0.21985 ,  -0.22155 ,  -0.22325 ,  
+-0.22495 ,  -0.22665 ,  -0.22835 ,  -0.23005 ,  -0.23175 ,  -0.23345 ,  -0.23514 ,  -0.23684 ,  -0.23853 ,  -0.24023 ,  
+-0.24192 ,  -0.24362 ,  -0.24531 ,  -0.24700 ,  -0.24869 ,  -0.25038 ,  -0.25207 ,  -0.25376 ,  -0.25545 ,  -0.25713 ,  
+-0.25882 ,  -0.26050 ,  -0.26219 ,  -0.26387 ,  -0.26556 ,  -0.26724 ,  -0.26892 ,  -0.27060 ,  -0.27228 ,  -0.27396 ,  
+-0.27564 ,  -0.27731 ,  -0.27899 ,  -0.28067 ,  -0.28234 ,  -0.28402 ,  -0.28569 ,  -0.28736 ,  -0.28903 ,  -0.29070 ,  
+-0.29237 ,  -0.29404 ,  -0.29571 ,  -0.29737 ,  -0.29904 ,  -0.30071 ,  -0.30237 ,  -0.30403 ,  -0.30570 ,  -0.30736 ,  
+-0.30902 ,  -0.31068 ,  -0.31233 ,  -0.31399 ,  -0.31565 ,  -0.31730 ,  -0.31896 ,  -0.32061 ,  -0.32227 ,  -0.32392 ,  
+-0.32557 ,  -0.32722 ,  -0.32887 ,  -0.33051 ,  -0.33216 ,  -0.33381 ,  -0.33545 ,  -0.33710 ,  -0.33874 ,  -0.34038 ,  
+-0.34202 ,  -0.34366 ,  -0.34530 ,  -0.34694 ,  -0.34857 ,  -0.35021 ,  -0.35184 ,  -0.35347 ,  -0.35511 ,  -0.35674 ,  
+-0.35837 ,  -0.36000 ,  -0.36162 ,  -0.36325 ,  -0.36488 ,  -0.36650 ,  -0.36812 ,  -0.36975 ,  -0.37137 ,  -0.37299 ,  
+-0.37461 ,  -0.37622 ,  -0.37784 ,  -0.37946 ,  -0.38107 ,  -0.38268 ,  -0.38430 ,  -0.38591 ,  -0.38752 ,  -0.38912 ,  
+-0.39073 ,  -0.39234 ,  -0.39394 ,  -0.39555 ,  -0.39715 ,  -0.39875 ,  -0.40035 ,  -0.40195 ,  -0.40355 ,  -0.40514 ,  
+-0.40674 ,  -0.40833 ,  -0.40992 ,  -0.41151 ,  -0.41310 ,  -0.41469 ,  -0.41628 ,  -0.41787 ,  -0.41945 ,  -0.42104 ,  
+-0.42262 ,  -0.42420 ,  -0.42578 ,  -0.42736 ,  -0.42894 ,  -0.43051 ,  -0.43209 ,  -0.43366 ,  -0.43523 ,  -0.43680 ,  
+-0.43837 ,  -0.43994 ,  -0.44151 ,  -0.44307 ,  -0.44464 ,  -0.44620 ,  -0.44776 ,  -0.44932 ,  -0.45088 ,  -0.45243 ,  
+-0.45399 ,  -0.45554 ,  -0.45710 ,  -0.45865 ,  -0.46020 ,  -0.46175 ,  -0.46330 ,  -0.46484 ,  -0.46639 ,  -0.46793 ,  
+-0.46947 ,  -0.47101 ,  -0.47255 ,  -0.47409 ,  -0.47562 ,  -0.47716 ,  -0.47869 ,  -0.48022 ,  -0.48175 ,  -0.48328 ,  
+-0.48481 ,  -0.48634 ,  -0.48786 ,  -0.48938 ,  -0.49090 ,  -0.49242 ,  -0.49394 ,  -0.49546 ,  -0.49697 ,  -0.49849 ,  
+-0.50000 ,  -0.50151 ,  -0.50302 ,  -0.50453 ,  -0.50603 ,  -0.50754 ,  -0.50904 ,  -0.51054 ,  -0.51204 ,  -0.51354 ,  
+-0.51504 ,  -0.51653 ,  -0.51803 ,  -0.51952 ,  -0.52101 ,  -0.52250 ,  -0.52399 ,  -0.52547 ,  -0.52696 ,  -0.52844 ,  
+-0.52992 ,  -0.53140 ,  -0.53288 ,  -0.53435 ,  -0.53583 ,  -0.53730 ,  -0.53877 ,  -0.54024 ,  -0.54171 ,  -0.54317 ,  
+-0.54464 ,  -0.54610 ,  -0.54756 ,  -0.54902 ,  -0.55048 ,  -0.55194 ,  -0.55339 ,  -0.55484 ,  -0.55630 ,  -0.55775 ,  
+-0.55919 ,  -0.56064 ,  -0.56208 ,  -0.56353 ,  -0.56497 ,  -0.56641 ,  -0.56784 ,  -0.56928 ,  -0.57071 ,  -0.57215 ,  
+-0.57358 ,  -0.57501 ,  -0.57643 ,  -0.57786 ,  -0.57928 ,  -0.58070 ,  -0.58212 ,  -0.58354 ,  -0.58496 ,  -0.58637 ,  
+-0.58779 ,  -0.58920 ,  -0.59061 ,  -0.59201 ,  -0.59342 ,  -0.59482 ,  -0.59622 ,  -0.59763 ,  -0.59902 ,  -0.60042 ,  
+-0.60182 ,  -0.60321 ,  -0.60460 ,  -0.60599 ,  -0.60738 ,  -0.60876 ,  -0.61015 ,  -0.61153 ,  -0.61291 ,  -0.61429 ,  
+-0.61566 ,  -0.61704 ,  -0.61841 ,  -0.61978 ,  -0.62115 ,  -0.62251 ,  -0.62388 ,  -0.62524 ,  -0.62660 ,  -0.62796 ,  
+-0.62932 ,  -0.63068 ,  -0.63203 ,  -0.63338 ,  -0.63473 ,  -0.63608 ,  -0.63742 ,  -0.63877 ,  -0.64011 ,  -0.64145 ,  
+-0.64279 ,  -0.64412 ,  -0.64546 ,  -0.64679 ,  -0.64812 ,  -0.64945 ,  -0.65077 ,  -0.65210 ,  -0.65342 ,  -0.65474 ,  
+-0.65606 ,  -0.65738 ,  -0.65869 ,  -0.66000 ,  -0.66131 ,  -0.66262 ,  -0.66393 ,  -0.66523 ,  -0.66653 ,  -0.66783 ,  
+-0.66913 ,  -0.67043 ,  -0.67172 ,  -0.67301 ,  -0.67430 ,  -0.67559 ,  -0.67688 ,  -0.67816 ,  -0.67944 ,  -0.68072 ,  
+-0.68200 ,  -0.68327 ,  -0.68455 ,  -0.68582 ,  -0.68709 ,  -0.68835 ,  -0.68962 ,  -0.69088 ,  -0.69214 ,  -0.69340 ,  
+-0.69466 ,  -0.69591 ,  -0.69717 ,  -0.69842 ,  -0.69966 ,  -0.70091 ,  -0.70215 ,  -0.70339 ,  -0.70463 ,  -0.70587 ,  
+-0.70711 ,  -0.70834 ,  -0.70957 ,  -0.71080 ,  -0.71203 ,  -0.71325 ,  -0.71447 ,  -0.71569 ,  -0.71691 ,  -0.71813 ,  
+-0.71934 ,  -0.72055 ,  -0.72176 ,  -0.72297 ,  -0.72417 ,  -0.72537 ,  -0.72657 ,  -0.72777 ,  -0.72897 ,  -0.73016 ,  
+-0.73135 ,  -0.73254 ,  -0.73373 ,  -0.73491 ,  -0.73610 ,  -0.73728 ,  -0.73846 ,  -0.73963 ,  -0.74080 ,  -0.74198 ,  
+-0.74314 ,  -0.74431 ,  -0.74548 ,  -0.74664 ,  -0.74780 ,  -0.74896 ,  -0.75011 ,  -0.75126 ,  -0.75241 ,  -0.75356 ,  
+-0.75471 ,  -0.75585 ,  -0.75700 ,  -0.75813 ,  -0.75927 ,  -0.76041 ,  -0.76154 ,  -0.76267 ,  -0.76380 ,  -0.76492 ,  
+-0.76604 ,  -0.76717 ,  -0.76828 ,  -0.76940 ,  -0.77051 ,  -0.77162 ,  -0.77273 ,  -0.77384 ,  -0.77494 ,  -0.77605 ,  
+-0.77715 ,  -0.77824 ,  -0.77934 ,  -0.78043 ,  -0.78152 ,  -0.78261 ,  -0.78369 ,  -0.78478 ,  -0.78586 ,  -0.78694 ,  
+-0.78801 ,  -0.78908 ,  -0.79016 ,  -0.79122 ,  -0.79229 ,  -0.79335 ,  -0.79441 ,  -0.79547 ,  -0.79653 ,  -0.79758 ,  
+-0.79864 ,  -0.79968 ,  -0.80073 ,  -0.80178 ,  -0.80282 ,  -0.80386 ,  -0.80489 ,  -0.80593 ,  -0.80696 ,  -0.80799 ,  
+-0.80902 ,  -0.81004 ,  -0.81106 ,  -0.81208 ,  -0.81310 ,  -0.81412 ,  -0.81513 ,  -0.81614 ,  -0.81714 ,  -0.81815 ,  
+-0.81915 ,  -0.82015 ,  -0.82115 ,  -0.82214 ,  -0.82314 ,  -0.82413 ,  -0.82511 ,  -0.82610 ,  -0.82708 ,  -0.82806 ,  
+-0.82904 ,  -0.83001 ,  -0.83098 ,  -0.83195 ,  -0.83292 ,  -0.83389 ,  -0.83485 ,  -0.83581 ,  -0.83676 ,  -0.83772 ,  
+-0.83867 ,  -0.83962 ,  -0.84057 ,  -0.84151 ,  -0.84245 ,  -0.84339 ,  -0.84433 ,  -0.84526 ,  -0.84619 ,  -0.84712 ,  
+-0.84805 ,  -0.84897 ,  -0.84989 ,  -0.85081 ,  -0.85173 ,  -0.85264 ,  -0.85355 ,  -0.85446 ,  -0.85536 ,  -0.85627 ,  
+-0.85717 ,  -0.85806 ,  -0.85896 ,  -0.85985 ,  -0.86074 ,  -0.86163 ,  -0.86251 ,  -0.86340 ,  -0.86427 ,  -0.86515 ,  
+-0.86603 ,  -0.86690 ,  -0.86777 ,  -0.86863 ,  -0.86949 ,  -0.87036 ,  -0.87121 ,  -0.87207 ,  -0.87292 ,  -0.87377 ,  
+-0.87462 ,  -0.87546 ,  -0.87631 ,  -0.87715 ,  -0.87798 ,  -0.87882 ,  -0.87965 ,  -0.88048 ,  -0.88130 ,  -0.88213 ,  
+-0.88295 ,  -0.88377 ,  -0.88458 ,  -0.88539 ,  -0.88620 ,  -0.88701 ,  -0.88782 ,  -0.88862 ,  -0.88942 ,  -0.89021 ,  
+-0.89101 ,  -0.89180 ,  -0.89259 ,  -0.89337 ,  -0.89415 ,  -0.89493 ,  -0.89571 ,  -0.89649 ,  -0.89726 ,  -0.89803 ,  
+-0.89879 ,  -0.89956 ,  -0.90032 ,  -0.90108 ,  -0.90183 ,  -0.90259 ,  -0.90334 ,  -0.90408 ,  -0.90483 ,  -0.90557 ,  
+-0.90631 ,  -0.90704 ,  -0.90778 ,  -0.90851 ,  -0.90924 ,  -0.90996 ,  -0.91068 ,  -0.91140 ,  -0.91212 ,  -0.91283 ,  
+-0.91355 ,  -0.91425 ,  -0.91496 ,  -0.91566 ,  -0.91636 ,  -0.91706 ,  -0.91775 ,  -0.91845 ,  -0.91914 ,  -0.91982 ,  
+-0.92050 ,  -0.92119 ,  -0.92186 ,  -0.92254 ,  -0.92321 ,  -0.92388 ,  -0.92455 ,  -0.92521 ,  -0.92587 ,  -0.92653 ,  
+-0.92718 ,  -0.92784 ,  -0.92849 ,  -0.92913 ,  -0.92978 ,  -0.93042 ,  -0.93106 ,  -0.93169 ,  -0.93232 ,  -0.93295 ,  
+-0.93358 ,  -0.93420 ,  -0.93483 ,  -0.93544 ,  -0.93606 ,  -0.93667 ,  -0.93728 ,  -0.93789 ,  -0.93849 ,  -0.93909 ,  
+-0.93969 ,  -0.94029 ,  -0.94088 ,  -0.94147 ,  -0.94206 ,  -0.94264 ,  -0.94322 ,  -0.94380 ,  -0.94438 ,  -0.94495 ,  
+-0.94552 ,  -0.94609 ,  -0.94665 ,  -0.94721 ,  -0.94777 ,  -0.94832 ,  -0.94888 ,  -0.94943 ,  -0.94997 ,  -0.95052 ,  
+-0.95106 ,  -0.95159 ,  -0.95213 ,  -0.95266 ,  -0.95319 ,  -0.95372 ,  -0.95424 ,  -0.95476 ,  -0.95528 ,  -0.95579 ,  
+-0.95630 ,  -0.95681 ,  -0.95732 ,  -0.95782 ,  -0.95832 ,  -0.95882 ,  -0.95931 ,  -0.95981 ,  -0.96029 ,  -0.96078 ,  
+-0.96126 ,  -0.96174 ,  -0.96222 ,  -0.96269 ,  -0.96316 ,  -0.96363 ,  -0.96410 ,  -0.96456 ,  -0.96502 ,  -0.96547 ,  
+-0.96593 ,  -0.96638 ,  -0.96682 ,  -0.96727 ,  -0.96771 ,  -0.96815 ,  -0.96858 ,  -0.96902 ,  -0.96945 ,  -0.96987 ,  
+-0.97030 ,  -0.97072 ,  -0.97113 ,  -0.97155 ,  -0.97196 ,  -0.97237 ,  -0.97278 ,  -0.97318 ,  -0.97358 ,  -0.97398 ,  
+-0.97437 ,  -0.97476 ,  -0.97515 ,  -0.97553 ,  -0.97592 ,  -0.97630 ,  -0.97667 ,  -0.97705 ,  -0.97742 ,  -0.97778 ,  
+-0.97815 ,  -0.97851 ,  -0.97887 ,  -0.97922 ,  -0.97958 ,  -0.97992 ,  -0.98027 ,  -0.98061 ,  -0.98096 ,  -0.98129 ,  
+-0.98163 ,  -0.98196 ,  -0.98229 ,  -0.98261 ,  -0.98294 ,  -0.98325 ,  -0.98357 ,  -0.98389 ,  -0.98420 ,  -0.98450 ,  
+-0.98481 ,  -0.98511 ,  -0.98541 ,  -0.98570 ,  -0.98600 ,  -0.98629 ,  -0.98657 ,  -0.98686 ,  -0.98714 ,  -0.98741 ,  
+-0.98769 ,  -0.98796 ,  -0.98823 ,  -0.98849 ,  -0.98876 ,  -0.98902 ,  -0.98927 ,  -0.98953 ,  -0.98978 ,  -0.99002 ,  
+-0.99027 ,  -0.99051 ,  -0.99075 ,  -0.99098 ,  -0.99122 ,  -0.99144 ,  -0.99167 ,  -0.99189 ,  -0.99211 ,  -0.99233 ,  
+-0.99255 ,  -0.99276 ,  -0.99297 ,  -0.99317 ,  -0.99337 ,  -0.99357 ,  -0.99377 ,  -0.99396 ,  -0.99415 ,  -0.99434 ,  
+-0.99452 ,  -0.99470 ,  -0.99488 ,  -0.99506 ,  -0.99523 ,  -0.99540 ,  -0.99556 ,  -0.99572 ,  -0.99588 ,  -0.99604 ,  
+-0.99619 ,  -0.99635 ,  -0.99649 ,  -0.99664 ,  -0.99678 ,  -0.99692 ,  -0.99705 ,  -0.99719 ,  -0.99731 ,  -0.99744 ,  
+-0.99756 ,  -0.99768 ,  -0.99780 ,  -0.99792 ,  -0.99803 ,  -0.99813 ,  -0.99824 ,  -0.99834 ,  -0.99844 ,  -0.99854 ,  
+-0.99863 ,  -0.99872 ,  -0.99881 ,  -0.99889 ,  -0.99897 ,  -0.99905 ,  -0.99912 ,  -0.99919 ,  -0.99926 ,  -0.99933 ,  
+-0.99939 ,  -0.99945 ,  -0.99951 ,  -0.99956 ,  -0.99961 ,  -0.99966 ,  -0.99970 ,  -0.99974 ,  -0.99978 ,  -0.99982 ,  
+-0.99985 ,  -0.99988 ,  -0.99990 ,  -0.99993 ,  -0.99995 ,  -0.99996 ,  -0.99998 ,  -0.99999 ,  -0.99999 ,  -1.00000 ,  
+-1.00000 ,  -1.00000 ,  -0.99999 ,  -0.99999 ,  -0.99998 ,  -0.99996 ,  -0.99995 ,  -0.99993 ,  -0.99990 ,  -0.99988 ,  
+-0.99985 ,  -0.99982 ,  -0.99978 ,  -0.99974 ,  -0.99970 ,  -0.99966 ,  -0.99961 ,  -0.99956 ,  -0.99951 ,  -0.99945 ,  
+-0.99939 ,  -0.99933 ,  -0.99926 ,  -0.99919 ,  -0.99912 ,  -0.99905 ,  -0.99897 ,  -0.99889 ,  -0.99881 ,  -0.99872 ,  
+-0.99863 ,  -0.99854 ,  -0.99844 ,  -0.99834 ,  -0.99824 ,  -0.99813 ,  -0.99803 ,  -0.99792 ,  -0.99780 ,  -0.99768 ,  
+-0.99756 ,  -0.99744 ,  -0.99731 ,  -0.99719 ,  -0.99705 ,  -0.99692 ,  -0.99678 ,  -0.99664 ,  -0.99649 ,  -0.99635 ,  
+-0.99619 ,  -0.99604 ,  -0.99588 ,  -0.99572 ,  -0.99556 ,  -0.99540 ,  -0.99523 ,  -0.99506 ,  -0.99488 ,  -0.99470 ,  
+-0.99452 ,  -0.99434 ,  -0.99415 ,  -0.99396 ,  -0.99377 ,  -0.99357 ,  -0.99337 ,  -0.99317 ,  -0.99297 ,  -0.99276 ,  
+-0.99255 ,  -0.99233 ,  -0.99211 ,  -0.99189 ,  -0.99167 ,  -0.99144 ,  -0.99122 ,  -0.99098 ,  -0.99075 ,  -0.99051 ,  
+-0.99027 ,  -0.99002 ,  -0.98978 ,  -0.98953 ,  -0.98927 ,  -0.98902 ,  -0.98876 ,  -0.98849 ,  -0.98823 ,  -0.98796 ,  
+-0.98769 ,  -0.98741 ,  -0.98714 ,  -0.98686 ,  -0.98657 ,  -0.98629 ,  -0.98600 ,  -0.98570 ,  -0.98541 ,  -0.98511 ,  
+-0.98481 ,  -0.98450 ,  -0.98420 ,  -0.98389 ,  -0.98357 ,  -0.98325 ,  -0.98294 ,  -0.98261 ,  -0.98229 ,  -0.98196 ,  
+-0.98163 ,  -0.98129 ,  -0.98096 ,  -0.98061 ,  -0.98027 ,  -0.97992 ,  -0.97958 ,  -0.97922 ,  -0.97887 ,  -0.97851 ,  
+-0.97815 ,  -0.97778 ,  -0.97742 ,  -0.97705 ,  -0.97667 ,  -0.97630 ,  -0.97592 ,  -0.97553 ,  -0.97515 ,  -0.97476 ,  
+-0.97437 ,  -0.97398 ,  -0.97358 ,  -0.97318 ,  -0.97278 ,  -0.97237 ,  -0.97196 ,  -0.97155 ,  -0.97113 ,  -0.97072 ,  
+-0.97030 ,  -0.96987 ,  -0.96945 ,  -0.96902 ,  -0.96858 ,  -0.96815 ,  -0.96771 ,  -0.96727 ,  -0.96682 ,  -0.96638 ,  
+-0.96593 ,  -0.96547 ,  -0.96502 ,  -0.96456 ,  -0.96410 ,  -0.96363 ,  -0.96316 ,  -0.96269 ,  -0.96222 ,  -0.96174 ,  
+-0.96126 ,  -0.96078 ,  -0.96029 ,  -0.95981 ,  -0.95931 ,  -0.95882 ,  -0.95832 ,  -0.95782 ,  -0.95732 ,  -0.95681 ,  
+-0.95630 ,  -0.95579 ,  -0.95528 ,  -0.95476 ,  -0.95424 ,  -0.95372 ,  -0.95319 ,  -0.95266 ,  -0.95213 ,  -0.95159 ,  
+-0.95106 ,  -0.95052 ,  -0.94997 ,  -0.94943 ,  -0.94888 ,  -0.94832 ,  -0.94777 ,  -0.94721 ,  -0.94665 ,  -0.94609 ,  
+-0.94552 ,  -0.94495 ,  -0.94438 ,  -0.94380 ,  -0.94322 ,  -0.94264 ,  -0.94206 ,  -0.94147 ,  -0.94088 ,  -0.94029 ,  
+-0.93969 ,  -0.93909 ,  -0.93849 ,  -0.93789 ,  -0.93728 ,  -0.93667 ,  -0.93606 ,  -0.93544 ,  -0.93483 ,  -0.93420 ,  
+-0.93358 ,  -0.93295 ,  -0.93232 ,  -0.93169 ,  -0.93106 ,  -0.93042 ,  -0.92978 ,  -0.92913 ,  -0.92849 ,  -0.92784 ,  
+-0.92718 ,  -0.92653 ,  -0.92587 ,  -0.92521 ,  -0.92455 ,  -0.92388 ,  -0.92321 ,  -0.92254 ,  -0.92186 ,  -0.92119 ,  
+-0.92050 ,  -0.91982 ,  -0.91914 ,  -0.91845 ,  -0.91775 ,  -0.91706 ,  -0.91636 ,  -0.91566 ,  -0.91496 ,  -0.91425 ,  
+-0.91355 ,  -0.91283 ,  -0.91212 ,  -0.91140 ,  -0.91068 ,  -0.90996 ,  -0.90924 ,  -0.90851 ,  -0.90778 ,  -0.90704 ,  
+-0.90631 ,  -0.90557 ,  -0.90483 ,  -0.90408 ,  -0.90334 ,  -0.90259 ,  -0.90183 ,  -0.90108 ,  -0.90032 ,  -0.89956 ,  
+-0.89879 ,  -0.89803 ,  -0.89726 ,  -0.89649 ,  -0.89571 ,  -0.89493 ,  -0.89415 ,  -0.89337 ,  -0.89259 ,  -0.89180 ,  
+-0.89101 ,  -0.89021 ,  -0.88942 ,  -0.88862 ,  -0.88782 ,  -0.88701 ,  -0.88620 ,  -0.88539 ,  -0.88458 ,  -0.88377 ,  
+-0.88295 ,  -0.88213 ,  -0.88130 ,  -0.88048 ,  -0.87965 ,  -0.87882 ,  -0.87798 ,  -0.87715 ,  -0.87631 ,  -0.87546 ,  
+-0.87462 ,  -0.87377 ,  -0.87292 ,  -0.87207 ,  -0.87121 ,  -0.87036 ,  -0.86949 ,  -0.86863 ,  -0.86777 ,  -0.86690 ,  
+-0.86603 ,  -0.86515 ,  -0.86427 ,  -0.86340 ,  -0.86251 ,  -0.86163 ,  -0.86074 ,  -0.85985 ,  -0.85896 ,  -0.85806 ,  
+-0.85717 ,  -0.85627 ,  -0.85536 ,  -0.85446 ,  -0.85355 ,  -0.85264 ,  -0.85173 ,  -0.85081 ,  -0.84989 ,  -0.84897 ,  
+-0.84805 ,  -0.84712 ,  -0.84619 ,  -0.84526 ,  -0.84433 ,  -0.84339 ,  -0.84245 ,  -0.84151 ,  -0.84057 ,  -0.83962 ,  
+-0.83867 ,  -0.83772 ,  -0.83676 ,  -0.83581 ,  -0.83485 ,  -0.83389 ,  -0.83292 ,  -0.83195 ,  -0.83098 ,  -0.83001 ,  
+-0.82904 ,  -0.82806 ,  -0.82708 ,  -0.82610 ,  -0.82511 ,  -0.82413 ,  -0.82314 ,  -0.82214 ,  -0.82115 ,  -0.82015 ,  
+-0.81915 ,  -0.81815 ,  -0.81714 ,  -0.81614 ,  -0.81513 ,  -0.81412 ,  -0.81310 ,  -0.81208 ,  -0.81106 ,  -0.81004 ,  
+-0.80902 ,  -0.80799 ,  -0.80696 ,  -0.80593 ,  -0.80489 ,  -0.80386 ,  -0.80282 ,  -0.80178 ,  -0.80073 ,  -0.79968 ,  
+-0.79864 ,  -0.79758 ,  -0.79653 ,  -0.79547 ,  -0.79441 ,  -0.79335 ,  -0.79229 ,  -0.79122 ,  -0.79016 ,  -0.78908 ,  
+-0.78801 ,  -0.78694 ,  -0.78586 ,  -0.78478 ,  -0.78369 ,  -0.78261 ,  -0.78152 ,  -0.78043 ,  -0.77934 ,  -0.77824 ,  
+-0.77715 ,  -0.77605 ,  -0.77494 ,  -0.77384 ,  -0.77273 ,  -0.77162 ,  -0.77051 ,  -0.76940 ,  -0.76828 ,  -0.76717 ,  
+-0.76604 ,  -0.76492 ,  -0.76380 ,  -0.76267 ,  -0.76154 ,  -0.76041 ,  -0.75927 ,  -0.75813 ,  -0.75700 ,  -0.75585 ,  
+-0.75471 ,  -0.75356 ,  -0.75241 ,  -0.75126 ,  -0.75011 ,  -0.74896 ,  -0.74780 ,  -0.74664 ,  -0.74548 ,  -0.74431 ,  
+-0.74314 ,  -0.74198 ,  -0.74080 ,  -0.73963 ,  -0.73846 ,  -0.73728 ,  -0.73610 ,  -0.73491 ,  -0.73373 ,  -0.73254 ,  
+-0.73135 ,  -0.73016 ,  -0.72897 ,  -0.72777 ,  -0.72657 ,  -0.72537 ,  -0.72417 ,  -0.72297 ,  -0.72176 ,  -0.72055 ,  
+-0.71934 ,  -0.71813 ,  -0.71691 ,  -0.71569 ,  -0.71447 ,  -0.71325 ,  -0.71203 ,  -0.71080 ,  -0.70957 ,  -0.70834 ,  
+-0.70711 ,  -0.70587 ,  -0.70463 ,  -0.70339 ,  -0.70215 ,  -0.70091 ,  -0.69966 ,  -0.69842 ,  -0.69717 ,  -0.69591 ,  
+-0.69466 ,  -0.69340 ,  -0.69214 ,  -0.69088 ,  -0.68962 ,  -0.68835 ,  -0.68709 ,  -0.68582 ,  -0.68455 ,  -0.68327 ,  
+-0.68200 ,  -0.68072 ,  -0.67944 ,  -0.67816 ,  -0.67688 ,  -0.67559 ,  -0.67430 ,  -0.67301 ,  -0.67172 ,  -0.67043 ,  
+-0.66913 ,  -0.66783 ,  -0.66653 ,  -0.66523 ,  -0.66393 ,  -0.66262 ,  -0.66131 ,  -0.66000 ,  -0.65869 ,  -0.65738 ,  
+-0.65606 ,  -0.65474 ,  -0.65342 ,  -0.65210 ,  -0.65077 ,  -0.64945 ,  -0.64812 ,  -0.64679 ,  -0.64546 ,  -0.64412 ,  
+-0.64279 ,  -0.64145 ,  -0.64011 ,  -0.63877 ,  -0.63742 ,  -0.63608 ,  -0.63473 ,  -0.63338 ,  -0.63203 ,  -0.63068 ,  
+-0.62932 ,  -0.62796 ,  -0.62660 ,  -0.62524 ,  -0.62388 ,  -0.62251 ,  -0.62115 ,  -0.61978 ,  -0.61841 ,  -0.61704 ,  
+-0.61566 ,  -0.61429 ,  -0.61291 ,  -0.61153 ,  -0.61015 ,  -0.60876 ,  -0.60738 ,  -0.60599 ,  -0.60460 ,  -0.60321 ,  
+-0.60182 ,  -0.60042 ,  -0.59902 ,  -0.59763 ,  -0.59622 ,  -0.59482 ,  -0.59342 ,  -0.59201 ,  -0.59061 ,  -0.58920 ,  
+-0.58779 ,  -0.58637 ,  -0.58496 ,  -0.58354 ,  -0.58212 ,  -0.58070 ,  -0.57928 ,  -0.57786 ,  -0.57643 ,  -0.57501 ,  
+-0.57358 ,  -0.57215 ,  -0.57071 ,  -0.56928 ,  -0.56784 ,  -0.56641 ,  -0.56497 ,  -0.56353 ,  -0.56208 ,  -0.56064 ,  
+-0.55919 ,  -0.55775 ,  -0.55630 ,  -0.55484 ,  -0.55339 ,  -0.55194 ,  -0.55048 ,  -0.54902 ,  -0.54756 ,  -0.54610 ,  
+-0.54464 ,  -0.54317 ,  -0.54171 ,  -0.54024 ,  -0.53877 ,  -0.53730 ,  -0.53583 ,  -0.53435 ,  -0.53288 ,  -0.53140 ,  
+-0.52992 ,  -0.52844 ,  -0.52696 ,  -0.52547 ,  -0.52399 ,  -0.52250 ,  -0.52101 ,  -0.51952 ,  -0.51803 ,  -0.51653 ,  
+-0.51504 ,  -0.51354 ,  -0.51204 ,  -0.51054 ,  -0.50904 ,  -0.50754 ,  -0.50603 ,  -0.50453 ,  -0.50302 ,  -0.50151 ,  
+-0.50000 ,  -0.49849 ,  -0.49697 ,  -0.49546 ,  -0.49394 ,  -0.49242 ,  -0.49090 ,  -0.48938 ,  -0.48786 ,  -0.48634 ,  
+-0.48481 ,  -0.48328 ,  -0.48175 ,  -0.48022 ,  -0.47869 ,  -0.47716 ,  -0.47562 ,  -0.47409 ,  -0.47255 ,  -0.47101 ,  
+-0.46947 ,  -0.46793 ,  -0.46639 ,  -0.46484 ,  -0.46330 ,  -0.46175 ,  -0.46020 ,  -0.45865 ,  -0.45710 ,  -0.45554 ,  
+-0.45399 ,  -0.45243 ,  -0.45088 ,  -0.44932 ,  -0.44776 ,  -0.44620 ,  -0.44464 ,  -0.44307 ,  -0.44151 ,  -0.43994 ,  
+-0.43837 ,  -0.43680 ,  -0.43523 ,  -0.43366 ,  -0.43209 ,  -0.43051 ,  -0.42894 ,  -0.42736 ,  -0.42578 ,  -0.42420 ,  
+-0.42262 ,  -0.42104 ,  -0.41945 ,  -0.41787 ,  -0.41628 ,  -0.41469 ,  -0.41310 ,  -0.41151 ,  -0.40992 ,  -0.40833 ,  
+-0.40674 ,  -0.40514 ,  -0.40355 ,  -0.40195 ,  -0.40035 ,  -0.39875 ,  -0.39715 ,  -0.39555 ,  -0.39394 ,  -0.39234 ,  
+-0.39073 ,  -0.38912 ,  -0.38752 ,  -0.38591 ,  -0.38430 ,  -0.38268 ,  -0.38107 ,  -0.37946 ,  -0.37784 ,  -0.37622 ,  
+-0.37461 ,  -0.37299 ,  -0.37137 ,  -0.36975 ,  -0.36812 ,  -0.36650 ,  -0.36488 ,  -0.36325 ,  -0.36162 ,  -0.36000 ,  
+-0.35837 ,  -0.35674 ,  -0.35511 ,  -0.35347 ,  -0.35184 ,  -0.35021 ,  -0.34857 ,  -0.34694 ,  -0.34530 ,  -0.34366 ,  
+-0.34202 ,  -0.34038 ,  -0.33874 ,  -0.33710 ,  -0.33545 ,  -0.33381 ,  -0.33216 ,  -0.33051 ,  -0.32887 ,  -0.32722 ,  
+-0.32557 ,  -0.32392 ,  -0.32227 ,  -0.32061 ,  -0.31896 ,  -0.31730 ,  -0.31565 ,  -0.31399 ,  -0.31233 ,  -0.31068 ,  
+-0.30902 ,  -0.30736 ,  -0.30570 ,  -0.30403 ,  -0.30237 ,  -0.30071 ,  -0.29904 ,  -0.29737 ,  -0.29571 ,  -0.29404 ,  
+-0.29237 ,  -0.29070 ,  -0.28903 ,  -0.28736 ,  -0.28569 ,  -0.28402 ,  -0.28234 ,  -0.28067 ,  -0.27899 ,  -0.27731 ,  
+-0.27564 ,  -0.27396 ,  -0.27228 ,  -0.27060 ,  -0.26892 ,  -0.26724 ,  -0.26556 ,  -0.26387 ,  -0.26219 ,  -0.26050 ,  
+-0.25882 ,  -0.25713 ,  -0.25545 ,  -0.25376 ,  -0.25207 ,  -0.25038 ,  -0.24869 ,  -0.24700 ,  -0.24531 ,  -0.24362 ,  
+-0.24192 ,  -0.24023 ,  -0.23853 ,  -0.23684 ,  -0.23514 ,  -0.23345 ,  -0.23175 ,  -0.23005 ,  -0.22835 ,  -0.22665 ,  
+-0.22495 ,  -0.22325 ,  -0.22155 ,  -0.21985 ,  -0.21814 ,  -0.21644 ,  -0.21474 ,  -0.21303 ,  -0.21132 ,  -0.20962 ,  
+-0.20791 ,  -0.20620 ,  -0.20450 ,  -0.20279 ,  -0.20108 ,  -0.19937 ,  -0.19766 ,  -0.19595 ,  -0.19423 ,  -0.19252 ,  
+-0.19081 ,  -0.18910 ,  -0.18738 ,  -0.18567 ,  -0.18395 ,  -0.18224 ,  -0.18052 ,  -0.17880 ,  -0.17708 ,  -0.17537 ,  
+-0.17365 ,  -0.17193 ,  -0.17021 ,  -0.16849 ,  -0.16677 ,  -0.16505 ,  -0.16333 ,  -0.16160 ,  -0.15988 ,  -0.15816 ,  
+-0.15643 ,  -0.15471 ,  -0.15299 ,  -0.15126 ,  -0.14954 ,  -0.14781 ,  -0.14608 ,  -0.14436 ,  -0.14263 ,  -0.14090 ,  
+-0.13917 ,  -0.13744 ,  -0.13572 ,  -0.13399 ,  -0.13226 ,  -0.13053 ,  -0.12880 ,  -0.12706 ,  -0.12533 ,  -0.12360 ,  
+-0.12187 ,  -0.12014 ,  -0.11840 ,  -0.11667 ,  -0.11494 ,  -0.11320 ,  -0.11147 ,  -0.10973 ,  -0.10800 ,  -0.10626 ,  
+-0.10453 ,  -0.10279 ,  -0.10106 ,  -0.09932 ,  -0.09758 ,  -0.09585 ,  -0.09411 ,  -0.09237 ,  -0.09063 ,  -0.08889 ,  
+-0.08716 ,  -0.08542 ,  -0.08368 ,  -0.08194 ,  -0.08020 ,  -0.07846 ,  -0.07672 ,  -0.07498 ,  -0.07324 ,  -0.07150 ,  
+-0.06976 ,  -0.06802 ,  -0.06627 ,  -0.06453 ,  -0.06279 ,  -0.06105 ,  -0.05931 ,  -0.05756 ,  -0.05582 ,  -0.05408 ,  
+-0.05234 ,  -0.05059 ,  -0.04885 ,  -0.04711 ,  -0.04536 ,  -0.04362 ,  -0.04188 ,  -0.04013 ,  -0.03839 ,  -0.03664 ,  
+-0.03490 ,  -0.03316 ,  -0.03141 ,  -0.02967 ,  -0.02792 ,  -0.02618 ,  -0.02443 ,  -0.02269 ,  -0.02094 ,  -0.01920 ,  
+-0.01745 ,  -0.01571 ,  -0.01396 ,  -0.01222 ,  -0.01047 ,  -0.00873 ,  -0.00698 ,  -0.00524 ,  -0.00349 ,  -0.00175 ,  
+0.00000 ,   0.00175 ,   0.00349 ,   0.00524 ,   0.00698 ,   0.00873 ,   0.01047 ,   0.01222 ,   0.01396 ,   0.01571 ,   
+0.01745 ,   0.01920 ,   0.02094 ,   0.02269 ,   0.02443 ,   0.02618 ,   0.02792 ,   0.02967 ,   0.03141 ,   0.03316 ,   
+0.03490 ,   0.03664 ,   0.03839 ,   0.04013 ,   0.04188 ,   0.04362 ,   0.04536 ,   0.04711 ,   0.04885 ,   0.05059 ,   
+0.05234 ,   0.05408 ,   0.05582 ,   0.05756 ,   0.05931 ,   0.06105 ,   0.06279 ,   0.06453 ,   0.06627 ,   0.06802 ,   
+0.06976 ,   0.07150 ,   0.07324 ,   0.07498 ,   0.07672 ,   0.07846 ,   0.08020 ,   0.08194 ,   0.08368 ,   0.08542 ,   
+0.08716 ,   0.08889 ,   0.09063 ,   0.09237 ,   0.09411 ,   0.09585 ,   0.09758 ,   0.09932 ,   0.10106 ,   0.10279 ,   
+0.10453 ,   0.10626 ,   0.10800 ,   0.10973 ,   0.11147 ,   0.11320 ,   0.11494 ,   0.11667 ,   0.11840 ,   0.12014 ,   
+0.12187 ,   0.12360 ,   0.12533 ,   0.12706 ,   0.12880 ,   0.13053 ,   0.13226 ,   0.13399 ,   0.13572 ,   0.13744 ,   
+0.13917 ,   0.14090 ,   0.14263 ,   0.14436 ,   0.14608 ,   0.14781 ,   0.14954 ,   0.15126 ,   0.15299 ,   0.15471 ,   
+0.15643 ,   0.15816 ,   0.15988 ,   0.16160 ,   0.16333 ,   0.16505 ,   0.16677 ,   0.16849 ,   0.17021 ,   0.17193 ,   
+0.17365 ,   0.17537 ,   0.17708 ,   0.17880 ,   0.18052 ,   0.18224 ,   0.18395 ,   0.18567 ,   0.18738 ,   0.18910 ,   
+0.19081 ,   0.19252 ,   0.19423 ,   0.19595 ,   0.19766 ,   0.19937 ,   0.20108 ,   0.20279 ,   0.20450 ,   0.20620 ,   
+0.20791 ,   0.20962 ,   0.21132 ,   0.21303 ,   0.21474 ,   0.21644 ,   0.21814 ,   0.21985 ,   0.22155 ,   0.22325 ,   
+0.22495 ,   0.22665 ,   0.22835 ,   0.23005 ,   0.23175 ,   0.23345 ,   0.23514 ,   0.23684 ,   0.23853 ,   0.24023 ,   
+0.24192 ,   0.24362 ,   0.24531 ,   0.24700 ,   0.24869 ,   0.25038 ,   0.25207 ,   0.25376 ,   0.25545 ,   0.25713 ,   
+0.25882 ,   0.26050 ,   0.26219 ,   0.26387 ,   0.26556 ,   0.26724 ,   0.26892 ,   0.27060 ,   0.27228 ,   0.27396 ,   
+0.27564 ,   0.27731 ,   0.27899 ,   0.28067 ,   0.28234 ,   0.28402 ,   0.28569 ,   0.28736 ,   0.28903 ,   0.29070 ,   
+0.29237 ,   0.29404 ,   0.29571 ,   0.29737 ,   0.29904 ,   0.30071 ,   0.30237 ,   0.30403 ,   0.30570 ,   0.30736 ,   
+0.30902 ,   0.31068 ,   0.31233 ,   0.31399 ,   0.31565 ,   0.31730 ,   0.31896 ,   0.32061 ,   0.32227 ,   0.32392 ,   
+0.32557 ,   0.32722 ,   0.32887 ,   0.33051 ,   0.33216 ,   0.33381 ,   0.33545 ,   0.33710 ,   0.33874 ,   0.34038 ,   
+0.34202 ,   0.34366 ,   0.34530 ,   0.34694 ,   0.34857 ,   0.35021 ,   0.35184 ,   0.35347 ,   0.35511 ,   0.35674 ,   
+0.35837 ,   0.36000 ,   0.36162 ,   0.36325 ,   0.36488 ,   0.36650 ,   0.36812 ,   0.36975 ,   0.37137 ,   0.37299 ,   
+0.37461 ,   0.37622 ,   0.37784 ,   0.37946 ,   0.38107 ,   0.38268 ,   0.38430 ,   0.38591 ,   0.38752 ,   0.38912 ,   
+0.39073 ,   0.39234 ,   0.39394 ,   0.39555 ,   0.39715 ,   0.39875 ,   0.40035 ,   0.40195 ,   0.40355 ,   0.40514 ,   
+0.40674 ,   0.40833 ,   0.40992 ,   0.41151 ,   0.41310 ,   0.41469 ,   0.41628 ,   0.41787 ,   0.41945 ,   0.42104 ,   
+0.42262 ,   0.42420 ,   0.42578 ,   0.42736 ,   0.42894 ,   0.43051 ,   0.43209 ,   0.43366 ,   0.43523 ,   0.43680 ,   
+0.43837 ,   0.43994 ,   0.44151 ,   0.44307 ,   0.44464 ,   0.44620 ,   0.44776 ,   0.44932 ,   0.45088 ,   0.45243 ,   
+0.45399 ,   0.45554 ,   0.45710 ,   0.45865 ,   0.46020 ,   0.46175 ,   0.46330 ,   0.46484 ,   0.46639 ,   0.46793 ,   
+0.46947 ,   0.47101 ,   0.47255 ,   0.47409 ,   0.47562 ,   0.47716 ,   0.47869 ,   0.48022 ,   0.48175 ,   0.48328 ,   
+0.48481 ,   0.48634 ,   0.48786 ,   0.48938 ,   0.49090 ,   0.49242 ,   0.49394 ,   0.49546 ,   0.49697 ,   0.49849 ,   
+0.50000 ,   0.50151 ,   0.50302 ,   0.50453 ,   0.50603 ,   0.50754 ,   0.50904 ,   0.51054 ,   0.51204 ,   0.51354 ,   
+0.51504 ,   0.51653 ,   0.51803 ,   0.51952 ,   0.52101 ,   0.52250 ,   0.52399 ,   0.52547 ,   0.52696 ,   0.52844 ,   
+0.52992 ,   0.53140 ,   0.53288 ,   0.53435 ,   0.53583 ,   0.53730 ,   0.53877 ,   0.54024 ,   0.54171 ,   0.54317 ,   
+0.54464 ,   0.54610 ,   0.54756 ,   0.54902 ,   0.55048 ,   0.55194 ,   0.55339 ,   0.55484 ,   0.55630 ,   0.55775 ,   
+0.55919 ,   0.56064 ,   0.56208 ,   0.56353 ,   0.56497 ,   0.56641 ,   0.56784 ,   0.56928 ,   0.57071 ,   0.57215 ,   
+0.57358 ,   0.57501 ,   0.57643 ,   0.57786 ,   0.57928 ,   0.58070 ,   0.58212 ,   0.58354 ,   0.58496 ,   0.58637 ,   
+0.58779 ,   0.58920 ,   0.59061 ,   0.59201 ,   0.59342 ,   0.59482 ,   0.59622 ,   0.59763 ,   0.59902 ,   0.60042 ,   
+0.60182 ,   0.60321 ,   0.60460 ,   0.60599 ,   0.60738 ,   0.60876 ,   0.61015 ,   0.61153 ,   0.61291 ,   0.61429 ,   
+0.61566 ,   0.61704 ,   0.61841 ,   0.61978 ,   0.62115 ,   0.62251 ,   0.62388 ,   0.62524 ,   0.62660 ,   0.62796 ,   
+0.62932 ,   0.63068 ,   0.63203 ,   0.63338 ,   0.63473 ,   0.63608 ,   0.63742 ,   0.63877 ,   0.64011 ,   0.64145 ,   
+0.64279 ,   0.64412 ,   0.64546 ,   0.64679 ,   0.64812 ,   0.64945 ,   0.65077 ,   0.65210 ,   0.65342 ,   0.65474 ,   
+0.65606 ,   0.65738 ,   0.65869 ,   0.66000 ,   0.66131 ,   0.66262 ,   0.66393 ,   0.66523 ,   0.66653 ,   0.66783 ,   
+0.66913 ,   0.67043 ,   0.67172 ,   0.67301 ,   0.67430 ,   0.67559 ,   0.67688 ,   0.67816 ,   0.67944 ,   0.68072 ,   
+0.68200 ,   0.68327 ,   0.68455 ,   0.68582 ,   0.68709 ,   0.68835 ,   0.68962 ,   0.69088 ,   0.69214 ,   0.69340 ,   
+0.69466 ,   0.69591 ,   0.69717 ,   0.69842 ,   0.69966 ,   0.70091 ,   0.70215 ,   0.70339 ,   0.70463 ,   0.70587 ,   
+0.70711 ,   0.70834 ,   0.70957 ,   0.71080 ,   0.71203 ,   0.71325 ,   0.71447 ,   0.71569 ,   0.71691 ,   0.71813 ,   
+0.71934 ,   0.72055 ,   0.72176 ,   0.72297 ,   0.72417 ,   0.72537 ,   0.72657 ,   0.72777 ,   0.72897 ,   0.73016 ,   
+0.73135 ,   0.73254 ,   0.73373 ,   0.73491 ,   0.73610 ,   0.73728 ,   0.73846 ,   0.73963 ,   0.74080 ,   0.74198 ,   
+0.74314 ,   0.74431 ,   0.74548 ,   0.74664 ,   0.74780 ,   0.74896 ,   0.75011 ,   0.75126 ,   0.75241 ,   0.75356 ,   
+0.75471 ,   0.75585 ,   0.75700 ,   0.75813 ,   0.75927 ,   0.76041 ,   0.76154 ,   0.76267 ,   0.76380 ,   0.76492 ,   
+0.76604 ,   0.76717 ,   0.76828 ,   0.76940 ,   0.77051 ,   0.77162 ,   0.77273 ,   0.77384 ,   0.77494 ,   0.77605 ,   
+0.77715 ,   0.77824 ,   0.77934 ,   0.78043 ,   0.78152 ,   0.78261 ,   0.78369 ,   0.78478 ,   0.78586 ,   0.78694 ,   
+0.78801 ,   0.78908 ,   0.79016 ,   0.79122 ,   0.79229 ,   0.79335 ,   0.79441 ,   0.79547 ,   0.79653 ,   0.79758 ,   
+0.79864 ,   0.79968 ,   0.80073 ,   0.80178 ,   0.80282 ,   0.80386 ,   0.80489 ,   0.80593 ,   0.80696 ,   0.80799 ,   
+0.80902 ,   0.81004 ,   0.81106 ,   0.81208 ,   0.81310 ,   0.81412 ,   0.81513 ,   0.81614 ,   0.81714 ,   0.81815 ,   
+0.81915 ,   0.82015 ,   0.82115 ,   0.82214 ,   0.82314 ,   0.82413 ,   0.82511 ,   0.82610 ,   0.82708 ,   0.82806 ,   
+0.82904 ,   0.83001 ,   0.83098 ,   0.83195 ,   0.83292 ,   0.83389 ,   0.83485 ,   0.83581 ,   0.83676 ,   0.83772 ,   
+0.83867 ,   0.83962 ,   0.84057 ,   0.84151 ,   0.84245 ,   0.84339 ,   0.84433 ,   0.84526 ,   0.84619 ,   0.84712 ,   
+0.84805 ,   0.84897 ,   0.84989 ,   0.85081 ,   0.85173 ,   0.85264 ,   0.85355 ,   0.85446 ,   0.85536 ,   0.85627 ,   
+0.85717 ,   0.85806 ,   0.85896 ,   0.85985 ,   0.86074 ,   0.86163 ,   0.86251 ,   0.86340 ,   0.86427 ,   0.86515 ,   
+0.86603 ,   0.86690 ,   0.86777 ,   0.86863 ,   0.86949 ,   0.87036 ,   0.87121 ,   0.87207 ,   0.87292 ,   0.87377 ,   
+0.87462 ,   0.87546 ,   0.87631 ,   0.87715 ,   0.87798 ,   0.87882 ,   0.87965 ,   0.88048 ,   0.88130 ,   0.88213 ,   
+0.88295 ,   0.88377 ,   0.88458 ,   0.88539 ,   0.88620 ,   0.88701 ,   0.88782 ,   0.88862 ,   0.88942 ,   0.89021 ,   
+0.89101 ,   0.89180 ,   0.89259 ,   0.89337 ,   0.89415 ,   0.89493 ,   0.89571 ,   0.89649 ,   0.89726 ,   0.89803 ,   
+0.89879 ,   0.89956 ,   0.90032 ,   0.90108 ,   0.90183 ,   0.90259 ,   0.90334 ,   0.90408 ,   0.90483 ,   0.90557 ,   
+0.90631 ,   0.90704 ,   0.90778 ,   0.90851 ,   0.90924 ,   0.90996 ,   0.91068 ,   0.91140 ,   0.91212 ,   0.91283 ,   
+0.91355 ,   0.91425 ,   0.91496 ,   0.91566 ,   0.91636 ,   0.91706 ,   0.91775 ,   0.91845 ,   0.91914 ,   0.91982 ,   
+0.92050 ,   0.92119 ,   0.92186 ,   0.92254 ,   0.92321 ,   0.92388 ,   0.92455 ,   0.92521 ,   0.92587 ,   0.92653 ,   
+0.92718 ,   0.92784 ,   0.92849 ,   0.92913 ,   0.92978 ,   0.93042 ,   0.93106 ,   0.93169 ,   0.93232 ,   0.93295 ,   
+0.93358 ,   0.93420 ,   0.93483 ,   0.93544 ,   0.93606 ,   0.93667 ,   0.93728 ,   0.93789 ,   0.93849 ,   0.93909 ,   
+0.93969 ,   0.94029 ,   0.94088 ,   0.94147 ,   0.94206 ,   0.94264 ,   0.94322 ,   0.94380 ,   0.94438 ,   0.94495 ,   
+0.94552 ,   0.94609 ,   0.94665 ,   0.94721 ,   0.94777 ,   0.94832 ,   0.94888 ,   0.94943 ,   0.94997 ,   0.95052 ,   
+0.95106 ,   0.95159 ,   0.95213 ,   0.95266 ,   0.95319 ,   0.95372 ,   0.95424 ,   0.95476 ,   0.95528 ,   0.95579 ,   
+0.95630 ,   0.95681 ,   0.95732 ,   0.95782 ,   0.95832 ,   0.95882 ,   0.95931 ,   0.95981 ,   0.96029 ,   0.96078 ,   
+0.96126 ,   0.96174 ,   0.96222 ,   0.96269 ,   0.96316 ,   0.96363 ,   0.96410 ,   0.96456 ,   0.96502 ,   0.96547 ,   
+0.96593 ,   0.96638 ,   0.96682 ,   0.96727 ,   0.96771 ,   0.96815 ,   0.96858 ,   0.96902 ,   0.96945 ,   0.96987 ,   
+0.97030 ,   0.97072 ,   0.97113 ,   0.97155 ,   0.97196 ,   0.97237 ,   0.97278 ,   0.97318 ,   0.97358 ,   0.97398 ,   
+0.97437 ,   0.97476 ,   0.97515 ,   0.97553 ,   0.97592 ,   0.97630 ,   0.97667 ,   0.97705 ,   0.97742 ,   0.97778 ,   
+0.97815 ,   0.97851 ,   0.97887 ,   0.97922 ,   0.97958 ,   0.97992 ,   0.98027 ,   0.98061 ,   0.98096 ,   0.98129 ,   
+0.98163 ,   0.98196 ,   0.98229 ,   0.98261 ,   0.98294 ,   0.98325 ,   0.98357 ,   0.98389 ,   0.98420 ,   0.98450 ,   
+0.98481 ,   0.98511 ,   0.98541 ,   0.98570 ,   0.98600 ,   0.98629 ,   0.98657 ,   0.98686 ,   0.98714 ,   0.98741 ,   
+0.98769 ,   0.98796 ,   0.98823 ,   0.98849 ,   0.98876 ,   0.98902 ,   0.98927 ,   0.98953 ,   0.98978 ,   0.99002 ,   
+0.99027 ,   0.99051 ,   0.99075 ,   0.99098 ,   0.99122 ,   0.99144 ,   0.99167 ,   0.99189 ,   0.99211 ,   0.99233 ,   
+0.99255 ,   0.99276 ,   0.99297 ,   0.99317 ,   0.99337 ,   0.99357 ,   0.99377 ,   0.99396 ,   0.99415 ,   0.99434 ,   
+0.99452 ,   0.99470 ,   0.99488 ,   0.99506 ,   0.99523 ,   0.99540 ,   0.99556 ,   0.99572 ,   0.99588 ,   0.99604 ,   
+0.99619 ,   0.99635 ,   0.99649 ,   0.99664 ,   0.99678 ,   0.99692 ,   0.99705 ,   0.99719 ,   0.99731 ,   0.99744 ,   
+0.99756 ,   0.99768 ,   0.99780 ,   0.99792 ,   0.99803 ,   0.99813 ,   0.99824 ,   0.99834 ,   0.99844 ,   0.99854 ,   
+0.99863 ,   0.99872 ,   0.99881 ,   0.99889 ,   0.99897 ,   0.99905 ,   0.99912 ,   0.99919 ,   0.99926 ,   0.99933 ,   
+0.99939 ,   0.99945 ,   0.99951 ,   0.99956 ,   0.99961 ,   0.99966 ,   0.99970 ,   0.99974 ,   0.99978 ,   0.99982 ,   
+0.99985 ,   0.99988 ,   0.99990 ,   0.99993 ,   0.99995 ,   0.99996 ,   0.99998 ,   0.99999 ,   0.99999 ,   1.00000 ,   
+};
+*/
+#endif /*_MATH_TABLE_H_*/
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/minilib/switch.cpp	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,54 @@
+#include "mbed.h"
+#include "extern.h"
+
+
+uint8_t _samples[4]={0};
+uint8_t _output[4]={0};
+uint8_t _output_last[4]={0};
+uint8_t _rising_flag[4]={0};
+
+void Sw_sample(void) {
+    int i;
+    for(i=0; i<4; i++){
+        _output_last[i] = _output[i];
+        _output[i] = Sw[i].read();
+        if (!_output[i] && _output_last[i])
+        {
+            _rising_flag[i]++;
+        }
+    }
+    //pc.printf("food%d\r\n",_output_last[0]);
+}
+// return number of rising edges
+uint8_t Sw_count(uint8_t pin) {
+    //pin...from 0 to 3
+    if(pin>=4) return 0;
+     uint8_t return_value = _rising_flag[pin]; 
+     _rising_flag[pin] = 0;
+     return(return_value);
+ }
+// return the debounced status
+uint8_t ReadSw(void){
+/******
+ *return : sw_state
+ *スイッチを押したときの動作はdef.hを参照
+ *チャタリング防止ライブラリ採用式
+ *同時押しは判別されない
+ *****/
+    uint8_t i,result;
+    for(i=result=0; i<4; i++){
+        if(Sw_count(i) > 0){
+            result = i+1;
+        }
+    }
+    return result;
+}
+uint8_t CountSw(uint8_t pin){
+/******
+ *return : sw_state
+ *スイッチを押したときの動作はdef.hを参照
+ *チャタリング防止ライブラリ採用式
+ *同時押しは判別されない
+ *****/
+    return (Sw_count(pin) > 0);
+}
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/minilib/switch.h	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,11 @@
+#ifndef _SWITCH_H_
+#define _SWITCH_H_
+
+void Sw_sample(void);
+// return number of rising edges
+uint8_t Sw_count(uint8_t pin);
+// return the debounced status
+
+uint8_t ReadSw(void);
+uint8_t CountSw(uint8_t pin);
+#endif /*_SWITCH_H_*/
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/minilib/txrx.cpp	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,78 @@
+#include "mbed.h"
+#include "txrx.h"
+#include "def.h"
+
+#include "extern.h"
+
+void cls() {
+    for(int i=0;i<DATA_NUM;i++) INdata[i]=0;
+}
+void TX(void){//送信バッファ空き割り込み用関数
+    
+    static uint8_t Tx=DATA_NUM, i;
+    static uint8_t TXdata[DATA_NUM]={TX_KEYCODE};
+    static uint8_t TXcheckcode=0;
+    
+    if(Tx >= DATA_NUM){
+        
+        TXdata[KEY] = TX_KEYCODE;//Hello.
+        
+        TXdata[1] = EXdata[1];
+        TXdata[2] = EXdata[2];
+        TXdata[3] = EXdata[3];
+        TXdata[4] = EXdata[4];
+        TXdata[5] = EXdata[5];
+        TXdata[6] = EXdata[6];
+        TXdata[7] = EXdata[7];
+        TXdata[8] = EXdata[8];
+        //送信するデータ = メインで処理されたデータ
+        
+        for(i=KEY+1, TXcheckcode=0; i<CHECK; i++){//CHECKCODEの生成
+            TXcheckcode ^= TXdata[i];
+        }
+        
+        TXdata[CHECK] = TXcheckcode;//Good bye.
+        Tx=0;//配列をリセット
+        
+    }
+    RN42.putc(TXdata[Tx]);//データを送信する
+    Tx++;//配列を入れ替える
+    
+}
+void RX(void){//受信割り込み用関数
+
+    static uint8_t Rx=0, i;
+    static uint8_t RXdata[DATA_NUM]={RX_KEYCODE};
+    static uint8_t RXcheckcode=0;
+    
+    RXdata[Rx] = RN42.getc();//データを受け取る
+    
+    if(RXdata[KEY]==RX_KEYCODE){//KEYCODEが一致したら配列を入れ替える
+        Rx++;
+    }
+    
+    if(Rx==CHECK){//CHECKCODEの生成
+        for(i=KEY+1, RXcheckcode=0; i<CHECK; i++){
+            RXcheckcode ^= RXdata[i];
+        }
+    }
+    
+    if(Rx >= DATA_NUM){
+        if(RXdata[CHECK]==RXcheckcode){//CHECKCODEが合致したらデータを適用する
+            
+            Stp.attach(&cls, .5);
+            INdata[1] = RXdata[1];
+            INdata[2] = RXdata[2];
+            INdata[3] = RXdata[3];
+            INdata[4] = RXdata[4];
+            INdata[5] = RXdata[5];
+            INdata[6] = RXdata[6];
+            INdata[7] = RXdata[7];
+            INdata[8] = RXdata[8];
+            //メインで処理されるデータ = 受け取ったデータ
+            
+        }
+        Rx=0;//配列をリセット
+    }
+    
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/minilib/txrx.h	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,8 @@
+#ifndef _TXRX_H_
+#define _TXRX_H_
+
+void TX(void);//送信バッファ空き割り込み用関数
+void RX(void);//受信割り込み用関数
+void cls(void);
+
+#endif /*_TXRX_H_*/
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/minilib/wordString2.cpp	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,70 @@
+#include "mbed.h"
+#include "def.h"
+
+#include "extern.h"
+
+using namespace std;
+//string StringFIN;
+
+string Int2Char2String(int number)
+{
+    char str[5];
+    sprintf(str, "%d", number);
+    string ss;
+    ss = str;
+    return ss;
+}
+
+void array2(int power1,int power2,int power3,int power4)
+{
+    int input[4] = {power1,power2,power3,power4};
+    int value;
+    string StringA[4] = {"0","0","0","0"};
+    
+    
+    string StringX = "0";
+    string StringY = "0";
+    string StringZ = "0";
+    string String0 = "0";
+    
+    StringFIN = "0";
+    
+    for(int i = 0 ; i < 4; i++){
+        
+        value = input[i];
+        
+        StringX =  Int2Char2String(i+1);
+        
+        if( (value < 0) && (value >= -100) ){
+            StringY = "R";
+            value = abs(value);
+            StringZ = Int2Char2String(value);
+        }else if( (value >= 0) && (value <= 100) ){
+            StringY = "F";
+            StringZ = Int2Char2String(value);
+        }else{
+            value = abs(value);
+            StringY = "F";
+            StringZ = "000";
+        }
+        
+        if(value < 10){
+            String0 = "00";
+            StringZ = String0 + StringZ;
+        }else if(value < 100)
+        {
+            String0 = "0";
+            StringZ = String0 + StringZ;
+        }else{
+            
+        }
+        
+        StringA[i] = (StringX + StringY + StringZ);
+        
+        if(i == 0)StringFIN  = StringA[i];
+        else StringFIN  += StringA[i];
+        
+    }
+    
+    StringFIN += "\r\n";   
+}
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/minilib/wordString2.h	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,7 @@
+#ifndef _WORD_STRING_2_H_
+#define _WORD_STRING_2_H_
+
+string Int2Char2String(int number);
+void array2(int power1,int power2,int power3,int power4);
+
+#endif /*_WORD_STRING_2_H_*/
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/setting/ActiveConfig.h	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,75 @@
+#ifndef _ACTIVE_CONFIG_H_
+#define _ACTIVE_CONFIG_H_
+
+#include "mbed.h"
+#include "extern.h"
+
+
+
+#ifdef RED_CAT
+
+const ActiveItem static act[STRATEGY_NUM]={
+    {"NormalAtk_______", modeAttack0, MODE_ATTACK0},
+    {"Libero__________", modeAttack1, MODE_ATTACK1},
+    {"NonDri_Libero___", modeAttack2, MODE_ATTACK2},
+    {"NonDri_NormalAtk", modeAttack3, MODE_ATTACK3},
+    {"ORIGIN__________", modeAttack4, MODE_ATTACK4},
+    {"NormalAtk_______", modeAttack5, MODE_ATTACK5},
+    
+    {"NormalAtk_______", modeDebug0, MODE_DEBUG0},
+    {"NormalAtk_______", modeDebug1, MODE_DEBUG1},
+    {"NonLn_Libero____", modeDebug2, MODE_DEBUG2},
+    {"NonLn_NormalAtk_", modeDebug3, MODE_DEBUG3},
+    {"NonIr_Libero____", modeDebug4, MODE_DEBUG4},
+    {"NonIr_NormalAtk_", modeDebug5, MODE_DEBUG5},
+};
+
+#endif /*RED_CAT*/
+
+#ifdef GREEN_CAT
+
+
+const ActiveItem static act[STRATEGY_NUM]={
+    {"Libero__________", modeAttack1, MODE_ATTACK1},
+    {"NormalAtk_______", modeAttack0, MODE_ATTACK0},
+    {"NonDri_Libero___", modeAttack2, MODE_ATTACK2},
+    {"NonDri_NormalAtk", modeAttack3, MODE_ATTACK3},
+    {"ORIGIN__________", modeAttack4, MODE_ATTACK4},
+    {"NormalAtk_______", modeAttack5, MODE_ATTACK5},
+    
+    {"NormalAtk_______", modeDebug0, MODE_DEBUG0},
+    {"NormalAtk_______", modeDebug1, MODE_DEBUG1},
+    {"NonLn_Libero____", modeDebug2, MODE_DEBUG2},
+    {"NonLn_NormalAtk_", modeDebug3, MODE_DEBUG3},
+    {"NonIr_Libero____", modeDebug4, MODE_DEBUG4},
+    {"NonIr_NormalAtk_", modeDebug5, MODE_DEBUG5},
+};
+
+#endif /*GREEN_CAT*/
+
+/*
+//{"modeAttack5_____", modeAttack5, MODE_ATTACK5},
+//{"modeAttack2_____", modeAttack2, MODE_ATTACK2},
+{"modeAttack4_____", modeAttack4, MODE_ATTACK4},
+//{"modeAttack0_____", modeAttack0, MODE_ATTACK0},
+{"modeAttack1_____", modeAttack1, MODE_ATTACK1},
+{"modeAttack2_____", modeAttack2, MODE_ATTACK2},
+{"modeAttack3_____", modeAttack3, MODE_ATTACK3},
+{"modeAttack4_____", modeAttack4, MODE_ATTACK4},
+{"modeAttack5_____", modeAttack5, MODE_ATTACK5},
+
+{"modeDebug0______", modeDebug0, MODE_DEBUG0},
+{"modeDebug1______", modeDebug1, MODE_DEBUG1},
+{"modeDebug2______", modeDebug2, MODE_DEBUG2},
+{"modeDebug3______", modeDebug3, MODE_DEBUG3},
+{"modeDebug4______", modeDebug4, MODE_DEBUG4},
+{"modeDebug5______", modeDebug5, MODE_DEBUG5},
+*/
+
+
+//char LcdStr[LCD_COLUMN_NUM];
+//void (*ActiveFunction)(void);
+//uint16_t tag_num;
+
+
+#endif /*_ACTIVE_CONFIG_H_*/
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/setting/CommandConfig.h	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,31 @@
+#ifndef _COMMAND_CONFIG_H_
+#define _COMMAND_CONFIG_H_
+
+#include "mbed.h"
+#include "extern.h"
+
+const CommandItem static item[STATE_NUM_Y]={
+    {{"Start_","Active","______","______"}, 2, Start,               START},
+    {{"TrnSrt","Active","______","______"}, 2, TurnAndStart,        TURN_AND_START},
+    {{"Ir____","IrSpot","IrNote","IrPstn"}, 4, GetIr,               GET_IR},
+    {{"Sens0_","LnABC_","PING__","BallAn"}, 4, GetSns0,             GET_SNS0},
+    {{"Cmps__","cmps__","CpsRst","______"}, 3, RwPid,         RW_PID},
+    {{"ClbTrn","Tuning","______","______"}, 2, CalibrationTurn,    CALIBRATION_TURN},
+    {{"ClbEoE","EntExi","______","______"}, 3, CalibrationEnterOrExit,     CALIBRATION_ENTER_OR_EXIT},
+    {{"PowUP_","NEXT__","CHANGE","______"}, 3, SetPowerDown,           SET_POWER_DOWN},
+    {{"PowDWN","NEXT__","CHANGE","______"}, 3, SetPowerUp,           SET_POWER_UP},
+    {{"Reset_","ByeBye","______","______"}, 2, SoftReset,           SOFT_RESET},
+    {{"StrUP_","NEXT__","CHANGE","______"}, 3, SetStrategyDown,           SET_STRATEGY_DOWN},
+    {{"StrDWN","NEXT__","CHANGE","______"}, 3, SetStrategyUp,           SET_STRATEGY_UP},
+    {{"Kicker","DRIVE_","______","______"}, 2, DriveKicker,           DRIVE_KICKER},
+    {{"Dribbl","DRIVE_","______","______"}, 2, DriveDribblerAndKicker,DRIVE_DRIBBLER_AND_KICKER},
+    {{"Start2","Active","______","______"}, 2, Start2,              START2},
+    {{"None__","Strgy_","Power_","SftRst"}, 4, ZeroFunction,        ZERO_FUNCTION},
+    
+    //char LcdStr[STATE_NUM_X][BUFSIZE];
+    //uint8_t str_num;
+    //uint8_t (*CommandFunction)(uint8_t x);
+    //uint16_t tag_num;
+};
+
+#endif /*_COMMAND_CONFIG_H_*/
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/setting/IrConfig.h	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,789 @@
+#ifndef _IR_CONFIG_H_
+#define _IR_CONFIG_H_
+
+
+#define POW_TABLE_NUM 6
+
+#define IR_STATE_NUM 4
+
+#define IR_NONE     0
+#define IR_FAR      1
+#define IR_CLOSE    2
+#define IR_CLOSER   3
+
+#define IR_FAR2CLOSE 0xAA
+#define IR_CLOSE2FAR 0xBB
+
+#define IR_DEVICE_NUM 20
+
+#define POW_COMBI_NUM 10
+#define POW_SHORT 0
+#define POW_MIDDLE 1
+#define POW_LONG 2
+
+const uint8_t static ir_posi_s[12]={
+    8, 9, 10, 11, 
+    12, 13, 14, 15, 
+    16, 17, 18, 19
+};
+
+const uint8_t static ir_pow_val[POW_COMBI_NUM][3]={//sml
+    {25,25,25},
+    {30,30,50},//start
+    {35,35,35},
+    {40,40,40},
+    {20,30,40},
+    {20,25,30},
+    {25,30,35},
+    {30,35,40},
+    {30,30,40},
+    {25,30,30},
+};
+
+const double static ir_move_val[POW_TABLE_NUM][IR_STATE_NUM][IR_DEVICE_NUM][4]={
+                            
+                                    
+                                    
+                                    
+{                                   
+    {                               
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    },                              
+                                    
+                                    
+                                    
+                                    
+    {                               
+    {   0.7071  ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   0.2588  ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.2588     ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.7071     ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   -0.9239     ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   -0.3827     ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.3827  ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.9239  ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   1.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.8660  ,   0.5000  ,   0.0000  ,   0.0000  },
+    {   0.5000  ,   0.8660  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   1.0000  ,   0.0000  ,   0.0000  },
+    {   -0.5000     ,   0.8660  ,   0.0000  ,   0.0000  },
+    {   -0.8660     ,   0.5000  ,   0.0000  ,   0.0000  },
+    {   -1.0000     ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   -0.8660     ,   -0.5000     ,   0.0000  ,   0.0000  },
+    {   -0.5000     ,   -0.8660     ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   -1.0000     ,   0.0000  ,   0.0000  },
+    {   0.5000  ,   -0.8660     ,   0.0000  ,   0.0000  },
+    {   0.8660  ,   -0.5000     ,   0.0000  ,   0.0000  },
+    },                              
+                                    
+                                    
+                                    
+                                    
+    {                               
+    {   0.7071  ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   0.2588  ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.2588     ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.7071     ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   -0.9239     ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   -0.3827     ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.3827  ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.9239  ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   0.8660  ,   0.0000  ,   0.0000  ,   -0.5000     },
+    {   0.7500  ,   0.4330  ,   0.2500  ,   -0.4330     },
+    {   0.4330  ,   0.7500  ,   0.4330  ,   -0.2500     },
+    {   0.0000  ,   1.0000  ,   0.0000  ,   0.0000  },
+    {   -0.4330     ,   0.7500  ,   -0.4330     ,   -0.2500     },
+    {   -0.7500     ,   0.4330  ,   -0.2500     ,   -0.4330     },
+    {   -0.8660     ,   0.0000  ,   0.0000  ,   -0.5000     },
+    {   -0.7500     ,   -0.4330     ,   0.2500  ,   -0.4330     },
+    {   -0.4330     ,   -0.7500     ,   0.4330  ,   -0.2500     },
+    {   0.0000  ,   -0.8660     ,   0.5000  ,   0.0000  },
+    {   0.4330  ,   -0.7500     ,   -0.4330     ,   -0.2500     },
+    {   0.7500  ,   -0.4330     ,   -0.2500     ,   -0.4330     },
+    },                              
+                                    
+                                    
+                                    
+                                    
+    {                               
+    {   0.7071  ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   0.2588  ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.2588     ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.7071     ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   -0.9239     ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   -0.3827     ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.3827  ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.9239  ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   0.7071  ,   0.0000  ,   0.0000  ,   -0.7071     },
+    {   0.6124  ,   0.3536  ,   0.3536  ,   -0.6124     },
+    {   0.5000  ,   0.8660  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   1.0000  ,   0.0000  ,   0.0000  },
+    {   -0.5000     ,   0.8660  ,   0.0000  ,   0.0000  },
+    {   -0.6124     ,   0.3536  ,   -0.3536     ,   -0.6124     },
+    {   -0.7071     ,   0.0000  ,   0.0000  ,   -0.7071     },
+    {   -0.4330     ,   -0.2500     ,   0.4330  ,   -0.7500     },
+    {   -0.2500     ,   -0.4330     ,   0.7500  ,   -0.4330     },
+    {   0.0000  ,   -0.5000     ,   0.8660  ,   0.0000  },
+    {   0.2500  ,   -0.4330     ,   -0.7500     ,   -0.4330     },
+    {   0.4330  ,   -0.2500     ,   -0.4330     ,   -0.7500     },
+    },                              
+},                                  
+                                    
+                                    
+                                    
+                                    
+                                    
+                                    
+{                                   
+    {                               
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    },                              
+                                    
+                                    
+                                    
+                                    
+    {                               
+    {   0.7071  ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   0.2588  ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.2588     ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.7071     ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   -0.9239     ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   -0.3827     ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.3827  ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.9239  ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   0.8660  ,   0.0000  ,   0.0000  ,   -0.5000     },
+    {   0.7500  ,   0.4330  ,   0.2500  ,   -0.4330     },
+    {   0.4330  ,   0.7500  ,   0.4330  ,   -0.2500     },
+    {   0.0000  ,   1.0000  ,   0.0000  ,   0.0000  },
+    {   -0.4330     ,   0.7500  ,   -0.4330     ,   -0.2500     },
+    {   -0.7500     ,   0.4330  ,   -0.2500     ,   -0.4330     },
+    {   -0.8660     ,   0.0000  ,   0.0000  ,   -0.5000     },
+    {   -0.7500     ,   -0.4330     ,   0.2500  ,   -0.4330     },
+    {   -0.4330     ,   -0.7500     ,   0.4330  ,   -0.2500     },
+    {   0.0000  ,   -0.8660     ,   0.5000  ,   0.0000  },
+    {   0.4330  ,   -0.7500     ,   -0.4330     ,   -0.2500     },
+    {   0.7500  ,   -0.4330     ,   -0.2500     ,   -0.4330     },
+    },                              
+                                    
+                                    
+                                    
+                                    
+    {                               
+    {   0.7071  ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   0.2588  ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.2588     ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.7071     ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   -0.9239     ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   -0.3827     ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.3827  ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.9239  ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   1.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.7500  ,   0.4330  ,   0.2500  ,   -0.4330     },
+    {   0.4330  ,   0.7500  ,   0.4330  ,   -0.2500     },
+    {   0.0000  ,   1.0000  ,   0.0000  ,   0.0000  },
+    {   -0.4330     ,   0.7500  ,   -0.4330     ,   -0.2500     },
+    {   -0.7500     ,   0.4330  ,   -0.2500     ,   -0.4330     },
+    {   -1.0000     ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   -0.7500     ,   -0.4330     ,   -0.2500     ,   0.4330  },
+    {   -0.4330     ,   -0.7500     ,   0.4330  ,   -0.2500     },
+    {   0.0000  ,   -0.7071     ,   0.7071  ,   0.0000  },
+    {   0.4330  ,   -0.7500     ,   -0.4330     ,   -0.2500     },
+    {   0.7500  ,   -0.4330     ,   0.2500  ,   0.4330  },
+    },                              
+                                    
+                                    
+                                    
+                                    
+    {                               
+    {   0.7071  ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   0.2588  ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.2588     ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.7071     ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   -0.9239     ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   -0.3827     ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.3827  ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.9239  ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   1.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.7500  ,   0.4330  ,   0.2500  ,   -0.4330     },
+    {   0.5000  ,   0.8660  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   1.0000  ,   0.0000  ,   0.0000  },
+    {   -0.5000     ,   0.8660  ,   0.0000  ,   0.0000  },
+    {   -0.7500     ,   0.4330  ,   -0.2500     ,   -0.4330     },
+    {   -1.0000     ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   -0.7500     ,   -0.4330     ,   -0.2500     ,   0.4330  },
+    {   -0.4330     ,   -0.7500     ,   0.4330  ,   -0.2500     },
+    {   0.0000  ,   -0.7071     ,   0.7071  ,   0.0000  },
+    {   0.4330  ,   -0.7500     ,   -0.4330     ,   -0.2500     },
+    {   0.7500  ,   -0.4330     ,   0.2500  ,   0.4330  },
+    },                              
+},                                  
+                                    
+                                    
+                                    
+                                    
+                                    
+                                    
+{                                   
+    {                               
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    },                              
+                                    
+                                    
+                                    
+                                    
+    {                               
+    {   0.7071  ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   0.2588  ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.2588     ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.7071     ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   -0.9239     ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   -0.3827     ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.3827  ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.9239  ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   1.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.8660  ,   0.5000  ,   0.0000  ,   0.0000  },
+    {   0.5000  ,   0.8660  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   1.0000  ,   0.0000  ,   0.0000  },
+    {   -0.5000     ,   0.8660  ,   0.0000  ,   0.0000  },
+    {   -0.8660     ,   0.5000  ,   0.0000  ,   0.0000  },
+    {   -1.0000     ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   -0.8660     ,   -0.5000     ,   0.0000  ,   0.0000  },
+    {   -0.5000     ,   -0.8660     ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   -1.0000     ,   0.0000  ,   0.0000  },
+    {   0.5000  ,   -0.8660     ,   0.0000  ,   0.0000  },
+    {   0.8660  ,   -0.5000     ,   0.0000  ,   0.0000  },
+    },                              
+                                    
+                                    
+                                    
+                                    
+    {                               
+    {   0.7071  ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   0.2588  ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.2588     ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.7071     ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   -0.9239     ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   -0.3827     ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.3827  ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.9239  ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   1.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.8660  ,   0.5000  ,   0.0000  ,   0.0000  },
+    {   0.5000  ,   0.8660  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   1.0000  ,   0.0000  ,   0.0000  },
+    {   -0.5000     ,   0.8660  ,   0.0000  ,   0.0000  },
+    {   -0.8660     ,   0.5000  ,   0.0000  ,   0.0000  },
+    {   -1.0000     ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   -0.8660     ,   -0.5000     ,   0.0000  ,   0.0000  },
+    {   -0.5000     ,   -0.8660     ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   -1.0000     ,   0.0000  ,   0.0000  },
+    {   0.5000  ,   -0.8660     ,   0.0000  ,   0.0000  },
+    {   0.8660  ,   -0.5000     ,   0.0000  ,   0.0000  },
+    },                              
+                                    
+                                    
+                                    
+                                    
+    {                               
+    {   0.7071  ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   0.2588  ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.2588     ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.7071     ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   -0.9239     ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   -0.3827     ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.3827  ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.9239  ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   1.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.8660  ,   0.5000  ,   0.0000  ,   0.0000  },
+    {   0.5000  ,   0.8660  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   1.0000  ,   0.0000  ,   0.0000  },
+    {   -0.5000     ,   0.8660  ,   0.0000  ,   0.0000  },
+    {   -0.8660     ,   0.5000  ,   0.0000  ,   0.0000  },
+    {   -1.0000     ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   -0.8660     ,   -0.5000     ,   0.0000  ,   0.0000  },
+    {   -0.5000     ,   -0.8660     ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   -1.0000     ,   0.0000  ,   0.0000  },
+    {   0.5000  ,   -0.8660     ,   0.0000  ,   0.0000  },
+    {   0.8660  ,   -0.5000     ,   0.0000  ,   0.0000  },
+    },                              
+},                                  
+                                    
+                                    
+                                    
+                                    
+                                    
+                                    
+{                                   
+    {                               
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    },                              
+                                    
+                                    
+                                    
+                                    
+    {                               
+    {   0.7071  ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   0.2588  ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.2588     ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.7071     ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   -0.9239     ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   -0.3827     ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.3827  ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.9239  ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   1.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.8660  ,   0.5000  ,   0.0000  ,   0.0000  },
+    {   0.5000  ,   0.8660  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   1.0000  ,   0.0000  ,   0.0000  },
+    {   -0.5000     ,   0.8660  ,   0.0000  ,   0.0000  },
+    {   -0.8660     ,   0.5000  ,   0.0000  ,   0.0000  },
+    {   -1.0000     ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   -0.8660     ,   -0.5000     ,   0.0000  ,   0.0000  },
+    {   -0.5000     ,   -0.8660     ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   -1.0000     ,   0.0000  ,   0.0000  },
+    {   0.5000  ,   -0.8660     ,   0.0000  ,   0.0000  },
+    {   0.8660  ,   -0.5000     ,   0.0000  ,   0.0000  },
+    },                              
+                                    
+                                    
+                                    
+                                    
+    {                               
+    {   0.7071  ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   0.2588  ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.2588     ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.7071     ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   -0.9239     ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   -0.3827     ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.3827  ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.9239  ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   0.8660  ,   0.0000  ,   0.0000  ,   -0.5000     },
+    {   0.7500  ,   0.4330  ,   0.2500  ,   -0.4330     },
+    {   0.4330  ,   0.7500  ,   0.4330  ,   -0.2500     },
+    {   0.0000  ,   1.0000  ,   0.0000  ,   0.0000  },
+    {   -0.4330     ,   0.7500  ,   -0.4330     ,   -0.2500     },
+    {   -0.7500     ,   0.4330  ,   -0.2500     ,   -0.4330     },
+    {   -0.8660     ,   0.0000  ,   0.0000  ,   -0.5000     },
+    {   -0.7500     ,   -0.4330     ,   0.2500  ,   -0.4330     },
+    {   -0.4330     ,   -0.7500     ,   0.4330  ,   -0.2500     },
+    {   0.0000  ,   -0.8660     ,   0.5000  ,   0.0000  },
+    {   0.4330  ,   -0.7500     ,   -0.4330     ,   -0.2500     },
+    {   0.7500  ,   -0.4330     ,   -0.2500     ,   -0.4330     },
+    },                              
+                                    
+                                    
+                                    
+                                    
+    {                               
+    {   0.7071  ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   0.2588  ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.2588     ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.7071     ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   -0.9239     ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   -0.3827     ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.3827  ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.9239  ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   0.5000  ,   0.0000  ,   0.0000  ,   -0.8660     },
+    {   0.0000  ,   0.0000  ,   0.5000  ,   -0.8660     },
+    {   0.4330  ,   0.7500  ,   0.4330  ,   -0.2500     },
+    {   0.0000  ,   1.0000  ,   0.0000  ,   0.0000  },
+    {   -0.4330     ,   0.7500  ,   -0.4330     ,   -0.2500     },
+    {   0.0000  ,   0.0000  ,   -0.5000     ,   -0.8660     },
+    {   -0.5000     ,   0.0000  ,   0.0000  ,   -0.8660     },
+    {   -0.4330     ,   -0.2500     ,   0.4330  ,   -0.7500     },
+    {   -0.2500     ,   -0.4330     ,   0.7500  ,   -0.4330     },
+    {   0.0000  ,   -0.5000     ,   0.8660  ,   0.0000  },
+    {   0.2500  ,   -0.4330     ,   -0.7500     ,   -0.4330     },
+    {   0.4330  ,   -0.2500     ,   -0.4330     ,   -0.7500     },
+    },                              
+},                                  
+
+{                                   
+    {                               
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    },                              
+                                    
+                                    
+                                    
+                                    
+    {                               
+    {   0.7071  ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   0.2588  ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.2588     ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.7071     ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   -0.9239     ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   -0.3827     ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.3827  ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.9239  ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   1.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.8660  ,   0.5000  ,   0.0000  ,   0.0000  },
+    {   0.5000  ,   0.8660  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   1.0000  ,   0.0000  ,   0.0000  },
+    {   -0.5000     ,   0.8660  ,   0.0000  ,   0.0000  },
+    {   -0.8660     ,   0.5000  ,   0.0000  ,   0.0000  },
+    {   -1.0000     ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   -0.8660     ,   -0.5000     ,   0.0000  ,   0.0000  },
+    {   -0.5000     ,   -0.8660     ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   -1.0000     ,   0.0000  ,   0.0000  },
+    {   0.5000  ,   -0.8660     ,   0.0000  ,   0.0000  },
+    {   0.8660  ,   -0.5000     ,   0.0000  ,   0.0000  },
+    },                              
+                                    
+                                    
+                                    
+                                    
+    {                               
+    {   0.7071  ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   0.2588  ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.2588     ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.7071     ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   -0.9239     ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   -0.3827     ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.3827  ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.9239  ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   -1.0000     },
+    {   0.0000  ,   0.0000  ,   0.5000  ,   -0.8660     },
+    {   0.0000  ,   0.0000  ,   0.8660  ,   -0.5000     },
+    {   0.0000  ,   1.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   -0.8660     ,   -0.5000     },
+    {   0.0000  ,   0.0000  ,   -0.5000     ,   -0.8660     },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   -1.0000     },
+    {   0.0000  ,   0.0000  ,   0.5000  ,   -0.8660     },
+    {   0.0000  ,   0.0000  ,   0.8660  ,   -0.5000     },
+    {   0.0000  ,   -0.7071     ,   0.7071  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   -0.8660     ,   -0.5000     },
+    {   0.0000  ,   0.0000  ,   -0.5000     ,   -0.8660     },
+    },                              
+                                    
+                                    
+                                    
+                                    
+    {                               
+    {   0.7071  ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   0.2588  ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.2588     ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.7071     ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   -0.9239     ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   -0.3827     ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.3827  ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.9239  ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   -1.0000     },
+    {   0.0000  ,   0.0000  ,   0.5000  ,   -0.8660     },
+    {   0.0000  ,   0.0000  ,   0.8660  ,   -0.5000     },
+    {   0.0000  ,   1.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   -0.8660     ,   -0.5000     },
+    {   0.0000  ,   0.0000  ,   -0.5000     ,   -0.8660     },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   -1.0000     },
+    {   0.0000  ,   0.0000  ,   0.5000  ,   -0.8660     },
+    {   0.0000  ,   0.0000  ,   0.8660  ,   -0.5000     },
+    {   0.0000  ,   -0.7071     ,   0.7071  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   -0.8660     ,   -0.5000     },
+    {   0.0000  ,   0.0000  ,   -0.5000     ,   -0.8660     },
+    },                              
+},                                  
+                                    
+                                    
+                                    
+                                    
+{                                   
+    {                               
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    },                              
+                                    
+                                    
+                                    
+                                    
+    {                               
+    {   0.7071  ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   0.2588  ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.2588     ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.7071     ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   -0.9239     ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   -0.3827     ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.3827  ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.9239  ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   1.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.8660  ,   0.5000  ,   0.0000  ,   0.0000  },
+    {   0.5000  ,   0.8660  ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   1.0000  ,   0.0000  ,   0.0000  },
+    {   -0.5000     ,   0.8660  ,   0.0000  ,   0.0000  },
+    {   -0.8660     ,   0.5000  ,   0.0000  ,   0.0000  },
+    {   -1.0000     ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   -0.8660     ,   -0.5000     ,   0.0000  ,   0.0000  },
+    {   -0.5000     ,   -0.8660     ,   0.0000  ,   0.0000  },
+    {   0.0000  ,   -1.0000     ,   0.0000  ,   0.0000  },
+    {   0.5000  ,   -0.8660     ,   0.0000  ,   0.0000  },
+    {   0.8660  ,   -0.5000     ,   0.0000  ,   0.0000  },
+    },                              
+                                    
+                                    
+                                    
+                                    
+    {                               
+    {   0.7071  ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   0.2588  ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.2588     ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.7071     ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   -0.9239     ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   -0.3827     ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.3827  ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.9239  ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   1.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.7500  ,   0.4330  ,   0.2500  ,   -0.4330     },
+    {   0.2500  ,   0.4330  ,   0.7500  ,   -0.4330     },
+    {   0.0000  ,   1.0000  ,   0.0000  ,   0.0000  },
+    {   -0.2500     ,   0.4330  ,   -0.7500     ,   -0.4330     },
+    {   -0.7500     ,   0.4330  ,   -0.2500     ,   -0.4330     },
+    {   -1.0000     ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   -0.7500     ,   -0.4330     ,   -0.2500     ,   0.4330  },
+    {   -0.2500     ,   -0.4330     ,   -0.7500     ,   0.4330  },
+    {   0.0000  ,   0.0000  ,   1.0000  ,   0.0000  },
+    {   0.2500  ,   -0.4330     ,   0.7500  ,   0.4330  },
+    {   0.7500  ,   -0.4330     ,   0.2500  ,   0.4330  },
+    },                              
+                                    
+                                    
+                                    
+                                    
+    {                               
+    {   0.7071  ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   0.2588  ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.2588     ,   0.9659  ,   0.0000  ,   0.0000  },
+    {   -0.7071     ,   0.7071  ,   0.0000  ,   0.0000  },
+    {   -0.9239     ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   -0.3827     ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.3827  ,   -0.9239     ,   0.0000  ,   0.0000  },
+    {   0.9239  ,   -0.3827     ,   0.0000  ,   0.0000  },
+    {   1.0000  ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   0.7500  ,   0.4330  ,   0.2500  ,   -0.4330     },
+    {   0.2500  ,   0.4330  ,   0.7500  ,   -0.4330     },
+    {   0.0000  ,   1.0000  ,   0.0000  ,   0.0000  },
+    {   -0.2500     ,   0.4330  ,   -0.7500     ,   -0.4330     },
+    {   -0.7500     ,   0.4330  ,   -0.2500     ,   -0.4330     },
+    {   -1.0000     ,   0.0000  ,   0.0000  ,   0.0000  },
+    {   -0.7500     ,   -0.4330     ,   -0.2500     ,   0.4330  },
+    {   -0.2500     ,   -0.4330     ,   -0.7500     ,   0.4330  },
+    {   0.0000  ,   0.0000  ,   1.0000  ,   0.0000  },
+    {   0.2500  ,   -0.4330     ,   0.7500  ,   0.4330  },
+    {   0.7500  ,   -0.4330     ,   0.2500  ,   0.4330  },
+    },                              
+},                                  
+                          
+       
+
+};
+
+
+/*
+const double static ir_move_val_old[4][20][2]={
+{               
+{   0.0000  ,   0.0000  },
+{   0.0000  ,   0.0000  },
+{   0.0000  ,   0.0000  },
+{   0.0000  ,   0.0000  },
+{   0.0000  ,   0.0000  },
+{   0.0000  ,   0.0000  },
+{   0.0000  ,   0.0000  },
+{   0.0000  ,   0.0000  },
+{   0.0000  ,   0.0000  },
+{   0.0000  ,   0.0000  },
+{   0.0000  ,   0.0000  },
+{   0.0000  ,   0.0000  },
+{   0.0000  ,   0.0000  },
+{   0.0000  ,   0.0000  },
+{   0.0000  ,   0.0000  },
+{   0.0000  ,   0.0000  },
+{   0.0000  ,   0.0000  },
+{   0.0000  ,   0.0000  },
+{   0.0000  ,   0.0000  },
+{   0.0000  ,   0.0000  },
+},              
+                
+                
+{               
+{   0.7071  ,   0.7071  },
+{   0.2588  ,   0.9659  },
+{   -0.2588     ,   0.9659  },
+{   -0.7071     ,   0.7071  },
+{   -0.0093     ,   -0.7615     },
+{   0.0093  ,   -0.7615     },
+{   -0.0093     ,   -0.7615     },
+{   0.0093  ,   -0.7615     },
+{   0.2000  ,   -0.8000     },
+{   0.5732  ,   -0.5928     },
+{   0.5000  ,   0.8660  },
+{   0.0000  ,   1.0000  },
+{   -0.5000     ,   0.8660  },
+{   -0.5732     ,   -0.5928     },
+{   -0.2000     ,   -0.8000     },
+{   0.0902  ,   -0.7562     },
+{   0.4562  ,   -0.6098     },
+{   1.0000  ,   0.0000  },
+{   -0.4562     ,   -0.6098     },
+{   -0.0902     ,   -0.7562     },
+},              
+                
+                
+{               
+{   0.7071  ,   0.7071  },
+{   0.2588  ,   0.9659  },
+{   -0.2588     ,   0.9659  },
+{   -0.7071     ,   0.7071  },
+{   -0.0093     ,   -0.7615     },
+{   0.0093  ,   -0.7615     },
+{   -0.0093     ,   -0.7615     },
+{   0.0093  ,   -0.7615     },
+{   0.2000  ,   -0.8000     },
+{   0.5732  ,   -0.5928     },
+{   0.5000  ,   0.8660  },
+{   0.0000  ,   1.0000  },
+{   -0.5000     ,   0.8660  },
+{   -0.5732     ,   -0.5928     },
+{   -0.2000     ,   -0.8000     },
+{   0.0902  ,   -0.7562     },
+{   0.4562  ,   -0.6098     },
+{   1.0000  ,   0.0000  },
+{   -0.4562     ,   -0.6098     },
+{   -0.0902     ,   -0.7562     },
+},              
+                
+                
+{               
+{   0.7071  ,   0.7071  },
+{   0.2588  ,   0.9659  },
+{   -0.2588     ,   0.9659  },
+{   -0.7071     ,   0.7071  },
+{   -0.0093     ,   -0.7615     },
+{   0.0093  ,   -0.7615     },
+{   -0.0093     ,   -0.7615     },
+{   0.0093  ,   -0.7615     },
+{   0.2000  ,   -0.8000     },
+{   0.5732  ,   -0.5928     },
+{   0.5000  ,   0.8660  },
+{   0.0000  ,   1.0000  },
+{   -0.5000     ,   0.8660  },
+{   -0.5732     ,   -0.5928     },
+{   -0.2000     ,   -0.8000     },
+{   0.0902  ,   -0.7562     },
+{   0.4562  ,   -0.6098     },
+{   1.0000  ,   0.0000  },
+{   -0.4562     ,   -0.6098     },
+{   -0.0902     ,   -0.7562     },
+},              
+
+
+};
+*/
+#endif /*_IR_CONFIG_H_*/
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/setting/LineConfig.h	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,18 @@
+#ifndef _LINE_CONFIG_H_
+#define _LINE_CONFIG_H_
+//0...x, 1...y
+
+//const double static LineDecline[5] = {1, .75, .5, .375, 0};
+const double static LineDecline[5] = {1, .75, .50, 0, 0};
+const uint8_t static LineDecrease[5] = {30, 20, 20, 20, 0};//ping/1/2/3
+
+//const uint8_t static WhiteToWall[2] = {30, 30};
+const uint8_t static WhiteToWall[2] = {33, 33};
+const uint8_t static WhiteToWallPlus[2] = {35, 40};//{33, 36};
+//const uint8_t static OutToWall[2] = {16, 20};
+const uint8_t static OutToWall[2] = {25, 30};
+
+const uint8_t static GoalEdgeToWall[2] = {60, 60};
+const uint8_t static SelfToEmpty[2] = {100, 45};
+
+#endif /*_LINE_CONFIG_H_*/
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/setting/PinConfig.h	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,65 @@
+#ifndef _PIN_CONFIG_H_
+#define _PIN_CONFIG_H_
+
+//pc(Computer)
+static PinName const monitor_tx = SERIAL_TX;
+static PinName const monitor_rx = SERIAL_RX;
+//led(main)
+static PinName const led1 = PC_12;
+static PinName const led2 = PC_10;
+static PinName const led3 = PC_11;
+static PinName const led4 = PD_2;
+//write(main)
+static PinName const stlinkTMS = PA_13;
+static PinName const stlinkTCK = PA_14;
+static PinName const stlinkRX = D1;
+static PinName const stlinkNRST = NC;
+static PinName const stlink3V3 = NC;
+//line(bottom)
+static PinName const lineA1 = PB_7;
+static PinName const lineB1 = PC_13;
+static PinName const lineC1 = PC_3;
+static PinName const lineA2 = A0;
+static PinName const lineB2 = A1;
+static PinName const lineC2 = A2;
+static PinName const lineInA = A3;
+static PinName const lineInB = A4;
+static PinName const lineInC = A5;
+//ballcheck(bottom)
+static PinName const ballcheck = PC_2;
+//debug_switch(debug_board)
+static PinName const selectsw1 = PC_8;
+static PinName const selectsw2 = PC_9;
+static PinName const debugsw1 = D15;
+static PinName const debugsw2 = D14;
+//motor(main)
+static PinName const motor_rx = PA_12;
+static PinName const motor_tx = PA_11;
+//spi(main)
+static PinName const SPI_slck = D13;
+static PinName const SPI_miso = D12;
+static PinName const SPI_mosi = D11;
+static PinName const SPI_ss_sd = PB_12;
+static PinName const SPI_ss_sonic = D10;
+static PinName const SPI_ss_color = D9;
+static PinName const SPI_ss_ir = PB_1;
+//bluetooth(debug_board)
+static PinName const blue_txd = D2;
+static PinName const blue_rxd = D8;
+static PinName const blue_reset = PB_2;
+//lcd(debug_board)
+static PinName const lcd_sda = D5;
+static PinName const lcd_scl = D7;
+//gyro(debug_board)
+static PinName const sens_sda = D3;
+static PinName const sens_scl = D6;
+static PinName const sens_interrupt = D0;
+//mouse(bottom)
+static PinName const mouse_mosi = PB_15;
+static PinName const mouse_miso = PB_14;
+static PinName const mouse_slck = PB_13;
+static PinName const mouse_ss = D4;
+//solenoid(bottom)
+static PinName const solenoid = PC_4;
+
+#endif /*_PIN_CONFIG_H_*/
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/setting/def.h	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,317 @@
+#ifndef _DEF_H_
+#define _DEF_H_
+
+//red or green
+#define RED_CAT//jj
+//#define GREEN_CAT//lily
+
+//BT(BlueTooth)
+#define DATA_NUM 8+2//2byte→KEYCODE(拝啓)とCHECKCODE(敬具) 8byte→やりとりするデータ
+#define TX_KEYCODE 0xAA//あちらのKEYCODE
+#define RX_KEYCODE 0xAA//こちらのKEYCODE
+#define KEY 0//KEYCODEは配列の最初
+#define CHECK DATA_NUM-1//CHECKCODEは配列の最後
+
+
+//Switch 入力値
+#define NONE    0
+#define UP      1
+#define DOWN    2
+#define RIGHT   3
+#define LEFT    4
+
+//Lcd 設定値
+#define LCD_COLUMN_NUM 0x11
+#define BUFSIZE 7
+#define STATE_NUM_X 0x08
+#define STATE_NUM_Y 0x10
+
+#define JUMP_TAG_MAX 0xFFFF
+//tag
+#define ZERO_FUNCTION       0
+#define START               1
+#define GET_IR              2
+#define GET_SNS0            3
+#define GET_PID_VALUE       4
+#define CALIBRATION_ENTER   5
+#define CALIBRATION_EXIT    6
+#define FRONT_RESET         7
+#define SET_POWER1          8
+#define SET_POWER2          9
+#define SOFT_RESET          10
+#define SET_STRATEGY1       11
+#define SET_STRATEGY2       12
+#define SET_STRATEGY3       13
+#define SET_STRATEGY4       14
+#define START2              15
+
+#define SET_POWER_DOWN      16
+#define SET_POWER_UP        17
+#define SET_STRATEGY_DOWN   18
+#define SET_STRATEGY_UP     19
+
+#define DRIVE_KICKER 20
+#define DRIVE_DRIBBLER_AND_KICKER 21
+
+#define CALIBRATION_TURN 22
+#define RW_PID 23
+
+#define TURN_AND_START 24
+#define CALIBRATION_ENTER_OR_EXIT 25
+
+typedef struct {//for command
+    char LcdStr[STATE_NUM_X][BUFSIZE];
+    uint8_t str_num;
+    uint8_t (*CommandFunction)(uint8_t x);
+    uint16_t tag_num;
+} CommandItem;
+
+
+//tag
+#define MODE_ATTACK0 0
+#define MODE_ATTACK1 1
+#define MODE_ATTACK2 2
+#define MODE_ATTACK3 3
+#define MODE_ATTACK4 4
+#define MODE_ATTACK5 5
+
+#define MODE_DEBUG0 6
+#define MODE_DEBUG1 7
+#define MODE_DEBUG2 8
+#define MODE_DEBUG3 9
+#define MODE_DEBUG4 10
+#define MODE_DEBUG5 11
+
+typedef struct {//for active
+    char LcdStr[LCD_COLUMN_NUM];
+    void (*ActiveFunction)(void);
+    uint16_t tag_num;
+} ActiveItem;
+
+//繰り返し割り込み
+#define DUTY_NUM 1
+
+#define DUTY_SW     0
+#define DUTY_GYRO   1
+#define DUTY_PING   2
+#define DUTY_COLOR  3
+#define DUTY_MOUSE  4
+
+/*PID処理*/
+#define RATE    0.052//52
+#define PID_BIAS    0.0//1.0
+#define REFERENCE   180.0
+#define MINIMUM     0.0
+#define MAXIMUM     359.9
+#define P_GAIN  1.3//1.25//0.8    //0.78   
+#define I_GAIN  0.0     //0.0
+#define D_GAIN  0.01//0.01  //0.009
+#define OUT_LIMIT   30.0
+#define MAX_POW     100
+#define MIN_POW     -100
+#define PID_CYCLE   0.05   //s
+
+#define PID_OUT_MIN 5
+
+//hmc
+#define HMC_RUN 1
+#define HMC_RST 0
+
+//ir 
+//ir_pow_old
+#define IR_X 0
+#define IR_Y 1
+//ir_pow
+#define IR_X_DIR    0
+#define IR_Y_DIR    1
+#define IR_X_TURN   2
+#define IR_Y_TURN   3
+
+#define IR_SHORT 0
+#define IR_LONG 1
+
+#define X_AXIS 0
+#define Y_AXIS 1
+
+
+#define DIS_0 0x0//low_value
+#define DIS_1 0x1
+#define DIS_2 0x2
+#define DIS_3 0x3
+#define DIS_4 0x4
+#define DIS_5 0x5
+#define DIS_6 0x6
+#define DIS_7 0x7//high_value
+
+//ping
+#define L_PING 1
+#define R_PING 0
+#define F_PING 2
+#define B_PING 3
+
+#define X_PING 0
+#define Y_PING 1
+
+//0,1...main
+//2,3...debug board
+
+//line
+#define LINE_EMPTY 0xFF
+
+#define A_SPOT 0
+#define B_SPOT 1
+#define C_SPOT 2
+#define AB_SPOT 3
+
+#define LINE_RF 5
+#define LINE_DELAY_1 0.5//1.0
+#define LINE_DELAY_2 0.125//0.5//.25
+#define LINE_DELAY_3 0.125//.25
+
+#define LINE_REPEAT 1
+
+#define L_LINE 1
+#define R_LINE 0
+#define F_LINE 2
+#define B_LINE 3
+
+#define X_LINE 0
+#define Y_LINE 1
+
+#define LINE_INSIDE 0
+#define LINE_OUTSIDE 1
+
+//hard error
+
+#ifdef RED_CAT
+#define LINE_FIX 0x0
+#define LINE_FREE 0x7
+
+//右後左ド
+#define MD_1CH (1)
+#define MD_2CH (1)
+#define MD_3CH (1)
+#define MD_4CH (-1)
+#endif /*RED_CAT*/
+
+#ifdef GREEN_CAT
+#define LINE_FIX 0x7
+#define LINE_FREE 0x0
+
+//右後左ド
+#define MD_1CH (1)
+#define MD_2CH (1)
+#define MD_3CH (-1)
+#define MD_4CH (-1)
+#endif /*GREEN_CAT*/
+
+
+//思考パターン
+#define STRATEGY_NUM 12
+
+//計算
+#define ROUND(x) ((x > 0) ? (x + 0.5) : (x - 0.5))//x...整数
+#define PI  3.14159265358979323846
+#define DEG2RAD(deg)  (PI*(deg)/180.0)
+#define RAD2DEG(rad)  (180.0(rad)/PI)
+
+//データ
+typedef struct {
+    //cmps&pid
+    double cmps, CmpsInitialValue, CmpsInitialValue2, CmpsInitialValue0, CmpsDiff;//0<x<360
+    int16_t FrontDeg, AtkDeg, HoldDeg, GoalDeg;
+    //正...右回転
+    //負...左回転
+    double InputPID;//<<gyrosensor
+    int16_t OutputPID;//>>motor
+} CompassVal;
+typedef struct {
+    //ping
+    uint8_t ping[4];
+    //line
+    uint8_t lineSpot[3];
+    uint8_t lnFlag[3];
+    uint8_t NonWall[4];
+    uint8_t NearWall[2];
+    uint8_t ReturnDir[2];
+    
+    uint8_t lnHold;
+    uint8_t lnRaw;
+    uint8_t lnRawMemory[3];
+    uint8_t lnRawOrder[3];//first_second_third
+    uint8_t lnRawOrderLog1[3];//first_second_third
+    uint8_t lnRawOrderLog2[3];//first_second_third
+    uint8_t lnRawRise[3];
+    uint8_t lnRawReturn;
+    uint8_t lnRawLastRise;
+    uint8_t lnStop[2];
+    //uint8_t lnStay[2];
+    uint8_t lnStay[2];
+    uint8_t lnStayNow[2];
+    uint8_t lnCorner[4];
+    uint8_t lnRepeat;
+    uint8_t FieldSpot;//0...inside,1...outside
+    uint8_t lnOrder[3];//first_second_third
+    
+    uint8_t lnState;
+    /*uint8_t LineFlag[3];
+    uint8_t LinePriority[3];
+    uint8_t LineBind[3];*/
+    //ir(spi)
+    uint8_t irKey;//2bit
+    uint8_t irValPhase[2];//3*2bit
+    uint8_t irDif[2];//3bit
+    uint8_t irPosition;//5bit
+    
+    uint8_t irSpot[2];//4*2bit//old
+    //ir(playing)
+    uint8_t irNotice;
+    uint8_t irLastNotice;
+    uint8_t irStayNotice;
+    uint8_t irLastPosition;
+    //ball
+    uint8_t ball;
+} SensorVal;
+typedef struct {
+    //system,flag
+    uint8_t strategy;
+    uint16_t jump_flag;//0<=x<=JUMP_TAG_NUM
+    uint8_t stopflag;
+    uint8_t KickOffFlag;
+    uint8_t DribbleFlag;
+    uint8_t KickStopFlag;
+    uint8_t TurnStopFlag;
+    
+    uint8_t BallHoldJudgeFlag;
+    uint8_t BallHoldFlag;
+    
+    uint8_t BackHomeFlag;
+    uint8_t HomeStayFlag[2];
+    uint8_t TurnStartFlag;
+    uint8_t MotorFlag;
+    uint8_t InfoFlag;
+    //uint8_t PidFlag;
+    uint8_t DefenceFlag;
+    //blind//on...1/off...0
+    uint8_t IrBlind;
+    uint8_t LineBlind;
+    uint8_t PingBlind;
+    
+    uint8_t DriBlind;
+    uint8_t DriMotorBlind;
+    uint8_t TurnAtkBlind;
+    uint8_t TurnDriBlind;
+    uint8_t TurnHoldBlind;
+    uint8_t KickBlind;
+    uint8_t HomeBlind;
+    
+    //motor 
+    uint8_t pow_num;
+    uint8_t s_pow;
+    uint8_t m_pow;
+    uint8_t l_pow;
+    uint8_t dri_pow;
+    uint8_t ir_pow_table;
+} SystemVal;
+
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/setting/extern.h	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,114 @@
+#ifndef _EXTERN_H_
+#define _EXTERN_H_
+
+#include "def.h"
+
+/*追加ライブラリ*/
+#include <sstream>
+#include "math.h"
+#include "AQM1602.h"
+#include "HMC6352.h"
+#include "PID.h"
+
+#include "adns_9800.h"
+#include "txrx.h"
+#include "switch.h"
+#include "wordString2.h"
+#include "IrConfig.h"
+#include "LineConfig.h"
+
+#include "setup.h"
+#include "command.h"
+#include "command_functions.h"
+#include "active.h"
+#include "input.h"
+#include "output.h"
+#include "LineProcess.h"
+#include "strategy.h"
+#include "strategy2.h"
+#include "old_strategy.h"
+
+#include "PinConfig.h"
+#include "CommandConfig.h"
+#include "ActiveConfig.h"
+#include "MathTable.h"
+/*クラス*/
+
+//pc(Computer)
+extern RawSerial pc;
+//led(main)
+//extern DigitalOut LED[4];
+extern BusOut LED;
+//line(bottom)
+extern BusOut LineKeeper;
+extern BusIn LineRaw;
+extern BusIn LineHold;
+extern InterruptIn Line[3];
+extern InterruptIn LineHolding[3];
+//ballcheck(bottom)
+extern InterruptIn BallChecker;
+extern AnalogIn BallCheckerA;
+//debug_switch(debug_board)
+extern DigitalIn Sw[4];
+//motor(main)
+extern Serial motor;
+//spi(main)
+extern SPI spi;
+extern DigitalOut spi_ss[4];
+//bluetooth(debug_board)
+extern RawSerial RN42;
+extern DigitalOut hmc_reset;
+//lcd(debug_board)
+extern AQM1602 Lcd;
+//cmps
+extern HMC6352 hmc;
+//mouse(bottom)
+extern adns_9800 mouse_sensor;
+//solenoid(bottom)
+extern DigitalOut kicker;
+
+//Serial for motors
+extern int speed[4];
+extern string StringFIN;
+//PID
+extern PID pid;
+extern Ticker pidupdate;
+//for Serial
+extern volatile uint8_t INdata[DATA_NUM], EXdata[DATA_NUM];
+//for DataSet
+//extern Record data;
+//NewStruct
+extern CompassVal cmps_set;
+extern SensorVal data;
+extern SystemVal sys;
+//for transition
+extern Ticker Sw_ticker;
+extern Timeout button;
+extern bool state[4];
+extern uint8_t statesum, last_statesum;
+// for Time
+extern Ticker Motor_ticker;
+//extern Ticker Line_ticker;
+extern Ticker Info_ticker;
+//extern Ticker Hmc_ticker;
+
+//extern Timeout Line_timeout[3];
+extern Timeout Line_reset;
+
+extern Timeout Solenoid_timeout;
+extern Timeout Kick_stop;
+
+extern Timeout Turn_timeout;
+extern Timeout Turn_stop;
+
+extern Timeout Ball_judge;
+
+//extern Timeout Kick_now;
+//extern Timeout Front_now;
+//extern Timeout Line_home;
+
+extern Ticker Duty[DUTY_NUM];
+extern Timeout Stp;
+extern double dutycycle[DUTY_NUM];
+
+#endif /*_EXTERN_H_*/
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/setting/main.h	Tue Jun 14 07:22:22 2016 +0000
@@ -0,0 +1,85 @@
+#ifndef _MAIN_H_
+#define _MAIN_H_
+
+#include "def.h"
+
+//pc(Computer)
+RawSerial pc(monitor_tx, monitor_rx);
+//led(main)
+//DigitalOut LED[4]={led1, led2, led3, led4};
+BusOut LED(led1, led2, led3, led4);
+//line(bottom)
+BusOut LineKeeper(lineInA, lineInB, lineInC);
+BusIn LineRaw(lineA2, lineB2, lineC2);
+BusIn LineHold(lineA1, lineB1, lineC1);
+InterruptIn Line[3]={lineA2, lineB2, lineC2};
+InterruptIn LineHolding[3]={lineA1, lineB1, lineC1};
+//ballcheck(bottom)
+InterruptIn BallChecker(ballcheck);
+AnalogIn BallCheckerA(ballcheck);
+//debug_switch(debug_board)
+DigitalIn Sw[4] = {selectsw1, selectsw2, debugsw1, debugsw2};
+//motor(main)
+Serial motor(motor_tx, motor_rx);
+//spi(main)
+SPI spi(SPI_mosi, SPI_miso, SPI_slck);
+DigitalOut spi_ss[4]={SPI_ss_sd, SPI_ss_sonic, SPI_ss_color, SPI_ss_ir};
+//bluetooth(debug_board)
+RawSerial RN42(blue_rxd, blue_txd);
+DigitalOut hmc_reset(blue_reset);
+//lcd(debug_board)
+AQM1602 Lcd(lcd_sda, lcd_scl);
+//cmps(debug_board)
+HMC6352 hmc(sens_sda, sens_scl);
+//mouse(bottom)
+adns_9800 mouse_sensor(mouse_mosi, mouse_miso, mouse_slck, mouse_ss);
+//solenoid(bottom)
+DigitalOut kicker(solenoid);
+
+//Serial for motors
+int speed[4]={0};
+string StringFIN;
+//PID
+PID pid(P_GAIN,I_GAIN,D_GAIN, RATE);
+//Ticker pidupdate;
+//for Serial
+volatile uint8_t INdata[DATA_NUM]={0}, EXdata[DATA_NUM]={0};
+//for DataSet
+//Record data;
+//NewStruct
+CompassVal cmps_set;
+SensorVal data;
+SystemVal sys;
+//for transition
+Ticker Sw_ticker;
+Timeout button;
+bool state[4]={0,0,0,0};
+uint8_t statesum=0, last_statesum=0;
+// for Time
+Ticker Motor_ticker;
+//Ticker Line_ticker;
+Ticker Info_ticker;
+//Ticker Hmc_ticker;
+
+//Timeout Line_timeout[3];
+Timeout Line_reset;
+
+Timeout Solenoid_timeout;
+Timeout Kick_stop;
+
+Timeout Turn_timeout;
+Timeout Turn_stop;
+
+Timeout Ball_judge;
+
+//Timeout Kick_now;
+//Timeout Front_now;
+//Timeout Line_home;
+
+Ticker Duty[DUTY_NUM];
+Timeout Stp;
+double dutycycle[DUTY_NUM] ={//[s]
+    0.2
+};
+
+#endif /*_MAIN_H_*/
\ No newline at end of file