first commit

Dependencies:   PM2_Libary

Branch:
lupo
Revision:
37:05252c4a2d4e
Parent:
36:a48b21a9635c
Child:
38:8121e7a79c0b
diff -r a48b21a9635c -r 05252c4a2d4e main.cpp
--- a/main.cpp	Wed Apr 13 09:40:06 2022 +0200
+++ b/main.cpp	Mon May 02 14:35:00 2022 +0200
@@ -1,12 +1,21 @@
 #include "mbed.h"
 #include "PM2_Libary.h"
 #include <cstdint>
-#include "sensor.cpp"
-
+#include <cstdio>
+#include "math.h"
+//*******************************************************************************************************************************************************************
+// Defined Variables in mm coming from Hardware-team. Need to be updated
+const float wheel_diameter                = 30; // diameter of wheel with caterpillar to calculate mm per wheel turn (4)
+const float arm_length                    = 118.5; // lenght of arm from pivotpoint to pivotpoint (3)
+const float dist_arm_attach_distsensor    = 20; // distance between pivot point arm  on body to start distancesensor on top in horizontal (6)
+const float dist_distsensors              = 200; // distance between the two distancesensors on top of Wall-E (9)
+const float dist_arm_ground               = 51; // distance between pivotpoint arm and ground (5)
+const float gripper_area_height           = 16 ; // Height of Grappler cutout to grapple Stair (8)
+const float dist_grappleratt_grappler_uk  = 33; // distance between pivotpoint Grappler and bottom edge (?)
 
-
-// logical variable main task
-bool do_execute_main_task = false;  // this variable will be toggled via the user button (blue button) to or not to execute the main task
+const float height_stairs                 = 100; // height to top of next stairstep in mm
+//***********************************************************************************************************************************************************
+// declaration of Input - Output pins
 
 // user button on nucleo board
 Timer user_button_timer;            // create Timer object which we use to check if user button was pressed for a certain time (robust against signal bouncing)
@@ -14,37 +23,42 @@
 void user_button_pressed_fcn();     // custom functions which gets executed when user button gets pressed and released, definition below
 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
-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
+// define variable to store measurement from infrared distancesensor in mm
+float ir_distance_mm_L;
+float ir_distance_mm_R;  
+float ir_distance_mm_Lookdown_B;
+float ir_distance_mm_Lookdown_F; 
 
-// Sharp GP2Y0A41SK0F, 4-40 cm IR Sensor
-float ir_distance_mV = 0.0f;    // define variable to store measurement
-AnalogIn ir_analog_in(PC_2);    // create AnalogIn object to read in infrared distance sensor, 0...3.3V are mapped to 0...1
-
-
+AnalogIn ir_analog_in_Distance_L(PC_2);  
+AnalogIn ir_analog_in_Distance_R(PC_3);
+AnalogIn ir_analog_in_Lookdown_B(PC_5);
+AnalogIn ir_analog_in_Lookdown_F(PB_1);
+// 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
+float   pwm_period_s = 0.00005f;    // define pwm period time in seconds and create FastPWM objects to command dc motors
 
-float   pwm_period_s = 0.00005f;    // define pwm period time in seconds and create FastPWM objects to command dc motors
 //motor pin declaration
-FastPWM pwm_M_right(PB_13);              
-FastPWM pwm_M_left(PA_9);
-FastPWM pwm_M_arm(PA_10);
+FastPWM pwm_M_right (PB_13);    //motor pin decalaration for wheels right side         
+FastPWM pwm_M_left  (PA_9);     //motor pin decalaration for wheels left side 
+FastPWM pwm_M_arm   (PA_10);    //motor pin decalaration for arm 
 
 //Encoder pin declaration
-EncoderCounter  encoder_M_right(PA_6, PC_7); //encoder pin decalaration for wheels right side
-EncoderCounter  encoder_M_left(PB_6, PB_7); //encoder pin decalaration for wheels left side
-EncoderCounter encoder_M_arm(PA_0, PA_1); //encoder pin decalaration for arm
+EncoderCounter  encoder_M_right (PA_6, PC_7); //encoder pin decalaration for wheels right side
+EncoderCounter  encoder_M_left  (PB_6, PB_7); //encoder pin decalaration for wheels left side
+EncoderCounter  encoder_M_arm   (PA_0, PA_1); //encoder pin decalaration for arm
+//***********************************************************************************************************************************************************
+// Hardware controll Setup and functions (motors and sensors)
 
 // create SpeedController and PositionController objects, default parametrization is for 78.125:1 gear box
-float max_voltage = 12.0f;                  // define maximum voltage of battery packs, adjust this to 6.0f V if you only use one batterypack
-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 kp = 0.1f;                            // define custom kp, this is the default speed controller gain for gear box 78.125:1
+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 * 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
 
 //motors for tracks
 PositionController positionController_M_right(counts_per_turn_wheels * k_gear, kn / k_gear, kp * k_gear, max_voltage, pwm_M_right, encoder_M_right); // parameters adjusted to 100:1 gear, we need a different speed controller gain here
