Руслан Бредун / Mbed 2 deprecated STM32-MC_node

Dependencies:   mbed Watchdog stm32-sensor-base2

Committer:
ruslanbredun
Date:
Sun Dec 06 11:06:23 2020 +0000
Revision:
13:0c732e06d675
Parent:
12:406f75196a12
Child:
14:b3530522908e
Add encoders

Who changed what in which revision?

UserRevisionLine numberNew contents of line
ommpy 0:d383e2dee0f7 1 #include <global.h>
ruslanbredun 12:406f75196a12 2
ommpy 10:0b7f23df690a 3 //RS485 RS485(UART2_TX,UART2_RX,DE_TXD_2); // Tx, Rx , !RE and DE MAX485 pin
ruslanbredun 12:406f75196a12 4 Serial RS2(UART2_TX, UART2_RX);
ruslanbredun 12:406f75196a12 5 Serial RS1(UART1_TX, UART1_RX);
ruslanbredun 12:406f75196a12 6
nestedslk 4:f6e22dd39313 7 Timer timer;
ommpy 6:a760ce6defbe 8 typedef uint8_t byte;
ruslanbredun 12:406f75196a12 9
ruslanbredun 12:406f75196a12 10 DigitalOut Select1(DE_TXD_1);
ruslanbredun 12:406f75196a12 11 DigitalOut Select2(DE_TXD_2);
ruslanbredun 12:406f75196a12 12
ruslanbredun 12:406f75196a12 13
ommpy 10:0b7f23df690a 14
ruslanbredun 12:406f75196a12 15 bool sendFlag = false;
ruslanbredun 12:406f75196a12 16 bool sendFlag1 = false;
ruslanbredun 12:406f75196a12 17 int cmd[13] = {0xA5,0x40,0x90,0x08,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x7D};
ruslanbredun 12:406f75196a12 18 char inChar[52];
ruslanbredun 12:406f75196a12 19 int index = 0;
ruslanbredun 12:406f75196a12 20 char c = '1';
ommpy 6:a760ce6defbe 21 const unsigned char CRC7_POLY = 0x91;
ruslanbredun 12:406f75196a12 22
ommpy 6:a760ce6defbe 23 unsigned char getCRC(unsigned char message[], unsigned char length)
ommpy 6:a760ce6defbe 24 {
ruslanbredun 12:406f75196a12 25 unsigned char i, j, crc = 0;
ruslanbredun 12:406f75196a12 26
ruslanbredun 12:406f75196a12 27 for (i = 0; i < length; i++) {
ruslanbredun 12:406f75196a12 28 crc ^= message[i];
ruslanbredun 12:406f75196a12 29 for (j = 0; j < 8; j++) {
ruslanbredun 12:406f75196a12 30 if (crc & 1)
ruslanbredun 12:406f75196a12 31 crc ^= CRC7_POLY;
ruslanbredun 12:406f75196a12 32 crc >>= 1;
ruslanbredun 12:406f75196a12 33 }
ommpy 6:a760ce6defbe 34 }
ruslanbredun 12:406f75196a12 35 return crc;
ruslanbredun 12:406f75196a12 36
ommpy 6:a760ce6defbe 37 }
ruslanbredun 12:406f75196a12 38
ruslanbredun 12:406f75196a12 39 void UART2_callback()
ruslanbredun 12:406f75196a12 40 {
ruslanbredun 12:406f75196a12 41 c = RS2.getc();
ruslanbredun 12:406f75196a12 42 if(c == '4') {
ruslanbredun 12:406f75196a12 43 sendFlag = true;
ruslanbredun 12:406f75196a12 44 } else {
ruslanbredun 12:406f75196a12 45 Select2 = 1;
ruslanbredun 13:0c732e06d675 46 wait_ms(90);
ruslanbredun 12:406f75196a12 47 Select2 = 0;
ruslanbredun 12:406f75196a12 48 }
ruslanbredun 12:406f75196a12 49
ruslanbredun 12:406f75196a12 50 }
ruslanbredun 12:406f75196a12 51
nestedslk 4:f6e22dd39313 52 int main()
nestedslk 4:f6e22dd39313 53 {
ruslanbredun 12:406f75196a12 54 RS2.baud (115200);
ruslanbredun 12:406f75196a12 55 Select1 = 0;
ruslanbredun 12:406f75196a12 56 Select2 = 0;
ruslanbredun 12:406f75196a12 57 RS2.attach(&UART2_callback);
ruslanbredun 12:406f75196a12 58 //RS1.attach(&UART1_callback);
ruslanbredun 12:406f75196a12 59
ruslanbredun 12:406f75196a12 60 #if DEMO_CODE
ruslanbredun 12:406f75196a12 61 int US1_data = 0,US2_data = 0, US3_data = 0;
ruslanbredun 12:406f75196a12 62
ruslanbredun 12:406f75196a12 63 int Lift_IR1 = 0,Lift_IR2 = 0;
ruslanbredun 12:406f75196a12 64
ruslanbredun 12:406f75196a12 65 bool IR1_data = 0,IR2_data = 0;
ruslanbredun 12:406f75196a12 66
ruslanbredun 12:406f75196a12 67 float temp_one_value = -1, temp_two_value = -1, Enc_left_data = 0, Enc_right_data = 0, time = 0;
ruslanbredun 12:406f75196a12 68
ruslanbredun 12:406f75196a12 69 Timer timer1;
ruslanbredun 12:406f75196a12 70 timer1.start();
ommpy 10:0b7f23df690a 71
ruslanbredun 12:406f75196a12 72 OneWire oneWire(PA_11); // substitute D8 with the actual pin name connected to the 1-wire bus
ommpy 10:0b7f23df690a 73 int sensorsFound = 0;
ruslanbredun 12:406f75196a12 74
ruslanbredun 12:406f75196a12 75 DigitalIn Lift1 (PB_0);
ruslanbredun 12:406f75196a12 76 DigitalIn Lift2 (PB_1);
ruslanbredun 12:406f75196a12 77
ruslanbredun 12:406f75196a12 78 AS5045 Enc_left(SP1_NSS1);
ruslanbredun 12:406f75196a12 79 AS5045 Enc_right(SP1_NSS2);
ruslanbredun 12:406f75196a12 80
ruslanbredun 12:406f75196a12 81 JSN_SR04 US_sensor_left (PB_14, PA_9);
ruslanbredun 12:406f75196a12 82 JSN_SR04 US_sensor_middle (PB_15, PA_9);
ruslanbredun 12:406f75196a12 83 JSN_SR04 US_sensor_right (PA_8, PA_9);
ruslanbredun 12:406f75196a12 84
ruslanbredun 12:406f75196a12 85 US_sensor_left.setRanges (20, 300);
ruslanbredun 12:406f75196a12 86 US_sensor_middle.setRanges (20, 300);
ruslanbredun 12:406f75196a12 87 US_sensor_right.setRanges (20, 300);
ruslanbredun 12:406f75196a12 88
ruslanbredun 12:406f75196a12 89 E18_D80NK IR_sensor_left (PB_13);
ruslanbredun 12:406f75196a12 90 E18_D80NK IR_sensor_right (PB_12);
ruslanbredun 12:406f75196a12 91
ruslanbredun 12:406f75196a12 92 for (sensorsFound = 0; sensorsFound < MAX_SENSOSRS; sensorsFound++) {
ommpy 10:0b7f23df690a 93 ds1820[sensorsFound] = new DS1820(&oneWire);
ommpy 10:0b7f23df690a 94 if (!ds1820[sensorsFound]->begin()) {
ommpy 10:0b7f23df690a 95 delete ds1820[sensorsFound];
ommpy 10:0b7f23df690a 96 break;
ommpy 10:0b7f23df690a 97 }
ommpy 10:0b7f23df690a 98 }
ruslanbredun 12:406f75196a12 99
ruslanbredun 12:406f75196a12 100 while (true) {
ruslanbredun 12:406f75196a12 101 timer1.reset();
ruslanbredun 12:406f75196a12 102
ruslanbredun 12:406f75196a12 103 for (int i = 0; i < sensorsFound; i++) {
ommpy 10:0b7f23df690a 104 ds1820[i]->startConversion();
ruslanbredun 12:406f75196a12 105 wait_ms(1);
ommpy 10:0b7f23df690a 106 //temp_one_value = ds1820[i]->read();
ommpy 10:0b7f23df690a 107 //temp_two_value = i;
ommpy 10:0b7f23df690a 108 }
ruslanbredun 12:406f75196a12 109
ruslanbredun 12:406f75196a12 110 US_sensor_left.startMeasurement ();
ruslanbredun 12:406f75196a12 111 US1_data = US_sensor_left.getDistance_cm ();
ruslanbredun 12:406f75196a12 112 wait_ms(15);
ruslanbredun 12:406f75196a12 113 US_sensor_middle.startMeasurement ();
ruslanbredun 12:406f75196a12 114 US2_data = US_sensor_middle.getDistance_cm ();
ruslanbredun 12:406f75196a12 115 wait_ms(15);
ruslanbredun 12:406f75196a12 116 US_sensor_right.startMeasurement ();
ruslanbredun 12:406f75196a12 117 US3_data = US_sensor_right.getDistance_cm ();
ruslanbredun 12:406f75196a12 118 wait_ms(15);
ruslanbredun 12:406f75196a12 119 IR1_data = IR_sensor_left.checkObstacle ();
ruslanbredun 12:406f75196a12 120 IR2_data = IR_sensor_right.checkObstacle ();
ommpy 10:0b7f23df690a 121
ommpy 10:0b7f23df690a 122
ruslanbredun 12:406f75196a12 123 Enc_left_data = Enc_left.getAngle();
ruslanbredun 12:406f75196a12 124 Enc_right_data = Enc_right.getAngle();
ruslanbredun 12:406f75196a12 125
ruslanbredun 12:406f75196a12 126 Lift_IR1 = Lift1.read();
ruslanbredun 12:406f75196a12 127 Lift_IR2 = Lift2.read();
ruslanbredun 12:406f75196a12 128
ruslanbredun 12:406f75196a12 129 time = timer1.read();
ruslanbredun 12:406f75196a12 130
ruslanbredun 12:406f75196a12 131 if (ds1820[0]->isPresent() ) {
ruslanbredun 12:406f75196a12 132 //pc.printf("temp[%d] = %3.1f%cC\r\n", 0, ds1820[0]->read(), 176); // read temperature
ruslanbredun 12:406f75196a12 133 temp_one_value = ds1820[0]->read();
ruslanbredun 12:406f75196a12 134 }
ruslanbredun 12:406f75196a12 135 if (ds1820[1]->isPresent() ) {
ruslanbredun 12:406f75196a12 136 //pc.printf("temp[%d] = %3.1f%cC\r\n", 1, ds1820[1]->read(), 176); // read temperature
ruslanbredun 12:406f75196a12 137 temp_two_value = ds1820[1]->read();
ruslanbredun 12:406f75196a12 138 }
ruslanbredun 12:406f75196a12 139 //if(sendFlag) {
ruslanbredun 12:406f75196a12 140 Select2 = 1;
ruslanbredun 12:406f75196a12 141 RS2.printf ("%d_%d_%d_%d_%d_%d_%d_%3.1f_%3.1f_%3.1f_%3.1f_%f\r\n", US1_data, US2_data, US3_data, IR1_data, IR2_data, Lift_IR1, Lift_IR2, temp_one_value, temp_two_value, Enc_right_data, Enc_left_data, time); //,(int)((Vcc -24 ) * 5 + 50));
ruslanbredun 12:406f75196a12 142 wait_ms(5);
ruslanbredun 12:406f75196a12 143 sendFlag = false;
ruslanbredun 12:406f75196a12 144 Select2 = 0;
ruslanbredun 12:406f75196a12 145 // }
ruslanbredun 12:406f75196a12 146 }
ommpy 6:a760ce6defbe 147 #endif
ruslanbredun 12:406f75196a12 148
ruslanbredun 12:406f75196a12 149 #if TEST_REQUEST
ruslanbredun 12:406f75196a12 150
ruslanbredun 12:406f75196a12 151 while (true) {
ruslanbredun 12:406f75196a12 152 // if(RS1.readable()) {
ruslanbredun 12:406f75196a12 153 // Select1 = 1;
ruslanbredun 12:406f75196a12 154 // RS1.putc(RS1.getc());
ruslanbredun 12:406f75196a12 155 // wait_ms (1000);
ruslanbredun 12:406f75196a12 156 // Select1 = 0;
ruslanbredun 12:406f75196a12 157 // }else{
ruslanbredun 12:406f75196a12 158 Select1 = 1;
ruslanbredun 12:406f75196a12 159 RS1.printf ("nothing \n");
ruslanbredun 12:406f75196a12 160 wait_ms (5);
ruslanbredun 12:406f75196a12 161 Select1 = 0;
ruslanbredun 12:406f75196a12 162 wait_ms (1000);
ruslanbredun 12:406f75196a12 163 //}
ruslanbredun 12:406f75196a12 164 }
ruslanbredun 12:406f75196a12 165
ruslanbredun 12:406f75196a12 166 #endif
ruslanbredun 9:859bcb293e46 167 }