Basic Mid-Level control for the rebuilt MorphGI control unit, using PWM to communicate with the low level controllers.

Dependencies:   ros_lib_kinetic

Committer:
dofydoink
Date:
Fri Aug 10 10:40:18 2018 +0000
Revision:
11:7029367a1840
Parent:
10:1b6daba32452
Child:
12:595ed862e52f
Tested and working with 1 actuator.

Who changed what in which revision?

UserRevisionLine numberNew contents of line
WD40andTape 8:d6657767a182 1 // LLComms.h
WD40andTape 8:d6657767a182 2
WD40andTape 8:d6657767a182 3 #ifndef LLCOMMS_H
WD40andTape 8:d6657767a182 4 #define LLCOMMS_H
WD40andTape 8:d6657767a182 5
WD40andTape 8:d6657767a182 6 // STANDARD IMPORTS
WD40andTape 8:d6657767a182 7 // MBED IMPORTS
WD40andTape 8:d6657767a182 8 #include "mbed.h"
WD40andTape 8:d6657767a182 9 #include "mbed_events.h"
dofydoink 11:7029367a1840 10 // CUSTOM IMPORTS
dofydoink 11:7029367a1840 11 #include "MLOptions.h"
WD40andTape 8:d6657767a182 12
WD40andTape 8:d6657767a182 13 // ADC SPI DEFINES
WD40andTape 8:d6657767a182 14 #define PREAMBLE 0x06
WD40andTape 8:d6657767a182 15 #define CHAN_1 0x30
WD40andTape 8:d6657767a182 16 #define CHAN_2 0x70
WD40andTape 8:d6657767a182 17 #define CHAN_3 0xB0
WD40andTape 8:d6657767a182 18 #define CHAN_4 0xF0
WD40andTape 8:d6657767a182 19 #define DATA_MASK 0x0F
WD40andTape 8:d6657767a182 20
WD40andTape 8:d6657767a182 21 class LLComms
WD40andTape 8:d6657767a182 22 {
dofydoink 11:7029367a1840 23
WD40andTape 8:d6657767a182 24 public:
WD40andTape 8:d6657767a182 25
WD40andTape 8:d6657767a182 26 // PIN DECLARATIONS
WD40andTape 8:d6657767a182 27 InterruptIn pinGate6; // This pin HAS TO BE defined before SPI set up. No Clue Why.
WD40andTape 8:d6657767a182 28 SPI spi; // mosi, miso, sclk
dofydoink 11:7029367a1840 29 DigitalOut* cs_LL[N_CHANNELS]; // Chip select for low level controller
dofydoink 11:7029367a1840 30 DigitalOut* cs_ADC[N_CHANNELS]; // Chip select for ADC
WD40andTape 8:d6657767a182 31 DigitalOut pinCheck;
WD40andTape 8:d6657767a182 32 // These interrupt pins have to be declared AFTER SPI declaration. No Clue Why.
WD40andTape 8:d6657767a182 33 InterruptIn pinGate0;
WD40andTape 8:d6657767a182 34 InterruptIn pinGate1;
WD40andTape 8:d6657767a182 35 InterruptIn pinGate2;
WD40andTape 8:d6657767a182 36 InterruptIn pinGate3;
WD40andTape 8:d6657767a182 37 InterruptIn pinGate4;
WD40andTape 8:d6657767a182 38 InterruptIn pinGate5;
WD40andTape 8:d6657767a182 39 InterruptIn pinGate7;
WD40andTape 8:d6657767a182 40 DigitalOut pinReset; // Reset pin for all controllers.
WD40andTape 8:d6657767a182 41
dofydoink 11:7029367a1840 42 bool isDataReady[N_CHANNELS]; // Flag to indicate path data is ready for transmission to low level.
dofydoink 11:7029367a1840 43 Mutex mutChannel[N_CHANNELS];
dofydoink 11:7029367a1840 44 int ThreadID[N_CHANNELS];
WD40andTape 10:1b6daba32452 45 EventQueue queue;
WD40andTape 8:d6657767a182 46
dofydoink 11:7029367a1840 47 int demandPosition[N_CHANNELS]; // 13-bit value to be sent to the actuator
dofydoink 11:7029367a1840 48 char chrErrorFlag[N_CHANNELS]; // 3 error bits from LL
WD40andTape 8:d6657767a182 49
dofydoink 11:7029367a1840 50 LLComms(int low_level_spi_frequency); // Constructor
dofydoink 11:7029367a1840 51 //~LLComms(); // Destructor
WD40andTape 10:1b6daba32452 52 void SendReceiveData(int channel);
WD40andTape 10:1b6daba32452 53 void common_rise_handler(int channel);
WD40andTape 10:1b6daba32452 54 void common_fall_handler(int channel);
WD40andTape 10:1b6daba32452 55 void rise0(void);
WD40andTape 10:1b6daba32452 56 void rise1(void);
WD40andTape 10:1b6daba32452 57 void rise2(void);
WD40andTape 10:1b6daba32452 58 void rise3(void);
WD40andTape 10:1b6daba32452 59 void rise4(void);
WD40andTape 10:1b6daba32452 60 void rise5(void);
WD40andTape 10:1b6daba32452 61 void rise6(void);
WD40andTape 10:1b6daba32452 62 void rise7(void);
WD40andTape 10:1b6daba32452 63 void fall0(void);
WD40andTape 10:1b6daba32452 64 void fall1(void);
WD40andTape 10:1b6daba32452 65 void fall2(void);
WD40andTape 10:1b6daba32452 66 void fall3(void);
WD40andTape 10:1b6daba32452 67 void fall4(void);
WD40andTape 10:1b6daba32452 68 void fall5(void);
WD40andTape 10:1b6daba32452 69 void fall6(void);
WD40andTape 10:1b6daba32452 70 void fall7(void);
WD40andTape 8:d6657767a182 71
WD40andTape 8:d6657767a182 72 private:
WD40andTape 8:d6657767a182 73
WD40andTape 8:d6657767a182 74 int _spi_frequency;
WD40andTape 8:d6657767a182 75
WD40andTape 8:d6657767a182 76 double ReadADCPosition_mtrs(int channel);
WD40andTape 8:d6657767a182 77 double ReadADCPressure_bar(int channel);
WD40andTape 8:d6657767a182 78
WD40andTape 8:d6657767a182 79 };
WD40andTape 8:d6657767a182 80
WD40andTape 8:d6657767a182 81 #endif