car_test

Dependencies:   APDS_9960 AutomationElements ESP8266 HALLFX_ENCODER HCSR04 MotorDriver PID

Fork of car_test by 涂 桂旺

Revision:
2:35738c77d454
Parent:
0:d4b2a035ffe3
--- a/main.cpp	Fri Jun 23 14:21:38 2017 -0500
+++ b/main.cpp	Sat Nov 25 02:04:08 2017 +0000
@@ -1,3 +1,286 @@
+#include "mbed.h"
+
+#include "HALLFX_ENCODER.h"
+#include "MotorDriver.h"
+
+#include "HCSR04.h"
+#include "AutomationElements.h"
+
+#include "glibr.h"
+
+Thread thread;
+DigitalOut led1(LED1);
+volatile bool running = true;
+
+//----------------------motor
+MotorDriver mtrR(PA_0, PA_4, PA_1, 10000.0, true); // in1, in2, pwm, pwmFreq, isBrakeable
+MotorDriver mtrL(PC_1, PC_0, PB_0, 10000.0, true); // in1, in2, pwm, pwmFreq, isBrakeable
+HALLFX_ENCODER encR(PB_3);
+HALLFX_ENCODER encL(PB_5);
+
+//------------------------hc-sr04
+Serial pc(USBTX, USBRX);
+HCSR04 sensor(PA_6, PA_7);
+float sampleTime = 0.1;
+PT1 filter(1, 2, sampleTime);
+Timer timer;
+float distance;
+float filteredDistance; 
+
+//----------------------------GSensor APDS-9960
+glibr GSensor(PB_9,PB_8);//i2c
+int ge_diff;//gesture differentiate
+
+Thread thread_sonar;
+Thread thread_motor;
+Thread thread_gsensor;
+
+int txlength_sonar;
+int txlength_motor;
+int txlength_gsensor;
+
+char txbuf_sonar[256];
+char txbuf_motor[256];
+char txbuf_gsensor[256];
+
+Thread thread_pc_send;
+void pc_send_Thread(){
+    while(true)
+    {
+        if(txlength_sonar>0)
+        {
+            puts(txbuf_sonar);
+            memset(&txbuf_sonar,0,256);
+            txlength_sonar=0;
+        }
+        else if(txlength_motor>0)
+        {
+            puts(txbuf_motor);
+            memset(&txbuf_motor,0,256);
+            txlength_motor=0;
+        }
+        else if(txlength_gsensor>0)
+        {
+            puts(txbuf_gsensor);
+            memset(&txbuf_gsensor,0,256);
+            txlength_gsensor=0;
+            led1=!led1;
+        }
+        //wait_ms(50); 
+    }
+}
+//void motorThread(void const *argument){
+void motorThread(){
+    pc.printf("motor : start.....\r\n");
+    encL.reset();
+    encR.reset();
+    while(true)
+    {
+         switch ( ge_diff ) 
+         {        // gesture differentiate
+                case DIR_UP:
+                    mtrL.forceSetSpeed(0.1);
+                    mtrR.forceSetSpeed(0.1);  
+                    break;
+                case DIR_DOWN:
+                    mtrL.forceSetSpeed(-0.1);
+                    mtrR.forceSetSpeed(-0.1);  
+                    break;
+                case DIR_LEFT:
+                    mtrL.forceSetSpeed(-0.1);
+                    mtrR.forceSetSpeed(0.1);  
+                    break;
+                case DIR_RIGHT:
+                    mtrL.forceSetSpeed(0.1);
+                    mtrR.forceSetSpeed(-0.1);  
+                    break;
+                case DIR_NEAR:
+                    mtrL.forceSetSpeed(0);
+                    mtrR.forceSetSpeed(0);  
+                    break;
+                case DIR_FAR:
+                    mtrL.forceSetSpeed(0.1);
+                    mtrR.forceSetSpeed(0.1);  
+                    break;
+                default:
+                    if(filteredDistance>2 && filteredDistance <=25)
+                    {
+                        mtrL.forceSetSpeed(-0.1);
+                        mtrR.forceSetSpeed(0.1); 
+                    }
+                    else if( filteredDistance>2 && filteredDistance <400)
+                    {
+                        mtrL.forceSetSpeed(0.1);
+                        mtrR.forceSetSpeed(0.1);  
+                    }
+                    else
+                    {
+                        mtrL.forceSetSpeed(0);
+                        mtrR.forceSetSpeed(0);  
+                    }
+                    break;
+        }
+        
+        /*
+        // Set motor speed in open loop mode
+        // Motor direction based on working setpoint var
+        int dirL, dirR;
+        if(working_setpoint < 0.0){
+             dirL = -1; dirR = -1;
+        }
+        else{
+            dirL = 1; dirR = 1;
+        }
+        float speed = abs(working_setpoint) / 90.0; // Normalize based on 90 RPM
+        mtrL.forceSetSpeed(speed * dirL);
+        mtrR.forceSetSpeed(speed * dirR);
+        */
+        wait(0.1);
+        if(ge_diff!=DIR_NEAR)ge_diff=DIR_NONE;
+    }
+}
+
+//void sonarThread(void const *argument){
+void sonarThread(){  
+//int t_ms=0;  
+    sensor.setRanges(2, 400);
+    pc.printf("Minimum sensor range = %g cm\n\rMaximum sensor range = %g cm\n\r", sensor.getMinRange(), sensor.getMaxRange());
+    pc.printf("Sensor:       Filtered:\n\r");
+    while(true) {
+        led1=1;
+        timer.reset();
+        timer.start();
+        sensor.startMeasurement();
+        
+        /*
+        while(!sensor.isNewDataReady()) {
+        // waiting time depends on the distance
+        // wait for new data
+        }
+        */
+        wait_ms(50);
+        
+        distance = sensor.getDistance_cm();
+        filter.in(distance);
+        filteredDistance = filter.out();
+        //pc.printf("%7.1f cm  %7.1f cm\n\r", distance, filteredDistance);
+        sprintf(txbuf_sonar,"sensor : %7.1f cm  %7.1f cm\n\r", distance, filteredDistance);
+        txlength_sonar=8;
+        //timer.stop();
+        //t_ms=timer.read_ms();
+        //if(t_ms<100)wait_ms(sampleTime * 1000 - timer.read_ms()); // time the loop
+        led1=0;
+    }
+}
+
+//void gsensorThread(void const *argument){
+void gsensorThread(){    
+    // Initialize Sensor with I2C
+    if ( GSensor.ginit() ) {
+        pc.printf("APDS-9960 initialization complete\r\n");
+    } else {
+        pc.printf("Something went wrong during APDS-9960 init\r\n");
+    }
+
+    // Start running the APDS-9960 gesture sensor engine
+    if ( GSensor.enableGestureSensor(true) ) {
+        pc.printf("Gesture sensor is now running\r\n");
+    } else {
+        pc.printf("Something went wrong during gesture sensor init!\r\n");
+    }
+    
+    while(1) {
+        if ( GSensor.isGestureAvailable() ) {         // gesture detect
+            
+            switch ( GSensor.readGesture() ) {        // gesture differentiate
+                case DIR_UP:
+                    ge_diff=DIR_UP;
+                    //pc.printf("UP\r\n");
+                    sprintf(txbuf_gsensor,"GSensor : UP\r\n");
+                    txlength_gsensor=16;
+                    break;
+                case DIR_DOWN:
+                    ge_diff=DIR_DOWN;
+                    //pc.printf("DOWN\r\n");
+                    sprintf(txbuf_gsensor,"GSensor : DOWN\r\n");
+                    txlength_gsensor=18;
+                    break;
+                case DIR_LEFT:
+                    ge_diff=DIR_LEFT;
+                    //pc.printf("LEFT\r\n");
+                    sprintf(txbuf_gsensor,"GSensor : LEFT\r\n");
+                    txlength_gsensor=18;
+                    break;
+                case DIR_RIGHT:
+                    ge_diff=DIR_RIGHT;
+                    //pc.printf("RIGHT\r\n");
+                    sprintf(txbuf_gsensor,"GSensor : RIGHT\r\n");
+                    txlength_gsensor=19;
+                    break;
+                case DIR_NEAR:
+                    ge_diff=DIR_NEAR;
+                    //pc.printf("NEAR\r\n");
+                    sprintf(txbuf_gsensor,"GSensor : NEAR\r\n");
+                    txlength_gsensor=18;
+                    break;
+                case DIR_FAR:
+                    ge_diff=DIR_FAR;
+                    //pc.printf("FAR\r\n");
+                    sprintf(txbuf_gsensor,"GSensor : FAR\r\n");
+                    txlength_gsensor=17;
+                    break;
+                default:
+                    //ge_diff=DIR_NONE;
+                    //pc.printf("NONE\r\n");
+                    break;
+            }
+        }
+    } 
+}
+// Blink function toggles the led in a long running loop
+void blink(DigitalOut *led) {
+    while (running) {
+        *led = !*led;
+        wait(1);
+    }
+}
+void callback_ex() {
+    // Note: you need to actually read from the serial to clear the RX interrupt
+    int tmp=pc.getc();
+    //printf("%c\n", tmp);
+}
+// Spawns a thread to run blink for 5 seconds
+int main() {
+    pc.baud(9600);
+    pc.attach(&callback_ex);
+    thread_pc_send.start(callback(pc_send_Thread));
+    
+    thread.start(callback(blink, &led1));
+    
+    wait(5);
+    running = false;
+    thread.join();
+    
+    thread_gsensor.start(callback(gsensorThread));
+    wait(1);
+    thread_motor.start(callback(motorThread));
+    wait(1);
+    //thread_sonar.start(callback(sonarThread));
+    
+    //Thread thread_sonar(sonarThread);
+}
+
+/*
+主程序指定中断函数
+flipper.attach(&flip, 2.0); // the address of the function to be attached (flip) and the interval (2 seconds)
+
+主程序指定 类 的 方法
+t.attach(callback(&f, &Flipper::flip), 2.0); // the address of the object, member function, and interval
+
+
+1、线程
+需加载mbed-os
+
 #include "mbed.h"
 
 Thread thread;
@@ -18,4 +301,188 @@
     wait(5);
     running = false;
     thread.join();
-}
\ No newline at end of file
+}
+
+
+2、休眠+按键中断唤醒
+需更新mbed
+使用F401板时,IDD电流测试,运行时:18mA,灯亮时21 .2mA,睡眠时:6.26 mA,深度睡眠时:0.68 mA,
+
+RTC唤醒使用第三方类(未测试)
+
+#include "mbed.h"
+
+InterruptIn event(USER_BUTTON);
+DigitalOut myled(LED1);
+
+int go_to_sleep = 0;
+
+void pressed()
+{
+    printf("Button pressed\n");
+    go_to_sleep = go_to_sleep + 1;
+    if (go_to_sleep > 3) go_to_sleep = 0;
+
+}
+
+int main()
+{
+    int i = 0;
+
+    printf("\nPress Button to enter/exit sleep & deepsleep\n");
+
+    event.fall(&pressed);
+
+    while (1) {
+
+        if ((go_to_sleep == 0) || (go_to_sleep == 2)) {
+            printf("%d: Running\n", i);
+            myled = !myled;
+            wait(1.0);
+        }
+
+        if (go_to_sleep == 1) {
+            myled = 0;
+            printf("%d: Entering sleep (press user button to resume)\n", i);
+            sleep();
+        }
+
+        if (go_to_sleep == 3) {
+            myled = 0;
+            printf("%d: Entering deepsleep (press user button to resume)\n", i);
+            deepsleep();
+        }
+
+        i++;
+    }
+}
+
+
+3、系统定时器中断
+#include "mbed.h"
+
+Ticker toggle_led_ticker;
+
+DigitalOut led1(LED1);
+
+void toggle_led() {
+    led1 = !led1;
+}
+
+int main() {
+    // Init the ticker with the address of the function (toggle_led) to be attached and the interval (100 ms)
+    toggle_led_ticker.attach(&toggle_led, 0.1);
+    while (true) {
+        // Do other things...
+    }
+}
+
+4、超时定时器中断
+#include "mbed.h"
+ 
+// A class for flip()-ing a DigitalOut 
+class Flipper {
+public:
+    Flipper(PinName pin) : _pin(pin) {
+        _pin = 0;
+    }
+    void flip() {
+        _pin = !_pin;
+    }
+private:
+    DigitalOut _pin;
+};
+ 
+DigitalOut led1(LED1);
+Flipper f(LED2);
+Timeout t;
+ 
+int main() {
+    // the address of the object, member function, and interval
+    t.attach(callback(&f, &Flipper::flip), 2.0); 
+ 
+    // spin in a main loop. flipper will interrupt it to call flip
+    while(1) {
+        led1 = !led1;
+        wait(0.2);
+    }
+}
+            
+
+5、通用定时器中断
+
+ // Count the time to toggle a LED
+ 
+ #include "mbed.h"
+ 
+ Timer timer;
+ DigitalOut led(LED1);
+ int begin, end;
+ 
+ int main() {
+     timer.start();
+     begin = timer.read_us();
+     led = !led;
+     end = timer.read_us();
+     printf("Toggle the led takes %d us", end - begin);
+ }
+
+6、外部中断附加事件
+需加载mbed-os
+
+#include "mbed.h"
+#include "mbed_events.h"
+
+DigitalOut led1(LED1);
+InterruptIn sw(SW2);
+EventQueue queue(32 * EVENTS_EVENT_SIZE);
+Thread t;
+
+void rise_handler(void) {
+    // Toggle LED
+    led1 = !led1;
+}
+
+void fall_handler(void) {
+    printf("fall_handler in context %p\r\n", Thread::gettid());
+    // Toggle LED
+    led1 = !led1;
+}
+
+int main() {
+    // Start the event queue
+    t.start(callback(&queue, &EventQueue::dispatch_forever));
+    printf("Starting in context %p\r\n", Thread::gettid());
+    // The 'rise' handler will execute in IRQ context
+    sw.rise(rise_handler);
+    // The 'fall' handler will execute in the context of thread 't'
+    sw.fall(queue.event(fall_handler));
+}
+
+
+7、线程间信号量的传递
+需加载mbed-os
+
+#include "mbed.h"
+ 
+Thread thread;
+DigitalOut led(LED1);
+ 
+void led_thread() {
+    while (true) {
+        // Signal flags that are reported as event are automatically cleared.
+        Thread::signal_wait(0x1);
+        led = !led;
+    }
+}
+ 
+int main (void) {
+    thread.start(callback(led_thread));
+ 
+    while (true) {
+        wait(1);
+        thread.signal_set(0x1);
+    }
+}
+
+*/