first commit

Dependencies:   PM2_Libary

main.cpp

Committer:
lupomic
Date:
2022-05-22
Revision:
43:057640e99f8e
Parent:
42:ec3a88a24666

File content as of revision 43:057640e99f8e:

#include "mbed.h"
#include "PM2_Libary.h"
#include <cstdint>
#include <cstdio>
#include "math.h"
//*******************************************************************************************************************************************************************
// Defined Variables in mm coming from Hardware-team. Need to be updated
const float wheel_diameter                = 30.0f; // 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 dist_arm_attach_OK_griparea   = 10.5 ; // Height of Grappler cutout to grapple Stair (8) (maybe add 1mm so gripper is a bit over the plate)
const float dist_grappleratt_grappler_uk  = 36.5; // distance between pivotpoint Grappler and bottom edge (?)

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)
InterruptIn user_button(PC_13);     // create InterruptIn interface object to evaluate user button falling and rising edge (no blocking code in ISR)
void user_button_pressed_fcn();     // custom functions which gets executed when user button gets pressed and released, definition below
void user_button_released_fcn();

// 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; 

// 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_Lookdown_B(PC_5);
AnalogIn ir_analog_in_Lookdown_F(PB_1);

// Digital Inputs
DigitalIn mechanical_button(PC_3);


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

//motor pin declaration
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
//***********************************************************************************************************************************************************
// Hardware controll Setup and functions (motors and sensors)



// 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 * 19.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
PositionController positionController_M_left(counts_per_turn_wheels * k_gear, kn / k_gear, kp * k_gear, max_voltage, pwm_M_left, encoder_M_left); // parameters adjusted to 100:1 gear, we need a different speed controller gain here
//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

// 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
//***********************************************************************************************************************************************************


//these variables represent relative position NOT absolut
float startPos = -0.545; //from last lift up position to start position
float liftPos = -0.555; //from start position to lift up position

const float   drive_straight_mm = 200.0;
const float   drive_back_mm = -20.0f;    
int         ToNextFunction = 0;      // current state of the system (which function is beeing executed)
int         state=0;        //return value of functions
float       desired_pos;
int        nextStep=0;

// definition variables for calculations
const float   pi = 2 * acos(0.0); // definiton of pi
const float   end_pos_lift_deg = 180 + asin((dist_arm_ground-(dist_grappleratt_grappler_uk))/arm_length) * 180 / pi;  // calculates the degree which the arm has to have when lift_up has been executed.
const 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)

// definition of rotation speeds for motors 0 = none 1.0 = max.
const float   max_speed_rps_wheel = 0.8f;  // 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.9f; // define maximum speed that the position controller is changig the speed for the arm, has to be smaller or equal to kn * max_voltage

// 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)
// PARAM: height_mm = height which OK Gripperarea has to reach.
// RETURN: deg_arm = absolut Position in deg that the arm has to take.
float calc_arm_deg_for_height(int height_mm)
{
    float height_arm = height_mm - (dist_arm_ground - dist_arm_attach_OK_griparea); // calculates the height which only the arm has to cover (- attachement height (arm to robot) etc.)
    float deg_arm = asin(height_arm / arm_length) * 180.0/pi; // calculates the absolute degrees which the arm has to reach
    return deg_arm;
}

