sriramgbhagwat / arducopter

Automatically exported from code.google.com/p/arducopter
0 stars 0 forks source link

Change triggering for acc and auto level calibration #373

Closed GoogleCodeExporter closed 8 years ago

GoogleCodeExporter commented 8 years ago
Purpose is to trigger :
- acc calibration with yaw and roll full left and throttle down
- auto level calibration with yaw and roll full right and throttle down

For this modifications are :

File : motors.pde

#define ARM_DELAY 6
#define DISARM_DELAY 4 
#define LEVEL_DELAY 10 //No need to wait too long

...

// full right
        if (g.rc_4.control_in > 4000) {
        if (arming_counter == LEVEL_DELAY){
                   if (g.rc_1.control_in > 4000) { //Modification : roll full right
            //Serial.printf("\nINFLIGHT AUTO LEVEL\n"); 
            // begin auto leveling
            auto_level_counter = 250;
                    }
            arming_counter = 0;

        }else if (arming_counter == ARM_DELAY){
            if(motor_armed == false){
                // arm the motors and configure for flight
                                //Serial.printf("\nARMING MOTORS\n"); 
                init_arm_motors();
            }
            // keep going up
            arming_counter++;
        } else{
            arming_counter++;
        }

    // full left
    }else if (g.rc_4.control_in < -4000) {
        if (arming_counter == LEVEL_DELAY ){
                    if (g.rc_1.control_in < -4000) { //Modification : roll full left
            //Serial.printf("\nLEVELING - INIT ACC\n");

            // begin manual leveling
            imu.init_accel(mavlink_delay, flash_leds);
                    }
            arming_counter = 0;

        }else if (arming_counter == DISARM_DELAY){
            if(motor_armed == true){
                // arm the motors and configure for flight
                                //Serial.printf("\nDESARMING MOTORS\n"); 
                init_disarm_motors();
            }
            // keep going up
            arming_counter++;
        }else{
            arming_counter++;
        }

    // Yaw is centered
    }else{
        arming_counter = 0;
    }

File : control_modes.pde
static void auto_trim()
{

        if(auto_level_counter > 0){
        //g.rc_1.dead_zone = 60;        // 60 = .6 degrees
        //g.rc_2.dead_zone = 60;

                //Modification : start acc tuning only when roll is back to center, to avoid problem with roll in full rigth position.
                if( !inflight_auto_level && abs(g.rc_1.control_in) < 100 ) {
                    inflight_auto_level = true;
                }

        auto_level_counter--;
                if (!(g.rc_3.control_in == 0 && g.rc_4.control_in < -4000) && inflight_auto_level) { //Modification : don't activate when motor ara stopped
          trim_accel();
                }
        led_mode = AUTO_TRIM_LEDS;
        do_simple = false;

        //if(auto_level_counter == 1){
                if(auto_level_counter == 1 || motor_armed == false){ //Modification : could record new parameter when copter is disarmed

                        inflight_auto_level = false; //Modification
            //g.rc_1.dead_zone = 0;     // 60 = .6 degrees
            //g.rc_2.dead_zone = 0;
            led_mode = NORMAL_LEDS;
            clear_leds();
            imu.save();

            reset_control_switch();

            //Serial.println("Done auto trim"); 
            auto_level_counter = 0;

            // set TC
            init_throttle_cruise();
        }
    }
}

File : ArduCopter.pde

// Used for Inflight Auto Level
static bool             inflight_auto_level;

Original issue reported on code.google.com by airma...@gmail.com on 2 Mar 2012 at 3:08

GoogleCodeExporter commented 8 years ago
I like it! :-)

Original comment by robustin...@gmail.com on 14 Mar 2012 at 7:50

GoogleCodeExporter commented 8 years ago
Thanks :)

Original comment by airma...@gmail.com on 15 Mar 2012 at 8:14

GoogleCodeExporter commented 8 years ago
[deleted comment]
GoogleCodeExporter commented 8 years ago
I reported on the dev list, I hope that is taken into account, thanks anyway 
for the great suggestion!

Bests, 
Marco Robustini

Original comment by robustin...@gmail.com on 15 Mar 2012 at 8:48

GoogleCodeExporter commented 8 years ago
Closing all issues on the old issues list by marking them WontFix.

If this is still a valid issue please re-raise it on the new GitHub issues 
list: https://github.com/diydrones/ardupilot/issues

Thanks!

Original comment by rmackay...@gmail.com on 21 Jul 2013 at 2:14