@@ -52,122 +66,283 @@
 //Arm Motor
 PositionController positionController_M_Arm(counts_per_turn_arm * k_gear, kn / k_gear, kp * k_gear, max_voltage, pwm_M_arm, encoder_M_arm); // parameters adjusted to 100:1 gear, we need a different speed controller gain here
 
-//float max_speed_rps = 0.5f;       not sure if needed          // define maximum speed that the position controller is changig the speed, has to be smaller or equal to kn * max_voltage
 // PositionController positionController_M3(counts_per_turn, kn, max_voltage, pwm_M3, encoder_M3); // default 78.125:1 gear with default contoller parameters
 //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
-
+//***********************************************************************************************************************************************************
+// logic functions for basic movement
 
-// 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"
+//placeholder variables for prototype testing
 
-//Platzhalter Variabeln für die Positionierung
-float PositionStair    = 0.2;
-float PositionBackOff  = -0.5;
-float degArmStart      = 0.5;
-float degArmLift       = -0.5;
-int ToNextFunction = 0;
-float max_speed_rps = 0.5f;  
+const int   drive_stright_mm = 500; // 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;
 
 
-int StartPosition(float deg){
+// definition important variables
+const float   pi = 2 * acos(0.0); // definiton of pi
+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)
+// import functions from file mapping
+extern double powerx(double base, double pow2);
+extern double mapping (float adc_value_mV);
 
-    positionController_M_Arm.setDesiredRotation(deg);
+// 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)
+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
+    {
+        printf("Error in calc_arm_deg_for_height: desired height is bigger than Wall-E arm lenght."); // error message when desired height is not reachable. 
+    }
+    else 
+    {
+        float height_arm = height_mm - dist_arm_ground - (dist_grappleratt_grappler_uk - gripper_area_height); // calculates the height which only the arm has to cover (- attachement height (arm to robot) etc.)
+        deg_arm = asin(height_arm / arm_length) * 180.0/pi; // calculates the absolute degrees which the arm has to reach
+    }
+    return deg_arm;
+}
 
-    return NULL;
+//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;
 }
-//Drives forward into the next step
-int Drive(float dist){
+
+// 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;
+}
 
-float distance;
+// 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;
+}
 
-distance=dist;
+// bring arm in starting position. Height of stairs.
+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
+    float deg = deg_up_from_horizon + start_deg_arm;
+    if ((0.0 > deg) || (deg > 360.0))
+    {
+        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.
+
+    diff = deg-(positionController_M_Arm.getRotation() * 360.0);
+    if (diff<=0.3){
+        return 1;
+    }
+    else {
+        return NULL;}
 
 
-    positionController_M_right.setDesiredRotation(distance,max_speed_rps);
-    positionController_M_left.setDesiredRotation(distance,max_speed_rps);
+    enable_motors = 0;
+
+}
+
+//Drives forward into the next step 
+//Prameter:distance in milimeter
+int drive_straight(float distance)
+{
+    float diff_R;
+    float diff_L;
+    float deg_to_turn = wheel_dist_to_deg(distance);
+    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());
 
+    ;
+    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;
 
-    return 0;   
+    diff_R= fabs(relativ_turns_rightmotor-positionController_M_right.getRotation());
+    diff_L= fabs(relativ_turns_leftmotor-positionController_M_left.getRotation());
+
+     printf("Case 2: Position Left(rot): %3.3f    Position Right (rot): %3.3f  Desired Rotation Left:%3.3f Desired Rotation Right;%3.3f Diff L:%3.3f Diff R:%3.3f \n",
+            positionController_M_left.getRotation(),positionController_M_right.getRotation(),relativ_turns_leftmotor, relativ_turns_rightmotor, diff_L, diff_R );
+    if ((diff_R<=0.01) && (diff_L<=0.01))
+    {
+        return 1;
+    }
+    else 
+    {
+    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
+int lift_up()
+{
+    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());
+    
+    enable_motors = 1;
+    positionController_M_Arm.setDesiredRotation(relativ_turns_arm , max_speed_rps_arm);
+    enable_motors = 0;
     
-        positionController_M_Arm.setDesiredRotation(deg);
-        
+    diff=relativ_turns_arm-positionController_M_Arm.getRotation();
+    if(diff<=0.01)
+    { return 1;
+    }
+    else 
+    { return 0;
+    }  
     
-    return 0;
+    
+}
+//***********************************************************************************************************************************************************
+
+int NextStep (float){
+    return 1;
 }
 
 
