common_edc_ethercat_protocol.h
Go to the documentation of this file.
00001 //
00002 // © 2010 Shadow Robot Company Limited.
00003 //
00004 // FileName:        common_edc_ethercat_protocol.h
00005 // Dependencies:
00006 // Processor:       PIC32
00007 // Compiler:        MPLAB® C32
00008 //
00009 //  +------------------------------------------------------------------------+
00010 //  | This file is part of The Shadow Robot PIC32 firmware code base.        |
00011 //  |                                                                        |
00012 //  | It is free software: you can redistribute it and/or modify             |
00013 //  | it under the terms of the GNU General Public License as published by   |
00014 //  | the Free Software Foundation, either version 3 of the License, or      |
00015 //  | (at your option) any later version.                                    |
00016 //  |                                                                        |
00017 //  | It is distributed in the hope that it will be useful,                  |
00018 //  | but WITHOUT ANY WARRANTY; without even the implied warranty of         |
00019 //  | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the          |
00020 //  | GNU General Public License for more details.                           |
00021 //  |                                                                        |
00022 //  | You should have received a copy of the GNU General Public License      |
00023 //  | along with this code repository. The text of the license can be found  |
00024 //  | in Pic32/License/gpl.txt. If not, see <http://www.gnu.org/licenses/>.  |
00025 //  +------------------------------------------------------------------------+
00026 //
00027 //
00028 //
00029 //  Doxygen
00030 //  -------
00031 //
00042 //
00043 
00044 #ifndef COMMON_EDC_ETHERCAT_PROTOCOL_H_INCLUDED
00045 #define COMMON_EDC_ETHERCAT_PROTOCOL_H_INCLUDED
00046 
00048 typedef enum
00049 {
00050     EDC_COMMAND_INVALID = 0,                                    
00051     EDC_COMMAND_SENSOR_DATA,                                    
00052     EDC_COMMAND_SENSOR_CHANNEL_NUMBERS,                         
00053     EDC_COMMAND_SENSOR_ADC_CHANNEL_CS,                          
00054     EDC_COMMAND_CAN_DIRECT_MODE                                 
00055 
00056     //EDC_COMMAND_TEST_RESULTS,                                   //!< Might be used in the future for running automated tests inside the firmware.
00057 }EDC_COMMAND;
00058 
00059 
00060 
00061 #ifndef NO_STRINGS                                                                                                                              // The PIC compiler doesn't deal well with strings.
00062 
00063     static const char* slow_data_types[17] = {  "Invalid",                                  // 0x0000
00064                                                 "SVN revision",                             // 0x0001
00065                                                 "SVN revision on server at build time",     // 0x0002
00066 
00067                                                 "Modified from SVN revision",               // 0x0003
00068                                                 "Serial number low",                        // 0x0004
00069                                                 "Serial number high",                       // 0x0005
00070                                                 "Motor gear ratio",                         // 0x0006
00071                                                 "Assembly date year",                       // 0x0007
00072                                                 "Assembly date month, day",                 // 0x0008
00073 
00074                                                 "Controller F",                             // 0x0009
00075                                                 "Controller P",                             // 0x000A
00076                                                 "Controller I",                             // 0x000B
00077                                                 "Controller Imax",                          // 0x000D
00078                                                 "Controller D",                             // 0x000E
00079                                                 "Controller deadband and sign",             // 0x000F
00080 
00081                                                 "Controller loop frequency Hz"              // 0x0010
00082                                                };
00083 
00084 #endif
00085 
00086 
00089 typedef enum
00090 {
00091     DIRECTION_DATA_REQUEST              = 0x0,                  
00092     DIRECTION_TO_MOTOR                  = 0x1,                  
00093     DIRECTION_FROM_MOTOR                = 0x2,                  
00094     DIRECTION_BOOTLOADER                = 0x3                   
00095 }MESSAGE_DIRECTION;
00096 
00097 
00098 #define MESSAGE_ID_DIRECTION_BITS       0b11000000000           //!< Bit mask specifying which bits of the CAN message ID are used for the MESSAGE_DIRECTION
00099 #define MESSAGE_ID_MOTOR_ID_BITS        0b00111100000           //!< Bit mask specifying which bits of the CAN message ID are used for the motor ID [0..9]
00100 #define MESSAGE_ID_ACK_BIT              0b00000010000           //!< Bit mask specifying which bits of the CAN message ID are used for the ACK bit (only for bootloading)
00101 #define MESSAGE_ID_TYPE_BITS            0b00000001111           //!< Bit mask specifying which bits of the CAN message ID are used for the TO_MOTOR_DATA_TYPE or FROM_MOTOR_DATA_TYPE
00102                                                                 //                                               or for the TO_MUSCLE_DATA_TYPE or FROM_MUSCLE_DATA_TYPE
00103 
00104 #define MESSAGE_ID_DIRECTION_SHIFT_POS  9                       //!< Bit number of lowest bit of MESSAGE_ID_DIRECTION_BITS
00105 
00106 
00107 //Check this against the SENSORS_NUM_0320 and SENSORS_NUM_0220
00108 #define SENSORS_NUM_0X20  ((int)36)                             //!< The number of sensors in the robot.
00109 
00110 
00111 //Check this against the JOINTS_NUM_0320 and JOINTS_NUM_0220
00112 #define JOINTS_NUM_0X20   ((int)28)                             //!< The number of joints in the hand
00113 
00114 
00115 
00116 
00117 #ifndef NO_STRINGS                                              //   The PIC compiler doesn't deal well with strings.
00118 
00119     static const char* joint_names[JOINTS_NUM_0X20] = {  "FFJ0", "FFJ1", "FFJ2", "FFJ3", "FFJ4",
00120                                                          "MFJ0", "MFJ1", "MFJ2", "MFJ3", "MFJ4",
00121                                                          "RFJ0", "RFJ1", "RFJ2", "RFJ3", "RFJ4",
00122                                                          "LFJ0", "LFJ1", "LFJ2", "LFJ3", "LFJ4","LFJ5",
00123                                                          "THJ1", "THJ2", "THJ3", "THJ4", "THJ5",
00124                                                          "WRJ1", "WRJ2"
00125                                                       };
00126 
00127 
00129 
00130     static const char* sensor_names[SENSORS_NUM_0X20] = {"FFJ1",  "FFJ2",  "FFJ3", "FFJ4",                           //  [00..03] ADC readings from First finger
00131                                                          "MFJ1",  "MFJ2",  "MFJ3", "MFJ4",                       //  [04..07] ADC readings from Middle finger
00132                                                          "RFJ1",  "RFJ2",  "RFJ3", "RFJ4",                       //  [08..11] ADC readings from Ring finger
00133                                                          "LFJ1",  "LFJ2",  "LFJ3", "LFJ4", "LFJ5",               //  [12..16] ADC readings from Little finger
00134                                                          "THJ1",  "THJ2",  "THJ3", "THJ4", "THJ5A", "THJ5B",     //  [17..22] ADC readings from Thumb
00135                                                          "WRJ1A", "WRJ1B", "WRJ2",                               //  [23..25] ADC readings from Wrist
00136                                                          "ACCX",  "ACCY",  "ACCZ",                               //  [26..28] ADC readings from Accelerometer
00137                                                          "GYRX",  "GYRY",  "GYRZ",                               //  [29..31] ADC readings from Gyroscope
00138                                                          "AN0",   "AN1",   "AN2",  "AN3"                         //  [32..35] ADC readings from auxillary ADC port.
00139                                                        };
00140 #endif
00141 
00142 
00144 typedef enum
00145 {
00146         FFJ1=0, FFJ2,  FFJ3, FFJ4,                      // [ 0...3]
00147         MFJ1,   MFJ2,  MFJ3, MFJ4,                      // [ 4...7]
00148         RFJ1,   RFJ2,  RFJ3, RFJ4,                      // [ 8..11]
00149         LFJ1,   LFJ2,  LFJ3, LFJ4, LFJ5,                // [12..16]
00150     THJ1,   THJ2,  THJ3, THJ4, THJ5A, THJ5B,        // [17..22]
00151     WRJ1A,  WRJ1B, WRJ2,                            // [23..25]
00152 
00153         ACCX, ACCY, ACCZ,                               // [26..28]
00154         GYRX, GYRY, GYRZ,                               // [29..32]
00155 
00156         ANA0, ANA1, ANA2, ANA3,                     // [31..35]
00157     IGNORE                                          // [36]
00158 }SENSOR_NAME_ENUM;
00159 
00160 
00161 
00162 
00163 typedef enum
00164 {
00165       PALM_SVN_VERSION              =  0,
00166     SERVER_SVN_VERSION              =  1
00167 }HARD_CONFIGURATION_INFORMATION;
00168 
00169 
00170 
00171 #define INSERT_CRC_CALCULATION_HERE     crc_i = (int8u) (crc_result&0xff);          \
00172                                         crc_i ^= crc_byte;                          \
00173                                         crc_result >>= 8;                           \
00174                                         if(crc_i & 0x01)        crc_result ^= 0x3096;   \
00175                                         if(crc_i & 0x02)        crc_result ^= 0x612c;   \
00176                                         if(crc_i & 0x04)        crc_result ^= 0xc419;   \
00177                                         if(crc_i & 0x08)        crc_result ^= 0x8832;   \
00178                                         if(crc_i & 0x10)        crc_result ^= 0x1064;   \
00179                                         if(crc_i & 0x20)        crc_result ^= 0x20c8;   \
00180                                         if(crc_i & 0x40)        crc_result ^= 0x4190;   \
00181                                         if(crc_i & 0x80)        crc_result ^= 0x8320;
00182 
00183 
00184 #endif


sr_external_dependencies
Author(s): Ugo Cupcic
autogenerated on Mon Jul 1 2019 20:06:25