0230_palm_edc_ethercat_protocol.h
Go to the documentation of this file.
00001 //
00002 // © 2010 Shadow Robot Company Limited.
00003 //
00004 // FileName:        this_node.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_0230_ETHERCAT_PROTOCOL_H_INCLUDED
00045 #define PALM_EDC_0230_ETHERCAT_PROTOCOL_H_INCLUDED
00046 
00047 #include "../0220_palm_edc/0220_palm_edc_ethercat_protocol.h"
00048 
00050 typedef struct
00051 {
00052     EDC_COMMAND                 EDC_command;                        
00053 
00054 
00055 
00056 
00057     //  Joint data & Mid/Prox Tactile data  //
00058     int16u                                          sensors[SENSORS_NUM_0220+1];        
00059     TACTILE_SENSOR_MID_PROX     tactile_mid_prox[5];                
00060 
00061 
00062     //  Fingertip Tactile data  //
00063     int32u                      tactile_data_type;                  
00064     int16u                      tactile_data_valid;                 
00065     TACTILE_SENSOR_STATUS_v2    tactile[5];                         
00066 
00067 
00068     //  Aux SPI port data  //
00069     int32u                      aux_spi_data_type;                  
00070     AUX_SPI_SENSOR              aux_spi_sensor;                     
00071 
00072 
00073 
00074     //  Motor data  //
00075     FROM_MOTOR_DATA_TYPE        motor_data_type;                    
00076 
00077 
00078     int16s                      which_motors;                       
00079 
00080 
00081 
00082     int32u                      which_motor_data_arrived;           
00083     int32u                      which_motor_data_had_errors;        
00084 
00085     MOTOR_DATA_PACKET           motor_data_packet[10];              
00086 
00087                                                                     //  TOTAL MOTOR DATA = 54 bytes
00088 
00089 
00090     int16u                      idle_time_us;                       
00091 
00092 
00093 } __attribute__((packed)) ETHERCAT_DATA_STRUCTURE_0230_PALM_EDC_STATUS;
00094 
00095 #define STATUS_HEADER_START     0
00096 #define STATUS_TACTILE_START    (offsetof(ETHERCAT_DATA_STRUCTURE_0230_PALM_EDC_STATUS, tactile_data_type))
00097 #define STATUS_AUX_START        (offsetof(ETHERCAT_DATA_STRUCTURE_0230_PALM_EDC_STATUS, aux_spi_data_type))
00098 #define STATUS_MOTOR_START      (offsetof(ETHERCAT_DATA_STRUCTURE_0230_PALM_EDC_STATUS,   motor_data_type))
00099 #define STATUS_IDLETIME_START   (offsetof(ETHERCAT_DATA_STRUCTURE_0230_PALM_EDC_STATUS,      idle_time_us))
00100 
00101 #define STATUS_TOTAL_LENGTH     (sizeof(ETHERCAT_DATA_STRUCTURE_0230_PALM_EDC_STATUS))
00102 #define STATUS_JOINTS_LENGTH    (STATUS_TACTILE_START  - STATUS_HEADER_START)
00103 #define STATUS_TACTILE_LENGTH   (STATUS_AUX_START      - STATUS_TACTILE_START)
00104 #define STATUS_AUX_LENGTH       (STATUS_MOTOR_START    - STATUS_AUX_START)
00105 #define STATUS_MOTOR_LENGTH     (STATUS_IDLETIME_START - STATUS_MOTOR_START)
00106 #define STATUS_IDLETIME_LENGTH  (STATUS_TOTAL_LENGTH   - STATUS_IDLETIME_START)
00107 
00108 
00109 
00111 typedef struct
00112 {
00113     EDC_COMMAND             EDC_command;                        
00114 
00115 
00116     FROM_MOTOR_DATA_TYPE    from_motor_data_type;               
00117     int16s                  which_motors;                       
00118 
00119 
00120     TO_MOTOR_DATA_TYPE      to_motor_data_type;                 
00121     int32u                   tactile_data_type;                 
00122     int32u                       aux_data_type;                 
00123 
00124     
00125     int16s                  motor_data[NUM_MOTORS];             
00126 
00127 } __attribute__((packed)) ETHERCAT_DATA_STRUCTURE_0230_PALM_EDC_COMMAND;
00128 
00129 
00130 #define PALM_0230_ETHERCAT_COMMAND_HEADER_SIZE  (  sizeof(EDC_COMMAND)          +   \
00131                                                    sizeof(FROM_MOTOR_DATA_TYPE) +   \
00132                                                    sizeof(int16s)               +   \
00133                                                    sizeof(TO_MOTOR_DATA_TYPE)   +   \
00134                                                    sizeof(int32u)               )
00135 
00136 #define PALM_0230_ETHERCAT_STATUS_DATA_SIZE       sizeof(ETHERCAT_DATA_STRUCTURE_0230_PALM_EDC_STATUS)
00137 #define PALM_0230_ETHERCAT_COMMAND_DATA_SIZE      sizeof(ETHERCAT_DATA_STRUCTURE_0230_PALM_EDC_COMMAND)
00138 
00139                                                     //  Now we need to be *sure* that the Host and the Slave definitely
00140                                                     //  agree on the size of the EtherCAT packets, even if the host is a
00141                                                     //  64-bit machine or something. So we have these calculated sizes.
00142                                                     //  The host and slave can ASSERT that the sizeof() the packets
00143                                                     //  matches the agreed sizes.
00144 #define ETHERCAT_STATUS_0230_AGREED_SIZE     416    //! This is the size of the Status  EtherCAT packet (Status + CAN packet)
00145 #define ETHERCAT_COMMAND_0230_AGREED_SIZE    62     //! This is the size of the Command EtherCAT packet (Status + CAN packet)
00146 
00147 
00148 
00160 
00161 #define PALM_0230_ETHERCAT_COMMAND_DATA_ADDRESS               0x1000
00162 #define PALM_0230_ETHERCAT_CAN_BRIDGE_DATA_COMMAND_ADDRESS    (PALM_0230_ETHERCAT_COMMAND_DATA_ADDRESS            + PALM_0230_ETHERCAT_COMMAND_DATA_SIZE)
00163 
00164 #define PALM_0230_ETHERCAT_STATUS_DATA_ADDRESS                (PALM_0230_ETHERCAT_CAN_BRIDGE_DATA_COMMAND_ADDRESS + ETHERCAT_CAN_BRIDGE_DATA_SIZE)
00165 #define PALM_0230_ETHERCAT_CAN_BRIDGE_DATA_STATUS_ADDRESS     (PALM_0230_ETHERCAT_STATUS_DATA_ADDRESS             + PALM_0230_ETHERCAT_STATUS_DATA_SIZE)
00166 
00167 
00168 
00169 #endif


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