//calculates the deg which the wheels have to turn in order to cover specified distance in mm
//PARAM: distance = distance to drive in milimeter
//RETURN: deg_wheel = degree which the motor has to turn in order to cover distance(mm)
float wheel_dist_to_deg(float distance)
{
    float deg_wheel = (distance) / (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_rotation = the current rotation of the Motor (Motor.getRotation())
// RETURN: new_turn_rotation = new Rotation value in rotations
float turn_relative_deg(float deg_to_turn, float current_rotation)
{
    float new_turn_rotation = current_rotation + deg_to_turn;
    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_rotation = 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;
	if(current_rotations > 0)
	{
		full_rotations = round(current_rotations - 0.5);	
	}
	else if(current_rotations < 0)
	{
		full_rotations = round(current_rotations + 0.5);	
	} 
	else
	{
		full_rotations = 0;
	}
    float new_partial_rotation = full_rotations - start_deg_arm/360 + end_deg/360;
    return new_partial_rotation;
}

//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-dist_grappleratt_grappler_uk))/arm_length) + start_deg_arm;
    end_deg = end_deg * 180 / pi;
    return end_deg;
}

//***********************************************************************************************************************************************************
// important calculatet constant for Wall-E
const double deg_up_from_horizon_to_stair = calc_arm_deg_for_height(height_stairs);

// import functions from file mapping
extern double powerx(double base, double pow2);
extern double mapping (float adc_value_mV);

//
//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 nextStepDetection(double distanceCm,double setpointDistance){
    double distance = distanceCm;
    double setpoint = setpointDistance;
    if(distance == 0){
        return 10; //sensor value is outside the expected range
    }
    if((distance <= (setpoint + 2)) && (distance >= (setpoint - 2))){
        return 3; //the distance to the next step is in ±1cm of the setpoint
    }
    if(distance < setpoint){
        return 0; //the robot is to close to the step to rotate the arm unhindered
    }
    if(distance > setpoint){
        return 1; //the robot is too far away from the next step
    }
    else{
        return 2;
    }

}
//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_down(float sensor)

{
    double d_valueMM = mapping(sensor*1.0e3f*3.3f);   
    if(d_valueMM >= 4) return 0;
    else if( d_valueMM > 100 ) return  2;
    else if((d_valueMM < 4)||(d_valueMM==0))  return 1;
    
    else return 5;
}

// bring arm in starting position. Height of stairs.
int set_arm_stair_height()

{
    float diff;
    int gripper=nextStepDetection(ir_distance_mm_L, 2);

    //first step to calculate desired position
    if (desired_pos==0) {
    desired_pos=turn_relative_deg(startPos, positionController_M_Arm.getRotation()); 
    positionController_M_Arm.setDesiredRotation(desired_pos, 0.5); // command to turn motor to desired deg.
    }
    // to check if the position controller is finished
    diff =abs( desired_pos-(positionController_M_Arm.getRotation()));

    //prints for testing
    printf("Set arm      Position ARM (rot): %3.3f Desired:%3.3f    State:%d     ToNextfunction:%d Diff:%3.3f\n",
    positionController_M_Arm.getRotation(), desired_pos, state, ToNextFunction, diff);

    // stops the positioning, when the gripper is in proximity of the sensor
    if (gripper==3){
        desired_pos=turn_relative_deg(-0.01, positionController_M_Arm.getRotation() );
        positionController_M_Arm.setDesiredRotation(desired_pos, 0.2);
    }

    if((diff<0.008)&&gripper){
        return 1;
    }
    else {
        return NULL;
}
}

//Drives forward into the next step 
//Prameter:distance in milimeter
int drive_straight(float distance)
{
    float diff_R;
    float diff_L;

// calculates the desired position
if (desired_pos==0) {
          desired_pos=wheel_dist_to_deg(distance);
    float relativ_turns_rightmotor = turn_relative_deg(desired_pos, positionController_M_right.getRotation());
    float relativ_turns_leftmotor = turn_relative_deg(desired_pos, positionController_M_left.getRotation());
}


    positionController_M_right.setDesiredRotation(desired_pos, max_speed_rps_wheel);
    positionController_M_left.setDesiredRotation(desired_pos, max_speed_rps_wheel); 

 // to check if the position controller are finished
    diff_R= abs(desired_pos-(positionController_M_right.getRotation()));
    diff_L= abs(desired_pos-(positionController_M_left.getRotation()));

    //prints for testing
    printf("Drive Straight Position Right(rot): %3.3f; Position Left (rot): %3.3f Desired: %3.3f Diff:%3.3f State:%d ToNextfunction:%d\n",
     positionController_M_right.getRotation(),positionController_M_left.getRotation(),desired_pos,diff_L, state, ToNextFunction);


    if ((diff_R<=0.02) && (diff_L<=0.02))
    {
        return 1;
    }
    else 
    {
    return 0;
    }
}

