Hauptprogramm
Dependencies: ILI9340_Driver_Lib PM2_Libary Lib_DFPlayerMini
Diff: main.cpp
- Revision:
- 12:dfa3591affef
- Parent:
- 11:be62f37f3a98
- Child:
- 13:096e5dc3ac23
--- a/main.cpp Wed Apr 14 13:12:13 2021 +0000 +++ b/main.cpp Wed Apr 14 14:23:47 2021 +0000 @@ -1,9 +1,10 @@ +/*Zeitinput am Anfang: Startzeit 8:00*/ + +#include <I2C.h> #include "mbed.h" #include "platform/mbed_thread.h" - - - +#include "mbed_rtc_time.h" /* PM2_Libary */ #include "EncoderCounter.h" @@ -16,6 +17,7 @@ InterruptIn user_button(USER_BUTTON); DigitalOut led(LED1); + bool executeMainTask = false; Timer user_button_timer, loop_timer; int Ts_ms = 50; @@ -24,74 +26,59 @@ void button_fall(); void button_rise(); + /* create analog input object */ -AnalogIn analogIn(PC_2); +/*AnalogIn analogIn(PC_2); float dist = 0.0f; - -/* create enable dc motor digital out object */ -DigitalOut enable_motors(PB_15); -/* create pwm objects */ -FastPWM pwmOut_M1(PB_13); -FastPWM pwmOut_M2(PA_9); -FastPWM pwmOut_M3(PA_10); -double Ts_pwm_s = 0.00005; // this needs to be a double value (no f at the end) -/* create encoder read objects */ -EncoderCounter encoderCounter_M1(PA_6, PC_7); -EncoderCounter encoderCounter_M2(PB_6, PB_7); -EncoderCounter encoderCounter_M3(PA_0, PA_1); -/* create speed controller objects, only M1 and M2, M3 is used open-loop */ -float counts_per_turn = 20.0f*78.125f; // counts/turn * gearratio -float kn = 180.0f/12.0f; // (RPM/V) -float max_voltage = 12.0f; // adjust this to 6.0f if only one batterypack is used -SpeedController speedController_M1(counts_per_turn, kn, max_voltage, pwmOut_M1, encoderCounter_M1); -SpeedController speedController_M2(counts_per_turn, kn, max_voltage, pwmOut_M2, encoderCounter_M2); - +*/ /* create servo objects */ -Servo servo_S1(PB_2); +/*Servo servo_S1(PB_2); Servo servo_S2(PC_8); // Servo servo_S3(PC_6); // not needed in this example int servoPeriod_mus = 20000; int servoOutput_mus_S1 = 0; int servoOutput_mus_S2 = 0; -int servo_counter = 0; +int servo_counter = 0;*/ int loops_per_second = static_cast<int>(ceilf(1.0f/(0.001f*(float)Ts_ms))); int main() { + set_time(1618332129); // Set RTC time to Wed, 28 Oct 2009 11:35:37 user_button.fall(&button_fall); user_button.rise(&button_rise); loop_timer.start(); - /* enable hardwaredriver dc motors */ - enable_motors = 1; - /* initialize pwm for motor M3*/ - pwmOut_M3.period(Ts_pwm_s); - /* set pwm output zero at the beginning, range: 0...1 -> u_min...u_max */ - pwmOut_M3.write(0.5); /* enable servos, you can also disable them */ - servo_S1.Enable(servoOutput_mus_S1, servoPeriod_mus); - servo_S2.Enable(servoOutput_mus_S2, servoPeriod_mus); + //servo_S1.Enable(servoOutput_mus_S1, servoPeriod_mus); + //servo_S2.Enable(servoOutput_mus_S2, servoPeriod_mus); while (true) { loop_timer.reset(); + + - /* ------------- start hacking ------------- -------------*/ + if (executeMainTask) { + time_t seconds = time(NULL); + + printf("Time as seconds since January 1, 1970 = %u\n", (unsigned int)seconds); + + printf("Time as a basic string = %s", ctime(&seconds)); + + char buffer[32]; + strftime(buffer, 32, "%I:%M %p\n", localtime(&seconds)); + printf("Time as a custom formatted string = %s", buffer); + + ThisThread::sleep_for(50); /* read analog input */ - dist = analogIn.read() * 3.3f; - - /* command a speed to dc motors M1 and M2*/ - speedController_M1.setDesiredSpeedRPS( 1.0f); - speedController_M2.setDesiredSpeedRPS(-0.5f); - /* write output voltage to motor M3 */ - pwmOut_M3.write(0.75); + //dist = analogIn.read() * 3.3f; /* command servo position via output time, this needs to be calibrated */ - servo_S1.SetPosition(servoOutput_mus_S1); + /*servo_S1.SetPosition(servoOutput_mus_S1); servo_S2.SetPosition(servoOutput_mus_S2); if (servoOutput_mus_S1 <= servoPeriod_mus & servo_counter%loops_per_second == 0 & servo_counter != 0) { servoOutput_mus_S1 += 100; @@ -99,37 +86,30 @@ if (servoOutput_mus_S2 <= servoPeriod_mus & servo_counter%loops_per_second == 0 & servo_counter != 0) { servoOutput_mus_S2 += 100; } - servo_counter++; + servo_counter++;*/ /* visual feedback that the main task is executed */ led = !led; } else { - dist = 0.0f; + //dist = 0.0f; - speedController_M1.setDesiredSpeedRPS(0.0f); - speedController_M2.setDesiredSpeedRPS(0.0f); - pwmOut_M3.write(0.5); - - servoOutput_mus_S1 = 0; - servoOutput_mus_S2 = 0; - servo_S1.SetPosition(servoOutput_mus_S1); - servo_S2.SetPosition(servoOutput_mus_S2); + //servoOutput_mus_S1 = 0; + //servoOutput_mus_S2 = 0; + //servo_S1.SetPosition(servoOutput_mus_S1); + //servo_S2.SetPosition(servoOutput_mus_S2); led = 0; } /* do only output via serial what's really necessary (this makes your code slow)*/ - printf("%3.3f, %3d, %3d, %3d, %3.3f, %3.3f;\r\n", - dist, - servoOutput_mus_S1, - servoOutput_mus_S2, - encoderCounter_M3.read(), - speedController_M1.getSpeedRPS(), - speedController_M2.getSpeedRPS()); + //printf("%3.3f, %3d;\r\n", + //dist, + //servoOutput_mus_S1, + //servoOutput_mus_S2); + - /* ------------- stop hacking ------------- -------------*/ int T_loop_ms = duration_cast<milliseconds>(loop_timer.elapsed_time()).count(); int dT_loop_ms = Ts_ms - T_loop_ms;