0320_palm_edc_ethercat_protocol.h
Go to the documentation of this file.
00001 //
00002 // © 2010 Shadow Robot Company Limited.
00003 //
00004 // FileName:        0320_palm_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 PALM_EDC_0320_ETHERCAT_PROTOCOL_H_INCLUDED
00045 #define PALM_EDC_0320_ETHERCAT_PROTOCOL_H_INCLUDED
00046 
00047 #include "../common/tactile_edc_ethercat_protocol.h"
00048 #include "../common/ethercat_can_bridge_protocol.h"
00049 #include "../common/common_edc_ethercat_protocol.h"
00050 
00051 
00052 #define NUM_MUSCLES                         40
00053 #define NUM_PRESSURE_SENSORS_PER_MESSAGE     5
00054 #define NUM_MUSCLE_DATA_PACKETS              8
00055 
00056 
00057 // ========================================================
00058 // 
00059 //       F R O M    M U S C L E    D A T A    T Y P E
00060 // 
00061 // ========================================================
00062 
00063 
00065 typedef enum
00066 {
00067     MUSCLE_DATA_INVALID                  = 0x0,                  
00068     MUSCLE_DATA_PRESSURE                 = 0x1,                  
00069 
00070     MUSCLE_DATA_CAN_STATS                = 0x2,                  
00071     MUSCLE_DATA_SLOW_MISC                = 0x3                   
00072 }FROM_MUSCLE_DATA_TYPE;
00073 
00074 
00075 
00076 
00077 // ========================================================
00078 // 
00079 //                 S L O W    D A T A
00080 // 
00081 // ========================================================
00082 
00083 
00084 typedef enum
00085 {
00086     MUSCLE_SLOW_DATA_INVALID              = 0x0000,              
00087     MUSCLE_SLOW_DATA_SVN_REVISION         = 0x0001,              
00088     MUSCLE_SLOW_DATA_SVN_SERVER_REVISION  = 0x0002,              
00089 
00090     MUSCLE_SLOW_DATA_SVN_MODIFIED         = 0x0003,              
00091     MUSCLE_SLOW_DATA_SERIAL_NUMBER_LOW    = 0x0004,              
00092     MUSCLE_SLOW_DATA_SERIAL_NUMBER_HIGH   = 0x0005,              
00093     MUSCLE_SLOW_DATA_ASSEMBLY_DATE_YYYY   = 0x0006,              
00094     MUSCLE_SLOW_DATA_ASSEMBLY_DATE_MMDD   = 0x0007,              
00095 
00096 
00097     MUSCLE_SLOW_DATA_LAST                 = 0x0007               
00098 }FROM_MUSCLE_SLOW_DATA_TYPE;
00099 
00100 
00101 
00102 // ========================================================
00103 // 
00104 //                       F L A G S
00105 // 
00106 // ========================================================
00107 
00108 
00109                                                                 // Non serious flags, Just for information. Control still works.
00110                                                                 // -------------------------------------------------------------
00111 
00112 
00113                                                                 // Serious flags cause the valves to be switched off
00114                                                                 // ------------------------------------------------
00115 #define MUSCLE_FLAG_BITS_NO_DEMAND_SEEN              0x0400     //!< Haven't received any demand messages for longer than NO_DEMAND_TIMEOUT_MS. Valves switched off.
00116 
00117 
00118 #define PALM_0300_EDC_SERIOUS_ERROR_FLAGS            (  MOTOR_FLAG_BITS_NO_DEMAND_SEEN )
00119 
00120 #define PALM_0300_EDC_NO_DEMAND_TIMEOUT_MS    20                                                              //!< If a muscle driver doesn't see any Torque or PWM demand values,
00121 
00122 
00123 #ifndef NO_STRINGS                                                                                                                                  // The PIC compiler doesn't deal well with strings.
00124 
00127     static const char* palm_0300_edc_error_flag_names[16] = { "No demand seen for more than 20ms",            // 0x0400
00128                                                             };
00129 #endif
00130 
00131 
00132 
00133 
00134 
00135 // ========================================================
00136 // 
00137 //         T O    M U S C L E    D A T A    T Y P E
00138 // 
00139 // ========================================================
00140 
00145 typedef enum
00146 {
00147     MUSCLE_DEMAND_INVALID                = 0x0,                  
00148     MUSCLE_DEMAND_VALVES                 = 0x1,                  
00149 
00150     MUSCLE_SYSTEM_RESET                  = 0x3                   
00151 }TO_MUSCLE_DATA_TYPE;
00152 
00153 #define MUSCLE_SYSTEM_RESET_KEY             0x5200               //!< | Muscle board ID.
00154 
00155 
00156 
00157 
00158 #define MUSCLE_DEMAND_VALVES_RANGE_MIN     -0x4
00159 #define MUSCLE_DEMAND_VALVES_RANGE_MAX      0x4
00160 
00161 #define DIRECTION_TO_MUSCLE                 0x01
00162 #define DIRECTION_FROM_MUSCLE               0x02
00163 
00164 
00165 #ifndef NO_STRINGS                                                                                                                          // The PIC compiler doesn't deal well with strings.
00166 
00169     static const char* to_muscle_data_type_names[16] = { "INVALID",
00170                                                        "Demand: Valves",
00171                                                        };
00172 #endif
00173 
00174 
00175 
00178 
00179 typedef union
00180 {
00181     struct
00182     {
00183         unsigned int L:4;
00184         unsigned int M:4;
00185         unsigned int H:4;
00186         unsigned int padding:4;
00187     }   nibbles;
00188 
00189     int16u integer;
00190 
00191 } TWELVE_BIT_INT_TO_NIBBLES;
00192 
00193 
00194 typedef union
00195 {
00196     struct 
00197     {
00198         unsigned int pressure0_L:4;
00199         unsigned int pressure0_M:4;
00200         unsigned int pressure0_H:4;
00201 
00202         unsigned int pressure1_L:4; 
00203         unsigned int pressure1_M:4;
00204         unsigned int pressure1_H:4;
00205 
00206         unsigned int pressure2_L:4;
00207         unsigned int pressure2_M:4;
00208         unsigned int pressure2_H:4;
00209 
00210         unsigned int pressure3_L:4;
00211         unsigned int pressure3_M:4;
00212         unsigned int pressure3_H:4;
00213 
00214         unsigned int pressure4_L:4;
00215         unsigned int pressure4_M:4;
00216         unsigned int pressure4_H:4;
00217 
00218         unsigned int padding:4;
00219 
00220     } packed;
00221 
00222     struct
00223     {
00224         int16u      SVN_revision;
00225         int16u      SVN_server;
00226         int16u      SVN_modified;
00227         int16u      nothing;
00228     }slow_0;
00229 
00230     struct
00231     {
00232         int32u      serial_number;
00233         int16u      assembly_date_YYYY;
00234         int8u       assembly_date_MM;
00235         int8u       assembly_date_DD;
00236     }slow_1;
00237 
00238     struct
00239     {
00240         int8u       can_err_tx;
00241         int8u       can_err_rx;
00242         int16u      can_msgs_tx;
00243         int16u      can_msgs_rx;
00244         int8u       nothing[2];
00245     }misc;
00246 
00247     //struct
00248     //{
00249         int8u raw[8];
00250     //} raw;
00251 } MUSCLE_DATA_PACKET;
00252 
00253 
00254 
00255 #define MESSAGE_ID_MUSCLE_DRIVER_ID_SHIFT_POS  5                       //!< Bit number of lowest bit of MESSAGE_ID_MUSCLE_ID_BITS
00256 
00257 
00258 
00259 #define SENSORS_NUM_0320  ((int)36)                             //!< The number of sensors in the robot.
00260 
00261 
00262 #define JOINTS_NUM_0320   ((int)28)                             //!< The number of joints in the hand
00263 
00264 
00265 
00266 
00267 //#if (int)IGNORE > SENSORS_NUM
00268 //    #error Not enough sensors[] in ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_STATUS
00269 //#endif
00270 
00272 typedef struct
00273 {
00274     EDC_COMMAND                 EDC_command;                        
00275 
00276 
00277 
00278 
00279         int16u                                      sensors[SENSORS_NUM_0320+1];
00280 
00281     FROM_MUSCLE_DATA_TYPE       muscle_data_type;                   
00282 
00283 
00284 
00285     int16u                       which_muscle_data_arrived;         
00286 
00287 
00288 
00289     MUSCLE_DATA_PACKET          muscle_data_packet[NUM_MUSCLE_DATA_PACKETS];
00290 
00291 
00292     int32u                      tactile_data_type;
00293     int16u                      tactile_data_valid;                 
00294     TACTILE_SENSOR_STATUS_v1    tactile[5];                         //
00295 
00296     int16u                      idle_time_us;                       
00297 
00298 
00299 } __attribute__((packed)) ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_STATUS;
00300 
00301 
00302 
00304 typedef struct
00305 {
00306     EDC_COMMAND                 EDC_command;                        
00307 
00308     FROM_MUSCLE_DATA_TYPE       from_muscle_data_type;              
00309 
00310     TO_MUSCLE_DATA_TYPE         to_muscle_data_type;                
00311     int8u                       muscle_data[NUM_MUSCLES/2];         
00312 
00313     int32u                      tactile_data_type;                  
00314     //int32u                    tactile_data_type_1;                  //!< The host can request up to 2 different values per frame
00315 
00316 } __attribute__((packed)) ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_COMMAND;
00317 
00318 
00319 
00320 #define PALM_0300_ETHERCAT_COMMAND_HEADER_SIZE  (  sizeof(EDC_COMMAND) + sizeof(FROM_MUSCLE_DATA_TYPE) + sizeof(int16s)  )
00321 
00322 #define PALM_0300_ETHERCAT_STATUS_DATA_SIZE       sizeof(ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_STATUS)
00323 #define PALM_0300_ETHERCAT_COMMAND_DATA_SIZE      sizeof(ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_COMMAND)
00324 
00325                                                     //  Now we need to be *sure* that the Host and the Slave definitely
00326                                                     //  agree on the size of the EtherCAT packets, even if the host is a
00327                                                     //  64-bit machine or something. So we have these calculated sizes.
00328                                                     //  The host and slave can ASSERT that the sizeof() the packets
00329                                                     //  matches the agreed sizes.
00330 #define ETHERCAT_STATUS_0300_AGREED_SIZE     236    //! This is the size of the Status  EtherCAT packet (Status + CAN packet)
00331 #define ETHERCAT_COMMAND_0300_AGREED_SIZE    36     //! This is the size of the Command EtherCAT packet (Status + CAN packet)
00332 
00333 
00345 
00346 #define PALM_0300_ETHERCAT_COMMAND_DATA_ADDRESS               0x1000
00347 #define PALM_0300_ETHERCAT_CAN_BRIDGE_DATA_COMMAND_ADDRESS    (PALM_0300_ETHERCAT_COMMAND_DATA_ADDRESS            + PALM_0300_ETHERCAT_COMMAND_DATA_SIZE)
00348 
00349 #define PALM_0300_ETHERCAT_STATUS_DATA_ADDRESS                (PALM_0300_ETHERCAT_CAN_BRIDGE_DATA_COMMAND_ADDRESS + ETHERCAT_CAN_BRIDGE_DATA_SIZE)
00350 #define PALM_0300_ETHERCAT_CAN_BRIDGE_DATA_STATUS_ADDRESS     (PALM_0300_ETHERCAT_STATUS_DATA_ADDRESS             + PALM_0300_ETHERCAT_STATUS_DATA_SIZE)
00351 
00352 //#define NUM_CONFIGS_REQUIRED 5
00353 
00354 
00355 #endif


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