
Basic Mid-Level control for the rebuilt MorphGI control unit, using PWM to communicate with the low level controllers.
Dependencies: ros_lib_kinetic
LLComms.h@12:595ed862e52f, 2018-08-13 (annotated)
- Committer:
- dofydoink
- Date:
- Mon Aug 13 09:16:29 2018 +0000
- Revision:
- 12:595ed862e52f
- Parent:
- 11:7029367a1840
- Child:
- 14:54c3759e76ed
Tested and working with 3 channels.
Who changed what in which revision?
User | Revision | Line number | New 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 | 12:595ed862e52f | 11 | #include "MLSettings.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: |
dofydoink | 12:595ed862e52f | 25 | |
dofydoink | 12:595ed862e52f | 26 | EventQueue queue; |
dofydoink | 12:595ed862e52f | 27 | Mutex mutChannel[N_CHANNELS]; |
dofydoink | 12:595ed862e52f | 28 | bool isDataReady[N_CHANNELS]; // Flag to indicate path data is ready for transmission to low level. |
dofydoink | 12:595ed862e52f | 29 | int demandPosition[N_CHANNELS]; // 13-bit value to be sent to the actuator |
dofydoink | 12:595ed862e52f | 30 | char chrErrorFlag[N_CHANNELS]; // 3 error bits from LL |
dofydoink | 12:595ed862e52f | 31 | |
dofydoink | 12:595ed862e52f | 32 | LLComms(); // Constructor |
dofydoink | 12:595ed862e52f | 33 | //~LLComms(); // Destructor |
dofydoink | 12:595ed862e52f | 34 | double ReadADCPosition_mtrs(int channel); |
dofydoink | 12:595ed862e52f | 35 | double ReadADCPressure_bar(int channel); |
dofydoink | 12:595ed862e52f | 36 | |
dofydoink | 12:595ed862e52f | 37 | private: |
WD40andTape | 8:d6657767a182 | 38 | |
WD40andTape | 8:d6657767a182 | 39 | // PIN DECLARATIONS |
WD40andTape | 8:d6657767a182 | 40 | InterruptIn pinGate6; // This pin HAS TO BE defined before SPI set up. No Clue Why. |
WD40andTape | 8:d6657767a182 | 41 | SPI spi; // mosi, miso, sclk |
dofydoink | 11:7029367a1840 | 42 | DigitalOut* cs_LL[N_CHANNELS]; // Chip select for low level controller |
dofydoink | 11:7029367a1840 | 43 | DigitalOut* cs_ADC[N_CHANNELS]; // Chip select for ADC |
WD40andTape | 8:d6657767a182 | 44 | DigitalOut pinCheck; |
WD40andTape | 8:d6657767a182 | 45 | // These interrupt pins have to be declared AFTER SPI declaration. No Clue Why. |
WD40andTape | 8:d6657767a182 | 46 | InterruptIn pinGate0; |
WD40andTape | 8:d6657767a182 | 47 | InterruptIn pinGate1; |
WD40andTape | 8:d6657767a182 | 48 | InterruptIn pinGate2; |
WD40andTape | 8:d6657767a182 | 49 | InterruptIn pinGate3; |
WD40andTape | 8:d6657767a182 | 50 | InterruptIn pinGate4; |
WD40andTape | 8:d6657767a182 | 51 | InterruptIn pinGate5; |
WD40andTape | 8:d6657767a182 | 52 | InterruptIn pinGate7; |
WD40andTape | 8:d6657767a182 | 53 | DigitalOut pinReset; // Reset pin for all controllers. |
WD40andTape | 8:d6657767a182 | 54 | |
dofydoink | 11:7029367a1840 | 55 | int ThreadID[N_CHANNELS]; |
WD40andTape | 8:d6657767a182 | 56 | |
WD40andTape | 10:1b6daba32452 | 57 | void SendReceiveData(int channel); |
WD40andTape | 10:1b6daba32452 | 58 | void common_rise_handler(int channel); |
WD40andTape | 10:1b6daba32452 | 59 | void common_fall_handler(int channel); |
WD40andTape | 10:1b6daba32452 | 60 | void rise0(void); |
WD40andTape | 10:1b6daba32452 | 61 | void rise1(void); |
WD40andTape | 10:1b6daba32452 | 62 | void rise2(void); |
WD40andTape | 10:1b6daba32452 | 63 | void rise3(void); |
WD40andTape | 10:1b6daba32452 | 64 | void rise4(void); |
WD40andTape | 10:1b6daba32452 | 65 | void rise5(void); |
WD40andTape | 10:1b6daba32452 | 66 | void rise6(void); |
WD40andTape | 10:1b6daba32452 | 67 | void rise7(void); |
WD40andTape | 10:1b6daba32452 | 68 | void fall0(void); |
WD40andTape | 10:1b6daba32452 | 69 | void fall1(void); |
WD40andTape | 10:1b6daba32452 | 70 | void fall2(void); |
WD40andTape | 10:1b6daba32452 | 71 | void fall3(void); |
WD40andTape | 10:1b6daba32452 | 72 | void fall4(void); |
WD40andTape | 10:1b6daba32452 | 73 | void fall5(void); |
WD40andTape | 10:1b6daba32452 | 74 | void fall6(void); |
WD40andTape | 10:1b6daba32452 | 75 | void fall7(void); |
WD40andTape | 8:d6657767a182 | 76 | |
WD40andTape | 8:d6657767a182 | 77 | }; |
WD40andTape | 8:d6657767a182 | 78 | |
WD40andTape | 8:d6657767a182 | 79 | #endif |