Prototyp V2

Dependencies:   PM2_Libary

Branch:
michi
Revision:
38:c2663f7dcccb
Parent:
34:9f779e91168e
Child:
40:e32c57763d92
--- a/main.cpp	Sun Apr 10 19:40:59 2022 +0200
+++ b/main.cpp	Wed Apr 13 09:10:19 2022 +0200
@@ -12,15 +12,14 @@
 void user_button_released_fcn();
 
 // while loop gets executed every main_task_period_ms milliseconds
-int main_task_period_ms = 30;   // define main task period time in ms e.g. 50 ms -> main task runns 20 times per second
+int main_task_period_ms = 30;   // define main task period time in ms e.g. 30 ms -> main task runns ~33,33 times per second
 Timer main_task_timer;          // create Timer object which we use to run the main task every main task period time in ms
 
 // Sharp GP2Y0A41SK0F, 4-40 cm IR Sensor
-float ir_distance_mV = 0.0f;    // define variable to store measurement
+float ir_distance_mV = 0.0f;    // define variable to store measurement from infrared distancesensor in mVolt
 AnalogIn ir_analog_in(PC_2);    // create AnalogIn object to read in infrared distance sensor, 0...3.3V are mapped to 0...1
 
 
-
 // 78:1, 100:1, ... Metal Gearmotor 20Dx44L mm 12V CB
 DigitalOut enable_motors(PB_15);    // create DigitalOut object to enable dc motors
 
@@ -40,7 +39,7 @@
 float counts_per_turn_wheels = 2000.0f * 100.0f;    // define counts per turn at gearbox end (counts/turn * gearratio) for wheels
 float counts_per_turn_arm = 2000.0f * 100.0f;      // define counts per turn at gearbox end (counts/turn * gearratio) for arm
 float kn = 180.0f / 12.0f;                  // define motor constant in rpm per V
-float k_gear = 100.0f / 78.125f;            // define additional ratio in case you are using a dc motor with a different gear box, e.g. 100:1
+float k_gear = 100.0f / 78.125f;            // define additional ratio in case you are using a dc motor with a different gear box, e.g. 100:1 (DC with 100:1 has 256'000 turns for 360°)
 float kp = 0.1f;                            // define custom kp, this is the default speed controller gain for gear box 78.125:1
 
 //motors for tracks
@@ -54,9 +53,6 @@
 //PositionController positionController_M3(counts_per_turn * k_gear, kn / k_gear, kp * k_gear, max_voltage, pwm_M3, encoder_M3); // parameters adjusted to 100:1 gear, we need a different speed controller gain here
 
 
-// LSM9DS1 IMU, carefull: not all PES boards have an imu (chip shortage)
-// LSM9DS1 imu(PC_9, PA_8); // create LSM9DS1 comunication object, if you want to be able to use the imu you need to #include "LSM9DS1_i2c.h"
-
 //Platzhalter Variabeln für die Positionierung
 float PositionStair    = 0.2;
 float PositionBackOff  = -0.5;
@@ -65,38 +61,30 @@
 int ToNextFunction = 0;
 float max_speed_rps = 0.5f;  
 
+
 int StartPosition(float deg){
-
     positionController_M_Arm.setDesiredRotation(deg);
-
     return NULL;
 }
+
+
 //Drives forward into the next step
 int Drive(float dist){
-
 float distance;
-
 distance=dist;
-
-
-    positionController_M_right.setDesiredRotation(distance,max_speed_rps);
-    positionController_M_left.setDesiredRotation(distance,max_speed_rps);
-
-
-    return 0;   
+positionController_M_right.setDesiredRotation(distance,max_speed_rps);
+positionController_M_left.setDesiredRotation(distance,max_speed_rps);
+return 0;   
 }
 
 //only turns the arm until the robot is on the next step
 //not yet clear if the motor controler function drives to a absolute poition or if it drives the given distance relative to the current position
 int LiftUp(float deg){
-
     int8_t i = 0;         //prov condition variable
-    
-        positionController_M_Arm.setDesiredRotation(deg);
-        
-    
+    positionController_M_Arm.setDesiredRotation(deg);
     return 0;
 }
+
 //pow function is here so we dont have to use the math.h library
 //it takes 2 arguments the base can be any negative or positive floating point number the power has to be a hos to be an "integer" defined as a double
 double powerx(double base, double pow2){
@@ -115,7 +103,6 @@
     else{
     for(double i=1; i<=power; i++){
     result *= basis;}}
-
     return result;
     }
 
@@ -144,13 +131,8 @@
 
          ir_distance_mV = 1.0e3f * ir_analog_in.read() * 3.3f;
         
-        // printf("test pow function 2 ^ 2 %lf\n",powerx(2,2));
-         //printf("test mapping function %f\n", mapping(ir_distance_mV));
 
-         //printf("IR sensor (mV): %3.3f\n", ir_distance_mV);
-        
-
-       switch (ToNextFunction) {
+        switch (ToNextFunction) {
         case 1: StartPosition(degArmStart);
             printf("Case 1: Position ARM (rot): %3.3f\n",positionController_M_Arm.getRotation());
              //   ToNextFunction+=1;
@@ -175,9 +157,6 @@
             break;  
             default:  ;
         } 
-
-    
-    
     }
        // read timer and make the main thread sleep for the remaining time span (non blocking)
         int main_task_elapsed_time_ms = std::chrono::duration_cast<std::chrono::milliseconds>(main_task_timer.elapsed_time()).count();