Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00039
00040
00041 #ifndef THIS_NODE_H_INCLUDED
00042 #define THIS_NODE_H_INCLUDED
00043
00044 #define DUAL_CAN_AVAILABLE
00045
00046 #include "GenericTypeDefs.h"
00047
00048 #include <plib.h>
00049 #include <peripheral/can.h>
00050 #include <peripheral/timer.h>
00051 #include "hardware/can/shadow_can.h"
00052 #include "misc/typedefs_shadow.h"
00053 #include "tests/assert_shadow.h"
00054
00055 #include "this_node_serial_number.h"
00056
00057
00058
00059
00060 #define NO_STRINGS
00061 #include "0220_palm_edc_ethercat_protocol.h"
00062 #include "simple_can/simple_can.h"
00063
00069 #define INCLUDE_IMPLEMENTATION_DETAILS
00070 #include "hardware/spi/spi_32.h"
00071 #include "hardware/uart/uart_32.h"
00072 #undef INCLUDE_IMPLEMENTATION_DETAILS
00073
00074
00075
00076 #ifndef CAN_ERROR_CODES
00077 #error CAN_ERROR_CODES not defined
00078 #endif
00079
00080 #ifndef CAN_EVENT_CODES
00081 #error CAN_EVENT_CODES not defined
00082 #endif
00083
00084 #ifndef SIMPLE_CAN_ERROR_CODES
00085 #error SIMPLE_CAN_ERROR_CODES not defined
00086 #endif
00087
00088
00091
00094 typedef enum
00095 {
00096
00097 CAN_ERROR_CODES,
00098 SIMPLE_CAN_ERROR_CODES
00099 }ERROR_CODE;
00100
00101
00104
00107 typedef enum
00108 {
00109
00110 CAN_EVENT_CODES,
00111 }EVENT_CODE;
00112
00113
00114
00115 void initialise_this_node(void);
00116
00117 void handle_configuration_message(CAN_message* message);
00118 void Service_EtherCAT_Packet(void);
00119 void Check_For_EtherCAT_Packet(void);
00120
00121
00122
00123 #define THIS_NODE_PRODUCT_CODE 0x0006
00124
00125
00126
00127
00128
00129 #define SYSTEM_FREQ_HZ 80000000
00130 #define PERIPHERAL_BUS_CLOCK_HZ 40000000
00131 #define CAN_BUS_SPEED_HZ 1000000
00132
00133 #define NUM_PORTS 7
00134 #define NUM_PINS_PER_PORT 16
00135 #define NUM_LEDS 7
00136 #define NUM_SPI_PORTS 2
00137
00138 #define ET1200_SPI_CHANNEL 0
00139 #define CAN_BASE_ADR_MOTORS_TX 0x0200
00140 #define CAN_BASE_ADR_MOTORS_RX 0x0300
00141 #define FIND_FREE_CAN_BUFFER_MAX_TRIES 8
00142
00143
00144 #include "internal_reporting/internal_reporting.h"
00145 #include "hardware/ports/port_pin.h"
00146 #include "hardware/spi/spi_32.h"
00147 #include "hardware/spi/spi_parallel_32.h"
00148 #include "hardware/i2c/i2c_32.h"
00149 #include "hardware/eeprom/eeprom_i2c.h"
00150 #include "hardware/et1200/et1200_interface.h"
00151 #include "hardware/et1200/et1200_eeprom_contents.h"
00152 #include "hardware/et1200/et1200.h"
00153 #include "syntouch/biotac_2_3_parallel.h"
00154 #include "pst/pst_parallel.h"
00155 #include "itg3200/itg3200.h"
00156 #include "leds/leds.h"
00157
00158
00159 #include "../support/svnversion.h"
00160
00161 void Send_Sensor_Data_Structure(void);
00162 void Fill_Sensor_Data_Structure(I2C_MODULE I2Cm);
00163
00164 void Read_Commands_From_ET1200(void);
00165 void Send_All_CAN_Messages(void);
00166 void Translate_SOMI_Bits(void);
00167 void Read_All_Sensors(void);
00168 void Collect_All_CAN_Messages(void);
00169 int32u get_frame_time_us(void);
00170 void Wait_For_Until_Frame_Time(int32u frame_time_us);
00171 inline void write_status_data_To_ET1200(void);
00172
00173 void delay_us(int32u microseconds) ;
00174 void delay_ms(int32u milliseconds);
00175
00176 int8u get_which_motors(void);
00177 int8u get_from_motor_data_type(void);
00178
00179 void bad_CAN_message_seen(void);
00180
00181
00182 extern int8u palm_EDC_0200_sensor_mapping[64];
00183 extern int64u node_id;
00184
00185 extern ETHERCAT_CAN_BRIDGE_DATA can_bridge_data_from_ROS;
00186 extern ETHERCAT_CAN_BRIDGE_DATA can_bridge_data_to_ROS;
00187
00188 #define PALM_PCB_01 //!< Use PALM_PCB_00 for the old prototype board.
00189
00190
00191 #ifdef PALM_PCB_00 // Definitions for big square prototype board
00192
00193
00194 #define USE_SIMPLE_PST_CS
00195 #define AUTO_TRIGGER 0 //!< Trigger sampling even if there is no EtherCAT activity. Useful for debugging
00196
00197 #define ET1200_CHIP_SELECT_PIN 'C', 14
00198 #define ET1200_RESET_PIN 'F', 3
00199 #define ET1200_EEPROM_PIN 'G', 2
00200 #define SPI_CS_PIN 'B', 9
00201 #define SPI_CLOCK_PIN 'B', 15
00202 #define SPI_MOSI_PIN 'G', 9
00203 #define ET1200_SOMI_PIN 'D', 2
00204 #define LED_CAN1_TX_PIN 'D', 4
00205 #define LED_CAN1_RX_PIN 'D', 5
00206 #define LED_CAN1_ERR_PIN 'D', 0
00207 #define LED_CAN2_TX_PIN 'D', 7
00208 #define LED_CAN2_ERR_PIN 'D', 6
00209 #define LED_AL_ERR_PIN 'D', 11
00210 #define LED_CFG_PIN 'D', 8
00211
00212 #define SPI_PORT SPI_CHANNEL1A, 10, ET1200_chip_select
00213 #define I2C_PORT I2C1, 400000
00214
00215 #define ALL_LED_BITS
00216
00217 #define ALL_LED_BITS_PORTB 0b0000000000000000
00218 #define ALL_LED_BITS_PORTC 0b0000000000000000
00219 #define ALL_LED_BITS_PORTD 0b0000100111110001
00220 #define ALL_LED_BITS_PORTE 0b0000000000000000
00221 #define ALL_LED_BITS_PORTF 0b0000000000000000
00222
00223 #define SPIP_INPUT_BIT_0 (porte & 0x0001)
00224 #define SPIP_INPUT_BIT_1 (porte & 0x0002)
00225 #define SPIP_INPUT_BIT_2 (porte & 0x0004)
00226 #define SPIP_INPUT_BIT_3 (porte & 0x0008)
00227 #define SPIP_INPUT_BIT_4 (porte & 0x0010)
00228 #define SPIP_INPUT_BIT_5 (porte & 0x0020)
00229 #define SPIP_INPUT_BIT_6 (porte & 0x0040)
00230 #define SPIP_INPUT_BIT_7 (porte & 0x0080)
00231
00232 #define FF_SOMI (porte & 0x0001)
00233 #define MF_SOMI (porte & 0x0002)
00234 #define RF_SOMI (porte & 0x0004)
00235 #define LF_SOMI (porte & 0x0008)
00236 #define TH_SOMI (porte & 0x0040)
00237
00238 #define PIN_BIT(x) (1<<x)
00239
00240 #define SPIP_CHIP_SELECT_UP LATBSET = PIN_BIT(9);
00241 #define SPIP_CHIP_SELECT_DOWN LATBCLR = PIN_BIT(9);
00242
00243 #define SPIP_CLOCK_UP LATBSET = PIN_BIT(15);
00244 #define SPIP_CLOCK_DOWN LATBCLR = PIN_BIT(15);
00245
00246 #define SPIP_MOSI_UP LATGSET = PIN_BIT(9);
00247 #define SPIP_MOSI_DOWN LATGCLR = PIN_BIT(9);
00248
00249 #define SPI_BUF SPI1ABUF
00250 #define SPI_STAT SPI1ASTAT
00251 #define SPI_CON SPI1ACON
00252 #define SPI_STATbits SPI1ASTATbits
00253
00254 #endif
00255
00256
00257 #ifdef PALM_PCB_01 // Definitions for actual palm board inside hand
00258 #define USE_SIMPLE_PST_CS
00259 #define AUTO_TRIGGER 0 //!< Trigger sampling even if there is no EtherCAT activity. Useful for debugging
00260
00261 #define ET1200_CHIP_SELECT_PIN 'C', 14
00262 #define ET1200_RESET_PIN 'F', 3
00263 #define ET1200_EEPROM_PIN 'G', 2
00264 #define SPI2_CS_PIN 'D', 11
00265 #define SPI_CS_PIN 'D', 7
00266 #define SPI_CLOCK_PIN 'D', 6
00267 #define SPI_MOSI_PIN 'D', 5
00268 #define ET1200_SOMI_PIN 'G', 7
00269 #define ACCEL_CS_PIN 'G', 9
00270 #define LED_CAN1_TX_PIN 'D', 0
00271 #define LED_CAN1_RX_PIN 'D', 4
00272 #define LED_CAN1_ERR_PIN 'D', 8
00273 #define LED_CAN2_TX_PIN 'F', 4
00274 #define LED_CAN2_RX_PIN 'B', 15
00275 #define LED_CAN2_ERR_PIN 'F', 5
00276 #define LED_AL_ERR_PIN 'C', 13
00277
00278 #define SPI_PORT SPI_CHANNEL2A, 10, ET1200_chip_select
00279 #define I2C_PORT I2C1, 400000
00280
00281 #define ALL_LED_BITS_PORTB 0b1000000000000000
00282 #define ALL_LED_BITS_PORTC 0b0010000000000000
00283 #define ALL_LED_BITS_PORTD 0b0000000100010001
00284 #define ALL_LED_BITS_PORTE 0b0000000000000000
00285 #define ALL_LED_BITS_PORTF 0b0000000000100000
00286
00287
00288 #define SPIP_INPUT_BIT_0 (porte & 0x0001)
00289 #define SPIP_INPUT_BIT_1 (porte & 0x0002)
00290 #define SPIP_INPUT_BIT_2 (porte & 0x0004)
00291 #define SPIP_INPUT_BIT_3 (porte & 0x0008)
00292 #define SPIP_INPUT_BIT_4 (porte & 0x0010)
00293 #define SPIP_INPUT_BIT_5 (porte & 0x0020)
00294 #define SPIP_INPUT_BIT_6 (porte & 0x0040)
00295 #define SPIP_INPUT_BIT_7 (porte & 0x0080)
00296
00297 #define FF_SOMI (porte & 0x0004)
00298 #define MF_SOMI (porte & 0x0002)
00299 #define RF_SOMI (porte & 0x0001)
00300 #define LF_SOMI (porte & 0x0008)
00301 #define TH_SOMI (porte & 0x0040)
00302
00303 #define PIN_BIT(x) (1<<x)
00304
00305 #define SPIP_CHIP_SELECT_UP LATDSET = PIN_BIT(7);
00306 #define SPIP_CHIP_SELECT_DOWN LATDCLR = PIN_BIT(7);
00307
00308 #define SPIP_CLOCK_UP LATDSET = PIN_BIT(6);
00309 #define SPIP_CLOCK_DOWN LATDCLR = PIN_BIT(6);
00310
00311 #define SPIP_MOSI_UP LATDSET = PIN_BIT(5);
00312 #define SPIP_MOSI_DOWN LATDCLR = PIN_BIT(5);
00313
00314 #define SPI_BUF SPI2ABUF
00315 #define SPI_STAT SPI2ASTAT
00316 #define SPI_CON SPI2ACON
00317 #define SPI_STATbits SPI2ASTATbits
00318
00319 #endif
00320
00321
00322 #endif