Prototyp V2

Dependencies:   PM2_Libary

Branch:
Lupo_2
Revision:
71:e740ef7c7813
Parent:
70:da5754e1514c
Parent:
68:e3fc5ed0bc0e
Child:
86:56b35f01e4d4
--- a/main.cpp	Wed Apr 27 10:15:32 2022 +0200
+++ b/main.cpp	Wed Apr 27 11:08:49 2022 +0200
@@ -1,6 +1,5 @@
 #include "mbed.h"
 #include "PM2_Libary.h"
-#include <cmath>
 #include <cstdint>
 #include <cstdio>
 #include "math.h"
@@ -56,7 +55,7 @@
 // create SpeedController and PositionController objects, default parametrization is for 78.125:1 gear box
 const float max_voltage               = 12.0f;     // define maximum voltage of battery packs, adjust this to 6.0f V if you only use one batterypack
 const float counts_per_turn_wheels    = 20.0f * 78.125f;    // define counts per turn at gearbox end (counts/turn * gearratio) for wheels
-const float counts_per_turn_arm       = 20.0f * 78.125f * 10.0f;    // define counts per turn at gearbox end (counts/turn * gearratio) for arm
+const float counts_per_turn_arm       = 20.0f * 78.125f * 20.0f;    // define counts per turn at gearbox end (counts/turn * gearratio) for arm
 const float kn                        = 180.0f / 12.0f;      // define motor constant in rpm per V
 const 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 2'000 turns for 360°)
 const float kp                        = 0.1f;     // define custom kp, this is the default speed controller gain for gear box 78.125:1
@@ -73,24 +72,24 @@
 // logic functions for basic movement
 
 //placeholder variables for prototype testing
+
 const int   drive_stright_mm = 100; // placeholder for testing drives amount forward
 const int   drive_back_mm = -100; // placeholder for testing drives amount backwards
 int         ToNextFunction = 0;  // current state of the system (which function is beeing executed)
 int         state=0;
 
+
 // definition important variables
 const float   pi = 2 * acos(0.0); // definiton of pi
-const float   max_speed_rps_wheel = 0.6f;  // define maximum speed that the position controller is changig the speed for the wheels, has to be smaller or equal to kn * max_voltage
+const float   max_speed_rps_wheel = 0.5f;  // define maximum speed that the position controller is changig the speed for the wheels, has to be smaller or equal to kn * max_voltage
 const float   max_speed_rps_arm = 0.3f; // define maximum speed that the position controller is changig the speed for the arm, has to be smaller or equal to kn * max_voltage
-float         start_deg_arm = -asin((dist_arm_ground - dist_grappleratt_grappler_uk) / arm_length) * 180.0/pi ; //calculates the starting degree of the arm (gripper has to touch ground in frotn of Wall-E)
-float         current_deg_arm = start_deg_arm; // saves the current degree the arm has.
-
+float         start_deg_arm = -asin((dist_arm_ground - dist_grappleratt_grappler_uk) / arm_length) * 180.0/pi ; ///calculates the starting degree of the arm (gripper has to touch ground in frotn of Wall-E)
 // import functions from file mapping
 extern double powerx(double base, double pow2);
 extern double mapping (float adc_value_mV);
 
 // calculates the deg which the arm has to take to reach a certain height (the input height has to be the height of OK Gripper area)
-double calc_arm_deg_for_height(int height_mm)
+float calc_arm_deg_for_height(int height_mm)
 {
     float deg_arm;
     if ((height_mm - dist_arm_ground - (dist_grappleratt_grappler_uk - gripper_area_height)) > arm_length) //check if height is reachable
@@ -105,15 +104,48 @@
     return deg_arm;
 }
 
+//calculates position of arm when lift up has ended.
+//RETURN: end_deg = degree which the motor has to turn in order to reach end lift position.
+float calc_pos_end_lift()
+{
+    float end_deg;
+    end_deg = asin((dist_arm_ground-(dist_grappleratt_grappler_uk-gripper_area_height))/arm_length) + start_deg_arm;
+    end_deg = end_deg * 180 / pi;
+    return end_deg;
+}
+
 //calculates the deg which the wheels have to turn in order to cover specified distance in mm
+//RETURN: deg_wheel = degree which the motor has to turn in order to cover distance(mm)
 float wheel_dist_to_deg(int distance) // distance has to be in mm.
 {
     float deg_wheel = distance * 360 /(wheel_diameter * pi);
     return deg_wheel;
 }
 
+// increments the Motor for defined degree from the current one
+// PARAM: deg_to_turn = degree to turn the Motor
+// PARAM: current_full_rotation = the current rotation of the Motor (Motor.getRotation())
+// RETURN: new Rotation value in rotations
+float turn_relative_deg(float deg_to_turn, float current_full_rotation)
+{
+    float current_rotations = current_full_rotation;
+    float new_turn_rotation = current_rotations - deg_to_turn/360.0;
+    return new_turn_rotation;
+}
+
+// sets the Motor to a specified degree in one rotation 
+// PARAM: end_deg = new position of the arm in degree 0 <= value >=360
+// PARAM: current_rotations = the current rotation of the Motor (Motor.getRotation())
+// RETURN: new_partial_rotation = new deg value in rotations
+float turn_absolut_deg(float end_deg, float current_rotations)
+{
+    int full_rotations = current_rotations;
+    float new_partial_rotation = current_rotations - start_deg_arm/360;
+    return new_partial_rotation;
+}
+
 // bring arm in starting position. Height of stairs.
