
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@29:10a5cf37a875, 2019-02-08 (annotated)
- Committer:
- WD40andTape
- Date:
- Fri Feb 08 18:36:15 2019 +0000
- Revision:
- 29:10a5cf37a875
- Parent:
- 26:7c59002c9cd7
- Child:
- 33:9877ca32e43c
Actuator numbering standardised. Units converted to mm. Added text message feedback. Using Int16MultiArray instead of Float32MultiArray.
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 | 26:7c59002c9cd7 | 7 | #include "math.h" |
WD40andTape | 26:7c59002c9cd7 | 8 | #include <algorithm> |
WD40andTape | 8:d6657767a182 | 9 | // MBED IMPORTS |
WD40andTape | 8:d6657767a182 | 10 | #include "mbed.h" |
WD40andTape | 8:d6657767a182 | 11 | #include "mbed_events.h" |
dofydoink | 11:7029367a1840 | 12 | // CUSTOM IMPORTS |
dofydoink | 12:595ed862e52f | 13 | #include "MLSettings.h" |
WD40andTape | 8:d6657767a182 | 14 | |
WD40andTape | 8:d6657767a182 | 15 | // ADC SPI DEFINES |
WD40andTape | 8:d6657767a182 | 16 | #define PREAMBLE 0x06 |
WD40andTape | 8:d6657767a182 | 17 | #define CHAN_1 0x30 |
WD40andTape | 8:d6657767a182 | 18 | #define CHAN_2 0x70 |
WD40andTape | 8:d6657767a182 | 19 | #define CHAN_3 0xB0 |
WD40andTape | 8:d6657767a182 | 20 | #define CHAN_4 0xF0 |
WD40andTape | 8:d6657767a182 | 21 | #define DATA_MASK 0x0F |
WD40andTape | 8:d6657767a182 | 22 | |
WD40andTape | 8:d6657767a182 | 23 | class LLComms |
WD40andTape | 8:d6657767a182 | 24 | { |
dofydoink | 11:7029367a1840 | 25 | |
WD40andTape | 8:d6657767a182 | 26 | public: |
dofydoink | 12:595ed862e52f | 27 | |
dofydoink | 12:595ed862e52f | 28 | EventQueue queue; |
dofydoink | 12:595ed862e52f | 29 | Mutex mutChannel[N_CHANNELS]; |
dofydoink | 12:595ed862e52f | 30 | bool isDataReady[N_CHANNELS]; // Flag to indicate path data is ready for transmission to low level. |
WD40andTape | 26:7c59002c9cd7 | 31 | double demandPosition_mm[N_CHANNELS]; |
WD40andTape | 26:7c59002c9cd7 | 32 | double demandSpeed_mmps[N_CHANNELS]; |
dofydoink | 12:595ed862e52f | 33 | char chrErrorFlag[N_CHANNELS]; // 3 error bits from LL |
WD40andTape | 29:10a5cf37a875 | 34 | unsigned int positionSensor_uint[N_CHANNELS]; |
WD40andTape | 26:7c59002c9cd7 | 35 | double positionSensor_mm[N_CHANNELS]; // The actual chamber lengths in meters given as the change in length relative to neutral (should always be >=0) |
WD40andTape | 29:10a5cf37a875 | 36 | unsigned int pressureSensor_uint[N_CHANNELS]; |
WD40andTape | 22:82871f00f89d | 37 | double pressureSensor_bar[N_CHANNELS]; // The pressure in a given chamber in bar (1 bar = 100,000 Pa) |
dofydoink | 12:595ed862e52f | 38 | |
dofydoink | 12:595ed862e52f | 39 | LLComms(); // Constructor |
dofydoink | 12:595ed862e52f | 40 | //~LLComms(); // Destructor |
dofydoink | 12:595ed862e52f | 41 | |
dofydoink | 12:595ed862e52f | 42 | private: |
WD40andTape | 8:d6657767a182 | 43 | |
WD40andTape | 8:d6657767a182 | 44 | // PIN DECLARATIONS |
WD40andTape | 8:d6657767a182 | 45 | InterruptIn pinGate6; // This pin HAS TO BE defined before SPI set up. No Clue Why. |
WD40andTape | 14:54c3759e76ed | 46 | SPI spi_0; // mosi, miso, sclk |
WD40andTape | 14:54c3759e76ed | 47 | SPI spi_1; |
dofydoink | 11:7029367a1840 | 48 | DigitalOut* cs_LL[N_CHANNELS]; // Chip select for low level controller |
dofydoink | 11:7029367a1840 | 49 | DigitalOut* cs_ADC[N_CHANNELS]; // Chip select for ADC |
WD40andTape | 8:d6657767a182 | 50 | DigitalOut pinCheck; |
WD40andTape | 8:d6657767a182 | 51 | // These interrupt pins have to be declared AFTER SPI declaration. No Clue Why. |
WD40andTape | 8:d6657767a182 | 52 | InterruptIn pinGate0; |
WD40andTape | 8:d6657767a182 | 53 | InterruptIn pinGate1; |
WD40andTape | 8:d6657767a182 | 54 | InterruptIn pinGate2; |
WD40andTape | 8:d6657767a182 | 55 | InterruptIn pinGate3; |
WD40andTape | 8:d6657767a182 | 56 | InterruptIn pinGate4; |
WD40andTape | 8:d6657767a182 | 57 | InterruptIn pinGate5; |
WD40andTape | 8:d6657767a182 | 58 | InterruptIn pinGate7; |
WD40andTape | 8:d6657767a182 | 59 | DigitalOut pinReset; // Reset pin for all controllers. |
WD40andTape | 8:d6657767a182 | 60 | |
dofydoink | 11:7029367a1840 | 61 | int ThreadID[N_CHANNELS]; |
WD40andTape | 8:d6657767a182 | 62 | |
WD40andTape | 26:7c59002c9cd7 | 63 | unsigned int formatMessage(short int type, double dblValue, double dblMaxValue); |
WD40andTape | 26:7c59002c9cd7 | 64 | //bool CheckMessage(int msg, short int trueType); |
WD40andTape | 26:7c59002c9cd7 | 65 | bool CheckMessage(int msg); |
WD40andTape | 26:7c59002c9cd7 | 66 | bool PerformMasterSPI(SPI *spi, unsigned int outboundMsgs[], unsigned int inboundMsgsData[]); |
WD40andTape | 10:1b6daba32452 | 67 | void SendReceiveData(int channel); |
WD40andTape | 10:1b6daba32452 | 68 | void common_rise_handler(int channel); |
WD40andTape | 10:1b6daba32452 | 69 | void common_fall_handler(int channel); |
WD40andTape | 10:1b6daba32452 | 70 | void rise0(void); |
WD40andTape | 10:1b6daba32452 | 71 | void rise1(void); |
WD40andTape | 10:1b6daba32452 | 72 | void rise2(void); |
WD40andTape | 10:1b6daba32452 | 73 | void rise3(void); |
WD40andTape | 10:1b6daba32452 | 74 | void rise4(void); |
WD40andTape | 10:1b6daba32452 | 75 | void rise5(void); |
WD40andTape | 10:1b6daba32452 | 76 | void rise6(void); |
WD40andTape | 10:1b6daba32452 | 77 | void rise7(void); |
WD40andTape | 10:1b6daba32452 | 78 | void fall0(void); |
WD40andTape | 10:1b6daba32452 | 79 | void fall1(void); |
WD40andTape | 10:1b6daba32452 | 80 | void fall2(void); |
WD40andTape | 10:1b6daba32452 | 81 | void fall3(void); |
WD40andTape | 10:1b6daba32452 | 82 | void fall4(void); |
WD40andTape | 10:1b6daba32452 | 83 | void fall5(void); |
WD40andTape | 10:1b6daba32452 | 84 | void fall6(void); |
WD40andTape | 10:1b6daba32452 | 85 | void fall7(void); |
WD40andTape | 8:d6657767a182 | 86 | |
WD40andTape | 8:d6657767a182 | 87 | }; |
WD40andTape | 8:d6657767a182 | 88 | |
WD40andTape | 8:d6657767a182 | 89 | #endif |