Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: mbed Watchdog stm32-sensor-base2
main.cpp@7:2f218add711e, 2020-07-23 (annotated)
- Committer:
- ommpy
- Date:
- Thu Jul 23 11:34:08 2020 +0000
- Revision:
- 7:2f218add711e
- Parent:
- 6:a760ce6defbe
- Child:
- 8:c3cffab85b0d
us and ir for demo
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
ommpy | 0:d383e2dee0f7 | 1 | #include <global.h> |
ommpy | 0:d383e2dee0f7 | 2 | |
ommpy | 7:2f218add711e | 3 | //Serial pc(UART1_TX, UART1_RX); |
ommpy | 6:a760ce6defbe | 4 | RS485 RS485(UART2_TX,UART2_RX,DE_TXD_2); // Tx, Rx , !RE and DE MAX485 pin |
ommpy | 6:a760ce6defbe | 5 | |
ommpy | 7:2f218add711e | 6 | Serial pc(USBTX, USBRX); |
nestedslk | 4:f6e22dd39313 | 7 | Timer timer; |
ommpy | 6:a760ce6defbe | 8 | typedef uint8_t byte; |
ommpy | 0:d383e2dee0f7 | 9 | |
ommpy | 6:a760ce6defbe | 10 | DigitalOut select(DE_TXD_2); |
ommpy | 6:a760ce6defbe | 11 | byte full_value[9]; |
ommpy | 6:a760ce6defbe | 12 | byte base_data[4] = {0xAA,0x55,0x03,0x01}; |
ommpy | 6:a760ce6defbe | 13 | byte data[9] = {0x01,0x04,0x00,0x48,0x00,0x02,0xf1,0xdd};//your data |
ommpy | 6:a760ce6defbe | 14 | |
ommpy | 6:a760ce6defbe | 15 | char test_buffer[10]; |
ommpy | 6:a760ce6defbe | 16 | |
ommpy | 6:a760ce6defbe | 17 | const unsigned char CRC7_POLY = 0x91; |
ommpy | 6:a760ce6defbe | 18 | |
ommpy | 6:a760ce6defbe | 19 | unsigned char getCRC(unsigned char message[], unsigned char length) |
ommpy | 6:a760ce6defbe | 20 | { |
ommpy | 6:a760ce6defbe | 21 | unsigned char i, j, crc = 0; |
ommpy | 6:a760ce6defbe | 22 | |
ommpy | 6:a760ce6defbe | 23 | for (i = 0; i < length; i++) |
ommpy | 6:a760ce6defbe | 24 | { |
ommpy | 6:a760ce6defbe | 25 | crc ^= message[i]; |
ommpy | 6:a760ce6defbe | 26 | for (j = 0; j < 8; j++) |
ommpy | 6:a760ce6defbe | 27 | { |
ommpy | 6:a760ce6defbe | 28 | if (crc & 1) |
ommpy | 6:a760ce6defbe | 29 | crc ^= CRC7_POLY; |
ommpy | 6:a760ce6defbe | 30 | crc >>= 1; |
ommpy | 6:a760ce6defbe | 31 | } |
ommpy | 6:a760ce6defbe | 32 | } |
ommpy | 6:a760ce6defbe | 33 | return crc; |
ommpy | 6:a760ce6defbe | 34 | } |
ommpy | 6:a760ce6defbe | 35 | |
ommpy | 6:a760ce6defbe | 36 | |
nestedslk | 4:f6e22dd39313 | 37 | int main() |
nestedslk | 4:f6e22dd39313 | 38 | { |
nestedslk | 4:f6e22dd39313 | 39 | DigitalOut led(DEBUG_LED); |
nestedslk | 4:f6e22dd39313 | 40 | DigitalOut led2(DE_TXD_1, 1); // activate transmitting rs485-1 |
ommpy | 6:a760ce6defbe | 41 | |
ommpy | 0:d383e2dee0f7 | 42 | |
ommpy | 0:d383e2dee0f7 | 43 | #if TEST_ULTRASONIC |
nestedslk | 4:f6e22dd39313 | 44 | int time_to_check_us = 1000; |
ommpy | 0:d383e2dee0f7 | 45 | JSN_SR04 sensor1(TIM1_CH2, TRIG_PA8_OUT); |
nestedslk | 4:f6e22dd39313 | 46 | // JSN_SR04 sensor1(TIM1_CH2, TRIG_PB14_OUT); //no triger signal |
nestedslk | 4:f6e22dd39313 | 47 | // JSN_SR04 sensor1(TIM1_CH2, TRIG_PB15_OUT); |
nestedslk | 4:f6e22dd39313 | 48 | sensor1.setRanges(30, 200); |
nestedslk | 4:f6e22dd39313 | 49 | // sensor2.setRanges(30, 200); |
nestedslk | 4:f6e22dd39313 | 50 | // sensor3.setRanges(30, 200); |
nestedslk | 4:f6e22dd39313 | 51 | // pc.printf("Min. range = %g cm\n\r",sensor1.getMinRange()); |
ommpy | 0:d383e2dee0f7 | 52 | while(true) { |
nestedslk | 4:f6e22dd39313 | 53 | timer.reset(); |
nestedslk | 4:f6e22dd39313 | 54 | timer.start(); |
nestedslk | 4:f6e22dd39313 | 55 | sensor1.startMeasurement(); |
nestedslk | 5:97117a837d2c | 56 | //while (sensor1.isNewDataReady() == false && timer.read_ms() < time_to_check_us) { |
nestedslk | 5:97117a837d2c | 57 | //pc.printf("Distance1: %5.1f mm -- Distance2: %5.1f mm -- -- Distance3: %5.1f mm \r\n", sensor1.getDistance_cm()), sensor2.getDistance_cm(), sensor3.getDistance_cm()); |
nestedslk | 4:f6e22dd39313 | 58 | pc.printf("Distance1: %5.1f mm \r\n", sensor1.getDistance_cm()); |
ommpy | 6:a760ce6defbe | 59 | |
nestedslk | 4:f6e22dd39313 | 60 | |
nestedslk | 4:f6e22dd39313 | 61 | timer.stop(); |
ommpy | 6:a760ce6defbe | 62 | wait_ms(2); |
nestedslk | 4:f6e22dd39313 | 63 | |
nestedslk | 4:f6e22dd39313 | 64 | } |
nestedslk | 4:f6e22dd39313 | 65 | |
ommpy | 0:d383e2dee0f7 | 66 | #endif |
ommpy | 0:d383e2dee0f7 | 67 | |
ommpy | 0:d383e2dee0f7 | 68 | #if TEST_ENCODERS |
nestedslk | 4:f6e22dd39313 | 69 | int min1_value = 2000; |
nestedslk | 4:f6e22dd39313 | 70 | int max1_value = 0; |
nestedslk | 4:f6e22dd39313 | 71 | AS5045 encoder_1(SP1_NSS1); |
nestedslk | 4:f6e22dd39313 | 72 | AS5045 encoder_2(SP1_NSS2); |
nestedslk | 4:f6e22dd39313 | 73 | while(1) { |
nestedslk | 4:f6e22dd39313 | 74 | led = !led; |
nestedslk | 5:97117a837d2c | 75 | double encoder_1_Value = encoder_1.getPosition(); |
nestedslk | 4:f6e22dd39313 | 76 | wait_ms(30); |
nestedslk | 5:97117a837d2c | 77 | double encoder_2_Value = encoder_2.getPosition(); |
nestedslk | 4:f6e22dd39313 | 78 | wait_ms(30); |
nestedslk | 4:f6e22dd39313 | 79 | //encoder_1_Value = |
nestedslk | 4:f6e22dd39313 | 80 | //if( encoder_1_Value.IsValid() && encoder_2_Value.IsValid() ) |
nestedslk | 5:97117a837d2c | 81 | |
nestedslk | 5:97117a837d2c | 82 | pc.printf("Sensor Values = %f --- %f \n\r",encoder_1_Value, encoder_2_Value ); // |
nestedslk | 4:f6e22dd39313 | 83 | //else |
nestedslk | 4:f6e22dd39313 | 84 | //pc.printf("Invalid data read"); |
ommpy | 0:d383e2dee0f7 | 85 | |
nestedslk | 4:f6e22dd39313 | 86 | //wait_ms(50); |
nestedslk | 4:f6e22dd39313 | 87 | } |
nestedslk | 4:f6e22dd39313 | 88 | |
nestedslk | 4:f6e22dd39313 | 89 | #endif |
ommpy | 0:d383e2dee0f7 | 90 | |
ommpy | 0:d383e2dee0f7 | 91 | # if TEST_IR |
nestedslk | 5:97117a837d2c | 92 | PwmIn a(PB_4); |
nestedslk | 4:f6e22dd39313 | 93 | //E18_D80NK infared1 (IR1_PB12_OUT); |
nestedslk | 4:f6e22dd39313 | 94 | // E18_D80NK infared2 (IR2_PB13_OUT); |
nestedslk | 5:97117a837d2c | 95 | while (true) { |
nestedslk | 5:97117a837d2c | 96 | // pc.printf ("Is there any obstacle: %d ---- %d ", infared1.checkObstacle(),infared2.checkObstacle() ); |
nestedslk | 5:97117a837d2c | 97 | |
nestedslk | 5:97117a837d2c | 98 | pc.printf ("\n\r"); |
nestedslk | 5:97117a837d2c | 99 | } |
ommpy | 0:d383e2dee0f7 | 100 | |
nestedslk | 4:f6e22dd39313 | 101 | |
ommpy | 0:d383e2dee0f7 | 102 | #endif |
ommpy | 0:d383e2dee0f7 | 103 | |
ommpy | 6:a760ce6defbe | 104 | # if DEMO_CODE |
ommpy | 6:a760ce6defbe | 105 | |
ommpy | 6:a760ce6defbe | 106 | JSN_SR04 sensor1(TIM1_CH2, TRIG_PA8_OUT); |
ommpy | 6:a760ce6defbe | 107 | E18_D80NK infared1 (IR1_PB12_OUT); |
ommpy | 6:a760ce6defbe | 108 | E18_D80NK infared2 (IR2_PB13_OUT); |
ommpy | 7:2f218add711e | 109 | pc.baud(115200); |
ommpy | 6:a760ce6defbe | 110 | |
ommpy | 7:2f218add711e | 111 | sensor1.setRanges(10, 200); |
ommpy | 6:a760ce6defbe | 112 | |
ommpy | 6:a760ce6defbe | 113 | while(true) { |
ommpy | 6:a760ce6defbe | 114 | timer.reset(); |
ommpy | 6:a760ce6defbe | 115 | timer.start(); |
ommpy | 6:a760ce6defbe | 116 | sensor1.startMeasurement(); |
ommpy | 7:2f218add711e | 117 | //while (sensor1.isNewDataReady() == false && timer.read_ms() < time_to_check_us) { |
ommpy | 7:2f218add711e | 118 | //pc.printf("Distance1: %5.1f mm -- Distance2: %5.1f mm -- -- Distance3: %5.1f mm \r\n", sensor1.getDistance_cm()), sensor2.getDistance_cm(), sensor3.getDistance_cm()); |
ommpy | 7:2f218add711e | 119 | pc.printf("%5.1f_%d_%d \r\n", sensor1.getDistance_cm(),infared1.checkObstacle(),infared2.checkObstacle()); |
ommpy | 6:a760ce6defbe | 120 | |
ommpy | 6:a760ce6defbe | 121 | timer.stop(); |
ommpy | 7:2f218add711e | 122 | wait_ms(20); |
ommpy | 6:a760ce6defbe | 123 | |
ommpy | 6:a760ce6defbe | 124 | } |
ommpy | 7:2f218add711e | 125 | |
ommpy | 6:a760ce6defbe | 126 | |
ommpy | 6:a760ce6defbe | 127 | |
ommpy | 6:a760ce6defbe | 128 | #endif |
ommpy | 6:a760ce6defbe | 129 | |
ommpy | 0:d383e2dee0f7 | 130 | } |
ommpy | 0:d383e2dee0f7 | 131 |