+//simple check if there is an object in proximity
+//returns 0 if there is NO object present
+//returns 1 if there is an object present
+//returns 2 if the distance isn't in the expected range
+
+uint8_t StepDetection(double distance){
+    double d_valueMM = distance;
+    if(d_valueMM >= 4) return 0;
+    if(d_valueMM < 4)  return 1;
+    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.
+void check_start()
+{
+    
+}
+
+// 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. 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
+//***********************************************************************************************************************************************************
+
 int main(void)
 {
     // attach button fall and rise functions to user button object
-user_button.fall(&user_button_pressed_fcn);
-user_button.rise(&user_button_released_fcn);
-  
+    user_button.fall(&user_button_pressed_fcn);
+    user_button.rise(&user_button_released_fcn);
+
+
+    while (true)
+    {
+        enable_motors = 1;
+        ir_distance_mm_L= mapping(ir_analog_in_Distance_L.read()*1.0e3f * 3.3f);
+        ir_distance_mm_R= mapping(ir_analog_in_Distance_R.read()*1.0e3f * 3.3f);
+        ir_distance_mm_Lookdown_B= mapping(ir_analog_in_Lookdown_B.read()*1.0e3f * 3.3f);
+        ir_distance_mm_Lookdown_F= mapping(ir_analog_in_Lookdown_F.read()*1.0e3f * 3.3f);
 
 
-    while (true){
-         enable_motors = 1;
+        switch (ToNextFunction) 
+        {
 
-         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));
+            case 1: 
+            set_arm_stair_height();
+            printf("Case 1: Position ARM (rot): %3.3f\n",positionController_M_Arm.getRotation());
+            if (state==1){
+                    ToNextFunction += 1;
+            }
+            break;
 
-         //printf("IR sensor (mV): %3.3f\n", ir_distance_mV);
-        
+            case 2:
+            state=NextStep(ir_analog_in_Distance_L);
+            if (state==1){
+                    ToNextFunction = 0;
+            }
 
-       switch (ToNextFunction) {
-        case 1: StartPosition(degArmStart);
-            printf("Case 1: Position ARM (rot): %3.3f\n",positionController_M_Arm.getRotation());
-             //   ToNextFunction+=1;
+            case 3: 
+            state=drive_straight(drive_stright_mm);
+            printf("Case 2: Position Right(rot): %3.3f;    Position Left (rot): %3.3f\n",
+            positionController_M_right.getRotation(),positionController_M_left.getRotation());
+            if (state==1){
+                    ToNextFunction = 0;
+            }
             break;
-        case 2: Drive(PositionStair);
-           printf("Case 2: Position Right(rot): %3.3f;    Position Left (rot): %3.3f\n",
-           positionController_M_right.getRotation(),positionController_M_left.getRotation());
-            // ToNextFunction+=1;
-            break;
-        case 3: LiftUp(degArmLift);
-            //  ToNextFunction+=1;
+
+            case 4: 
+            state=lift_up();
             printf("Case 3: Position ARM (rot): %3.3f\n",positionController_M_Arm.getRotation());
-             break;
-        case 4: Drive(PositionBackOff);
+            if ((state==1)&&(StepDetection(ir_distance_mm_Lookdown_B))&&StepDetection(ir_distance_mm_Lookdown_F)){
+                    ToNextFunction += 1;
+            }
+
+
+            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());
-            //   ToNextFunction+=1;
+            positionController_M_right.getRotation(),positionController_M_left.getRotation());
+            if ((state==1)&&(StepDetection(ir_distance_mm_Lookdown_B)!=1)){
+                    ToNextFunction += 1;
+            }
             break;
-        case 5: LiftUp(degArmStart);
-                printf("Case 5: Position ARM (rot): %3.3f\n",positionController_M_Arm.getRotation());
-            //  ToNextFunction = 0;
+
+            case 6: 
+            state=lift_up();
+            printf("Case 5: Position ARM (rot): %3.3f\n",positionController_M_Arm.getRotation());
+             if (state==1){
+                    ToNextFunction = 1;
+            }
             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();
         thread_sleep_for(main_task_period_ms - main_task_elapsed_time_ms);
-    return 0;
+        return 0;
 }
 
 
+
 void user_button_pressed_fcn()
 {
     user_button_timer.start();
     user_button_timer.reset();
 }
 
-void user_button_released_fcn() {
+void user_button_released_fcn() 
+{
     // read timer and toggle do_execute_main_task if the button was pressed longer than the below specified time
     int user_button_elapsed_time_ms = std::chrono::duration_cast<std::chrono::milliseconds>(user_button_timer.elapsed_time()).count();
     user_button_timer.stop();
-    if (user_button_elapsed_time_ms > 200) {
-       ToNextFunction += 1;}
-       }
\ No newline at end of file
+    if (user_button_elapsed_time_ms > 200) 
+    {
+       ToNextFunction = 3;
+    }
+}
\ No newline at end of file