-int start_position()
+int set_arm_stair_height()
 {
     float diff;
     double deg_up_from_horizon = calc_arm_deg_for_height(height_stairs); //deg which arm motor has to turn to in order to grab stair. starting from horizontal position
@@ -123,9 +155,11 @@
         printf("Error in start_position: degree is out of bound for Start Position."); // error when desired reaching point is out of reach.
         return 2;
     }
+
+    enable_motors = 1;
     positionController_M_Arm.setDesiredRotation(deg / 360.0, max_speed_rps_arm); // command to turn motor to desired deg.
-    current_deg_arm = positionController_M_Arm.getRotation() * 360.0; //write new position to variable 
-    diff = deg-current_deg_arm;
+
+    diff = deg-(positionController_M_Arm.getRotation() * 360.0);
     if (diff<=0.3){
         return 1;
     }
@@ -133,6 +167,8 @@
         return NULL;}
 
 
+    enable_motors = 0;
+
 }
 
 //Drives forward into the next step 
@@ -142,16 +178,22 @@
     float diff_R;
     float diff_L;
     float deg_to_turn = wheel_dist_to_deg(distance);
-    positionController_M_right.setDesiredRotation(deg_to_turn / 360.0, max_speed_rps_wheel);
-    positionController_M_left.setDesiredRotation(deg_to_turn / 360.0, max_speed_rps_wheel);
+    float relativ_turns_rightmotor = turn_relative_deg(deg_to_turn, positionController_M_right.getRotation());
+    float relativ_turns_leftmotor = turn_relative_deg(deg_to_turn, positionController_M_left.getRotation());
 
- 
-    diff_R= deg_to_turn-(positionController_M_right.getRotation()*360);
-    diff_L= deg_to_turn-(positionController_M_left.getRotation()*360);
-    if (diff_R<=0.3&&diff_L<=0.3){
+    enable_motors = 1;
+    positionController_M_right.setDesiredRotation(relativ_turns_rightmotor, max_speed_rps_wheel);
+    positionController_M_left.setDesiredRotation(relativ_turns_leftmotor, max_speed_rps_wheel); 
+    enable_motors = 0;
+
+    diff_R= relativ_turns_rightmotor-positionController_M_right.getRotation();
+    diff_L= relativ_turns_leftmotor-positionController_M_left.getRotation();
+    if ((diff_R<=0.3) && (diff_L<=0.3))
+    {
         return 1;
     }
-    else {
+    else 
+    {
     return 0;
     }
 }
@@ -161,9 +203,21 @@
 {
     float diff;
     float position_lift_end_deg = asin((-dist_arm_ground - (dist_grappleratt_grappler_uk-gripper_area_height)) / arm_length) - 90; // calculates the degree which has to be reached in order to get on top of next step
+    float relativ_turns_arm = turn_absolut_deg(position_lift_end_deg, positionController_M_Arm.getRotation());
     
-    positionController_M_Arm.setDesiredRotation(0, max_speed_rps_arm);
-    return NULL;
+    enable_motors = 1;
+    positionController_M_Arm.setDesiredRotation(relativ_turns_arm , max_speed_rps_arm);
+    enable_motors = 0;
+    
+    diff=relativ_turns_arm-positionController_M_Arm.getRotation();
+    if(diff<=0.3)
+    { return 1;
+    }
+    else 
+    { return 0;
+    }  
+    
+    
 }
 //***********************************************************************************************************************************************************
 
@@ -177,16 +231,16 @@
 
 uint8_t StepDetection(double distance){
     double d_valueMM = distance;
-    if(d_valueMM >= 4)  return 0;
+    if(d_valueMM >= 4) return 0;
     if(d_valueMM < 4)  return 1;
-    if(d_valueMM < 0 || d_valueMM > 100 ) return 2;
-    else    return 2;
+    if(d_valueMM <= 0 || d_valueMM > 100 ) return 2;
+    else return 2;
+
 }
 //Function which checks if sensors and motors have been wired correctly and the expectet results will happen. otherwise Wall-E will show with armmovement.
-int check_start()
+void check_start()
 {
-
-    return NULL;
+    
 }
 
 // while loop gets executed every main_task_period_ms milliseconds
@@ -203,14 +257,13 @@
 
     while (true)
     {
-        enable_motors = 1;
 
-        
+
         switch (ToNextFunction) 
         {
 
             case 1: 
-            start_position();
+            set_arm_stair_height();
             printf("Case 1: Position ARM (rot): %3.3f\n",positionController_M_Arm.getRotation());
             if (state==1){
                     ToNextFunction += 1;
@@ -235,16 +288,16 @@
             case 4: 
             state=lift_up();
             printf("Case 3: Position ARM (rot): %3.3f\n",positionController_M_Arm.getRotation());
-            if (state==1){
+            if ((state==1)&&(ground(ir_distance_mm_Lookdown_B))&&ground(ir_distance_mm_Lookdown_F)){
                     ToNextFunction += 1;
             }
-            break;
+
 
             case 5: 
             state=drive_straight(drive_back_mm);
             printf("Case 4: Position Right(rot): %3.3f;    Position Left (rot): %3.3f\n",
             positionController_M_right.getRotation(),positionController_M_left.getRotation());
-            if (state==1){
+            if ((state==1)&&(ground(ir_distance_mm_Lookdown_B)!=1)){
                     ToNextFunction += 1;
             }
             break;
@@ -267,6 +320,7 @@
 }
 
 
+
 void user_button_pressed_fcn()
 {
     user_button_timer.start();