//turns the arm until the robot is on the next step
int lift_up()
{
    float diff;

    // calculates the desired position
    if (desired_pos==0) {
    desired_pos = turn_relative_deg(liftPos,positionController_M_Arm.getRotation());
    }
    
    positionController_M_Arm.setDesiredRotation(desired_pos, max_speed_rps_arm);

    // to check if the position controller is finished
    diff=abs(desired_pos-positionController_M_Arm.getRotation());
 
  //prints for testing
     printf("Lift Up:       Position ARM (rot): %3.3f Desired:%3.3f     State:%d  ToNextfunction:%d\n",positionController_M_Arm.getRotation(),desired_pos, state, ToNextFunction);

    if(diff<=0.03)
    { return 1;
    }
    else 
    { return 0;
    }  
    
}
//***********************************************************************************************************************************************************

// 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);
    mechanical_button.mode(PullDown);
 
    while (true)
    {

        ir_distance_mm_L= mapping(ir_analog_in_Distance_L.read()*1.0e3f * 3.3f);
     
    
        if (ToNextFunction>=1||(mechanical_button.read()!=1)) {
            enable_motors=1;
        }
        
        
        switch (ToNextFunction) 
        {
    
            // case 0: For referencing the arm position
            case 0: while  (mechanical_button.read()!=1) 
            {
            positionController_M_Arm.setDesiredRotation(-1,0.5);
           
            }
            if (mechanical_button){
                positionController_M_Arm.setDesiredRotation(positionController_M_Arm.getRotation());

            }
            break;

            // case 1:
            case 1:  
        
                ToNextFunction +=1;
                state=0;
            break;

            // case 2: drive too the stair
            case 2:  state=drive_straight(drive_straight_mm);
           
            if (state==1){
                    ToNextFunction += 1;
                    state=0;
                    desired_pos=0;
            }
            break;

            // case 3: lift the roboer up
            case 3:    state=lift_up();
            
            if (state==1){
                    ToNextFunction += 1;
                	   state=0;
                    desired_pos=0;
            }
            break;

            // case 4: detect if there is a next step
            case 4:          state=nextStepDetection(ir_distance_mm_L,4);
            // if there is a next step, variable nextStep=1
            if (state==3){
                 nextStep=1;
               }

        
            ToNextFunction +=1;
            state=0;

            printf("distance:%3.3f  Output:%d NextStep:%d\n ", ir_distance_mm_L, nextStepDetection(ir_distance_mm_L,4), nextStep); 
             break;

            // case 5: Drive the roboter back until there is no step underneath the lookdown sensor
            case 5: 
            state=drive_straight(drive_back_mm);
            
            if  (StepDetection_down(ir_analog_in_Lookdown_B) != 1)
            {
                    ToNextFunction += 1;
                    state=0;
                    desired_pos=0;
                    positionController_M_left.setDesiredRotation(positionController_M_left.getRotation());
                    positionController_M_right.setDesiredRotation(positionController_M_right.getRotation());

            }
            break;

            //case 6: bring arm back to starting positon
            case 6: 
            state=set_arm_stair_height();
            //if there is a next step, continue to climb up
             if ((state==1) && (nextStep)){
                    ToNextFunction = 1;
                    state=0;
                    desired_pos=0;
                    nextStep=0;
            }
            //if there is no next step, stop
            if ((state==1) && (nextStep!=1)) {
                ToNextFunction=0;
                state=0;
                desired_pos=0;
                nextStep=0;
            }
            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;
}



void user_button_pressed_fcn()
{
    user_button_timer.start();
    user_button_timer.reset();
}

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;
    }
}