Airplane mode RTH

Post Reply
rbirdie001
Posts: 178
Joined: Fri Apr 01, 2011 10:32 pm
Location: Czech Republic, Prague

Re: Airplane mode RTH

Post by rbirdie001 »

Hi,
thanks for both oppinions. Next week I'll be on bussiness trip so I hope on evenings at the hotel I'll look again at the RTH code and understand more if it ;) .
Also I took today one of my wings with me to family walk (Drenalyn - no computers, no GPS, no gyros, everything 100% manual) and whole family withstanded watching whole battery of crazy twisting (they are generally bored of my flying :( ).
Just to ensure I understand well:
if Dist home is <100m descend to set rthAlt using elevator.

When RTH is activated by switch, plane gets home, starts circling and reaches (from top) minimum safe altitude, should it then keep safe altitude until the battery is flat or descends further?
On my plane in this situation the motor is still running and throttle is automatically changing (so it remains armed), but elevator doesn't go up so plane descends and speeds up by increasing throttle and lovering height.
When I set higher P than approx. 4 for alt. control, plane when climbing reaches safe altitude then start jumping and wings are sometimes breaking...
I already changed Mediatek GPS for Ublox Neo6M which improved height control in 130322 but now in the new version I'm again unable to tune it up.
I'm afraid that anyway this was one of last nice weekends, winter is coming...
Have a nice days.
Roman

crashlander
Posts: 506
Joined: Thu May 05, 2011 8:13 am
Location: Slovenia

Re: Airplane mode RTH

Post by crashlander »

rbirdie001 wrote:Hi,
...
When RTH is activated by switch, plane gets home, starts circling and reaches (from top) minimum safe altitude, should it then keep safe altitude until the battery is flat or descends further?...

In previous versions when

Code: Select all

#define FAILSAFE_RTH true
was selected my wing disarmed at home point and start to glide/descend.
But in current version it seems that option is not working, plane is just circling around home point and adding TH to maintain height.

@PatrikE
in GPS.h you/I define

Code: Select all

#define FAILSAFE_RTH true

in def.h there is only deffinition for

Code: Select all

#if FAILSAFE_RTH  && !defined (FAILSAFE)
    #define FAILSAFE
  #endif

but in GPS.c you are looking for

Code: Select all

#if FAILSAFE_RTH_ENABLE



I'm afraid that anyway this was one of last nice weekends, winter is coming...
Have a nice days.
Roman

The winter is just another flying season! :)

Regards
Andrej

crashlander
Posts: 506
Joined: Thu May 05, 2011 8:13 am
Location: Slovenia

Re: Airplane mode RTH

Post by crashlander »

Another idee from one of earlies rbirdie001 posts is to disable I term zeroing for MINTH and thus enable proper glide with motor off (disarm):
in MultiWii.cpp add define for fixedwing around I term zeroing code!

Code: Select all

#if !defined(FIXEDWING) //crashlander test for glider FIXEDWINGS=====START
      errorGyroI[ROLL] = 0; errorGyroI[PITCH] = 0;
   
      #if PID_CONTROLLER == 1
        errorGyroI_YAW = 0;
      #elif PID_CONTROLLER == 2
        errorGyroI[YAW] = 0;
      #endif
      errorAngleI[ROLL] = 0; errorAngleI[PITCH] = 0;
     #endif //crashlander test for glider FIXEDWINGS=====STOP


Not yet tested code of-course... :)
Any obvious drawbacks?

Regards
Andrej

rbirdie001
Posts: 178
Joined: Fri Apr 01, 2011 10:32 pm
Location: Czech Republic, Prague

Re: Airplane mode RTH

Post by rbirdie001 »

Hi Andrej,
I'd be caredul with this. I have feeling, that I term should be sometimes reset. Imagine, that your wing is waiting for GPS fix or you just hold it with one hand longer time so I term accumulates until is full an then you throw the plane into the air. Due to I term influence it could make an unepected turn and crash. If disable reseting, then I'd make at least one reset e.g. when changing fom MINTHROTTLE to some significant TH. (Lets say do reset when last TH value was under 1300 and current TH is over 1300.) Just for an idea.
Anyway I have to say, that even removing I term resetting wich I already tested didn't solve my problem with height control so if your wing performs well with the current code, I'd apply old but smart saying "Don't touch what works well!" :D

BTW: Now I'm on the training in middle of Italy and I'm starting to understand your notice that
The winter is just another flying season!

Here, 1000km south from my home I'm walking in T-shirt and buy ice cream while at home I was two days ago walking in a sweater, jacket, cap and warmed my hands on a cup of hot tea... :D
You are not that far from me, but anyway it is some difference. ;)
Regards
Roman

rbirdie001
Posts: 178
Joined: Fri Apr 01, 2011 10:32 pm
Location: Czech Republic, Prague

Re: Airplane mode RTH

Post by rbirdie001 »

Hi Patrik,
I'm now trying to understand at least a little of RTH code, namely the height control and I'm still wonder about some lines in last FW_NAV_PID version GPS.cpp. In lines 1493 and 1500 I see that GPS_AltErr - means I am low and + means I am high, right?:

Code: Select all

GPS_AltErr = GPS_altitude - GPS_hold[ALT]; // Altitude error - means your'e to low
...
if(GPS_AltErr >=0) GPS_angle[PITCH] = GPS_angle[PITCH]/3;         // Limit throw for descending.

Now why on line 1523 we are proceeding "we are higher" code when GPS_AltErr <=0, which should mean that we are low or on the level?

Code: Select all

// Navigation while Altitude is higher than RTH Alt
if (f.GPS_HOME_MODE && !f.CLIMBOUT_FW && GPS_AltErr <=0 ){        // While we are higher than RTH alt.
if (GPS_distanceToHome >100){ GPS_angle[PITCH]=0 ;}             // RTH Nav Stage Use only ACC to maintain altitude

This is the strange thing I noticed but this seems not to be cause of my troubles because my plane is lowering even while it's circling around home so it's less than 100m far from home and in that case value calculated in the line 1499 should bypass all successive lines unmodified and be used as is for the elevator compensation. Right?

Code: Select all

GPS_angle[PITCH]= GPS_AltErr * GPS_ALTCORR ;                      // Calculate Elevator compensation.

I will be glad if you can answer me and possibly review one more time this part of the code, where GPS_angle[PITCH] is calculated and modified, if there isn't any hidden error.
Thanks!
Roman

crashlander
Posts: 506
Joined: Thu May 05, 2011 8:13 am
Location: Slovenia

Re: Airplane mode RTH

Post by crashlander »

Code: Select all

GPS_AltErr = GPS_altitude - GPS_hold[ALT];

GPS_hold[ALT] -> where I wanna be
GPS_altitude -> where I'm
So + means I'm higher and - means I'm too low.
And that works O.K. whene used here

Code: Select all

// Climb out before RTH
if(GPS_AltErr < 0 && f.CLIMBOUT_FW && f.GPS_HOME_MODE ){


But you are right that one is sure strange

Code: Select all

if (f.GPS_HOME_MODE && !f.CLIMBOUT_FW && GPS_AltErr <=0 ){        // While we are higher than RTH alt.

Because that activates active dive if we are higher. And that is probably what I observed but believed that I have ELEVATORCOMPENSATION issue (Patrik?!).

In the moment that plane passes that home zone mark (20m in my case) (and it is not in CLIMBOUT_FW and it is lower than target (in original, probably wrong code)) it will no longer use

Code: Select all

GPS_angle[PITCH]= GPS_AltErr * GPS_ALTCORR ;                      // Calculate Elevator compensation.

because of

Code: Select all

if (GPS_distanceToHome >20){ GPS_angle[PITCH]=0 ;} 

so the only active ALT control will be

Code: Select all

GPS_angle[PITCH]-= ( abs(att.angle[ROLL]) * ELEVATORCOMPENSATION ) /100;


Regards
Andrej

crashlander
Posts: 506
Joined: Thu May 05, 2011 8:13 am
Location: Slovenia

Re: Airplane mode RTH

Post by crashlander »

I've just flight tested all my mods from above (including disable I zeroing with min TH) and they works as expected!
I had to increase home zone to 100m otherwise my (quite)fast wing would hold altitude, circling with radius biger than small 20m zone.
I also increased DISARM zone to 30m since 5m was hard to hit.
I also suggest to remove alt checking in last DISARM step since it can be hard to please. My wing during circeling around home point loses height and when reaching disarm zone it is too low to disarm so it overflies it and when is out it starts to climb to safe height, and again upon return it is too low (so this continues for a while until luck strikes that both params are true).
I'm attaching changed files for reference.

Regards
Andrej
Attachments
Archive.zip
(29.6 KiB) Downloaded 287 times

crashlander
Posts: 506
Joined: Thu May 05, 2011 8:13 am
Location: Slovenia

Re: Airplane mode RTH

Post by crashlander »

rbirdie001 wrote:Hi Andrej,
I'd be caredul with this. I have feeling, that I term should be sometimes reset. Imagine, that your wing is waiting for GPS fix or you just hold it with one hand longer time so I ...

Hand launching the plane will produce more than enough disturbances to zero out I couple of times.

Regards
Andrej

User avatar
Chriss
Posts: 9
Joined: Mon Oct 21, 2013 9:03 pm
Location: Germany

Re: Airplane mode RTH

Post by Chriss »

Hello,

I am impressd of the good work! :) Thanks for that!

I orderd Crius MWC SE v2.5 and want to install FC, GPS in my Bixler2 (Crius doesn't arrived yet). For testing I use a Arduino Pro Mini (only for testing compiling e.g.). When I want to compile it with I2C_GPS, there is an error in GPS.cpp (FW_nav()).

Code: Select all

/******************************  
  PID Test for Navigating planes.
  ******************************/
    static int16_t oldif;
   
    naverrorI += (dif * (navPID_PARAM.kI)) *gpsFreq;
    naverrorI =constrain(naverrorI,-MAX_I,MAX_I);
   
    naverrorD += ((dif - oldif) *navPID_PARAM.kD) * gpsFreq;
    naverrorD =constrain(naverrorD,-MAX_D,MAX_D);
    oldif = dif;
    dif *= navPID_PARAM.kP;

    dif += naverrorI/100-naverrorD/100;
 //******************************


navPID_PARAM ist not defined when GPS_SERIAL is not set.

Is it the right way to configure it?

Connection is: Crius => [I2C] => NAV Modul => [UART] => GPS

Have I forgot something in config.h?

Code: Select all

see attachment :)


I use the latest NAV_PID_130909

Regards from Germany,
Chriss
Attachments
config.zip
(18.47 KiB) Downloaded 278 times

PatrikE
Posts: 1976
Joined: Tue Apr 12, 2011 6:35 pm
Location: Sweden
Contact:

Re: Airplane mode RTH

Post by PatrikE »

Hi chriss,

You're right.
It's missed when implementing PID's for navigation.
When using I2C gps only the PID's inside the I2C unit is used.

At ~row 56 in gps.cpp.

Code: Select all

#if defined(GPS_SERIAL) || defined(GPS_FROM_OSD) || defined(TINY_GPS)


Change to

Code: Select all

#if defined(GPS_SERIAL) || defined(GPS_FROM_OSD) || defined(TINY_GPS) || ( defined(FIXEDWING) && defined(I2C_GPS))

Then it will compile.

rbirdie001
Posts: 178
Joined: Fri Apr 01, 2011 10:32 pm
Location: Czech Republic, Prague

Re: Airplane mode RTH

Post by rbirdie001 »

Hi Patrik,
I see you are back!
Because I'm preparing another attempt to make running well new vesion FW_NAV_PID, I want to ask you if you can confirm my observations here: viewtopic.php?f=7&t=2456&start=330#p42370
This weekend we should have nice weather here :D so I want to finally move on!
Thanks Roman

bigcheese
Posts: 10
Joined: Sat Aug 17, 2013 12:17 am

Re: Airplane mode RTH

Post by bigcheese »

Hi,

have anyone an idea how can I debug or dig down the problem I have?
In the GUI I can see throttle, arm and pitch/roll when moving sticks on my control.

but i never get the final accoustic signal from the BEC that everything is fine... even in passthrough mode...
I can't find the right pin on my MEGA board (looks like)

Code: Select all

/***********************             HW PWM Servos             ***********************/ 
    /* HW PWM Servo outputs for Arduino Mega.. moves:
      Pitch   = pin 44
      Roll    = pin 45
      CamTrig = pin 46
      SERVO4  = pin 11 (aileron left for fixed wing or TRI YAW SERVO)
      SERVO5  = pin 12 (aileron right for fixed wing)
      SERVO6  = pin 6   (rudder for fixed wing)
      SERVO7  = pin 7   (elevator for fixed wing)
      SERVO8  = pin 8   (motor for fixed wing)       */

    #define MEGA_HW_PWM_SERVOS


I assume pin 8 for motor and 6 and 7 for left and right wing (have a fixed wing, but there are only 10 pins on my board!!)
how can I clarify if the board have a problem or the software or my wiring?
Having this board: http://www.hobbyking.com/hobbyking/store/__26588__multiwii_pro_flight_controller_w_mtk_gps_module.html

thanks for any help

User avatar
Chriss
Posts: 9
Joined: Mon Oct 21, 2013 9:03 pm
Location: Germany

Re: Airplane mode RTH

Post by Chriss »

PatrikE wrote:Hi chriss,

You're right.
It's missed when implementing PID's for navigation.
When using I2C gps only the PID's inside the I2C unit is used.

At ~row 56 in gps.cpp.

Code: Select all

#if defined(GPS_SERIAL) || defined(GPS_FROM_OSD) || defined(TINY_GPS)


Change to

Code: Select all

#if defined(GPS_SERIAL) || defined(GPS_FROM_OSD) || defined(TINY_GPS) || ( defined(FIXEDWING) && defined(I2C_GPS))

Then it will compile.


Hi Patrik,

thanks for your reply! Now it semms to work (on Arduino Pro Mini without sensors, only for upload testing).
Just waiting for the Crius SE v2.5...

Is NAV_PID_130909 the latest version?

Regards from Germany,
Chriss

PatrikE
Posts: 1976
Joined: Tue Apr 12, 2011 6:35 pm
Location: Sweden
Contact:

Re: Airplane mode RTH

Post by PatrikE »

@Bigcheese.
The servo order is somewhat a mes since the servocode was rewritten.
This is the pins that works on mu Crius AIO.
// With MEGA_HW_PWM_SERVOS enabled
servo[3] D11 wing 1
servo[4] D12 Wing 2
servo[5] D7 Elevator
servo[6] D6 Rudder
servo[7] D3 ESC


// Without MEGA_HW_PWM_SERVOS enabled
servo[0] Pin D34 & Pin D44 //
servo[1] Pin D35 & Pin D45; //
servo[2] Pin D33 & Pin D46; //
servo[3] Pin D37; // Wing 1 Pin D7 with hack
servo[4] Pin D6; // Wing 2
servo[5] Pin D2; // Rudder
servo[6] Pin D5; // Elevator
servo[7] Pin D3; // Throttle

With a hack it's possible to move Wing 1 servo to Pin D7
In def.h
Servo pinmodes for Mega boards, Replace SERVO_4 defs with this code.

Code: Select all

  #define SERVO_4_PINMODE            pinMode (37, OUTPUT); pinMode (7, OUTPUT);  // new       - alt TILT_ROLL
  #define SERVO_4_PIN_HIGH           PORTC |= 1<<0;PORTH |= 1<<4;
  #define SERVO_4_PIN_LOW            PORTC &= ~(1<<0);PORTH &= ~(1<<4);


My advice is disable MEGA_HW_PWM_SERVOS and add Pin D7 as servo output in def.

It's a Mod that should be implemented to public code.
Many boards don't have all pins.

/PatrikE

PatrikE
Posts: 1976
Joined: Tue Apr 12, 2011 6:35 pm
Location: Sweden
Contact:

Re: Airplane mode RTH

Post by PatrikE »

rbirdie001 wrote:Hi Patrik,
I see you are back!
Because I'm preparing another attempt to make running well new vesion FW_NAV_PID, I want to ask you if you can confirm my observations here: viewtopic.php?f=7&t=2456&start=330#p42370
Thanks Roman


Yes It seems like its inverted. :oops:
Test to use (>= radius) .
I think it will work better..

/Patrik

PatrikE
Posts: 1976
Joined: Tue Apr 12, 2011 6:35 pm
Location: Sweden
Contact:

Re: Airplane mode RTH

Post by PatrikE »

Chriss wrote:
Is NAV_PID_130909 the latest version?

Regards from Germany,
Chriss


Yes but it's time to make a corrected update.
Probably tomorrow.

crashlander
Posts: 506
Joined: Thu May 05, 2011 8:13 am
Location: Slovenia

Re: Airplane mode RTH

Post by crashlander »

@PatrikE
I have changed and tested some more lines of your code. You can check it here (if I remember correctly diff between r3 and r4 will show most of them).
https://code.google.com/p/crashlander-m ... 253Dclosed

Regards
Andrej

rbirdie001
Posts: 178
Joined: Fri Apr 01, 2011 10:32 pm
Location: Czech Republic, Prague

Re: Airplane mode RTH

Post by rbirdie001 »

PatrikE wrote:Yes but it's time to make a corrected update.
Probably tomorrow.

Sound great!
Weather forecast still say it should be here good weather this weekend so I'll take new version (if ready ;) ) and hopefully make the RTH code finally working also for me :lol: .
Patrik, I told you that I'm natural beta tester. If there is a bug, it will show up to me and if something works for me, then for everyone. :D
Roman

PatrikE
Posts: 1976
Joined: Tue Apr 12, 2011 6:35 pm
Location: Sweden
Contact:

Re: Airplane mode RTH

Post by PatrikE »

A updated version with corrections and some renaming in gps.h
Code also updated with latest changes in official branch.

FW_Nav_131024.rar

Dev-Branch for comparing.
https://code.google.com/p/multiwii/source/browse/branches/PatrikE/FixedWingNav_Dev/#FixedWingNav_Dev

/Patrik

crashlander
Posts: 506
Joined: Thu May 05, 2011 8:13 am
Location: Slovenia

Re: Airplane mode RTH

Post by crashlander »

Thank you Patrik!
One question:
Why are you checking height before DISARM (why wait/aim for 5m before disarming)? I have tested disarm on whatever height the wing returns and I did not find any issues.

Code: Select all

if( f.FAILSAFE_RTH_ENABLE){
if (GPS_distanceToHome <20  && GPS_AltErr <=5 ){f.ARMED = 0;}
}

In new release you doubled value for GPS_MAXCORR and GPS_MAXCLIMB! Now I had 15 for both and would say it was enough (maybe slightly more for climb but not for roll).

Regards
Andrej

PatrikE
Posts: 1976
Joined: Tue Apr 12, 2011 6:35 pm
Location: Sweden
Contact:

Re: Airplane mode RTH

Post by PatrikE »

Hi Andrej,

I love to get input on the code!... :D

The theory..
One don't know what altitude the plane keeps when returning.
It's just there to let the plane circulate and descend with low throttle until RTH altitude is close.
Low throttle makes my plane use propellor as efficient airbrake.
And then Disarm and autoland.
But it's maybe a unnecessary check?

GPS_MAXCORR and GPS_MAXCLIMB is mostly related to the type of plane.
It just limits the Maximum control Gps can apply during navigation.
20-30 degrees is a quite normal banking on most planes.
Maby a little to much in a climb in auto mode.

But as you say.
Better to run lower values as default.

Code: Select all

/* Maximum Limits for controls */
#define GPS_MAXCORR    15   // Degrees banking applied by GPS.
#define GPS_MAXCLIMB   15   // Degrees climbing . To much can stall plane.


One more thing that needs to be determined is The PID max values.

Code: Select all

/* Set Maximum Limits for PID-controls */
#define MAX_I 200    // Increase steps by 10 for more control (1 degree)
#define MAX_D 200    // 100 = 10 degree


Cheers
Patrik

i3dm
Posts: 57
Joined: Tue Oct 01, 2013 4:48 pm

Re: Airplane mode RTH

Post by i3dm »

This is a long and very interesting thread.
i apologize in advance for not reading entirely through it - but is there a good stable version of MultiWii airplane with RTH already available?
if so i might be able to assist in some testing soon..

crashlander
Posts: 506
Joined: Thu May 05, 2011 8:13 am
Location: Slovenia

Re: Airplane mode RTH

Post by crashlander »

i3dm wrote:This is a long and very interesting thread.
i apologize in advance for not reading entirely through it - but is there a good stable version of MultiWii airplane with RTH already available?
if so i might be able to assist in some testing soon..


IMO nothing is stable! ;)
That said I believe that PatrikE's code is mature and stable enough to test it (no serious bugs is known for long time).
But as always take plane that is not the most expensive / fast / hideous and start learning how to tune it properly.

Regards
Andrej

PatrikE
Posts: 1976
Joined: Tue Apr 12, 2011 6:35 pm
Location: Sweden
Contact:

Re: Airplane mode RTH

Post by PatrikE »

Info on latest code download
viewtopic.php?f=7&t=2456&start=340#p42611

rbirdie001
Posts: 178
Joined: Fri Apr 01, 2011 10:32 pm
Location: Czech Republic, Prague

Re: Airplane mode RTH

Post by rbirdie001 »

Hi Patrik,
new version 131024 is loaded in my flying wing, but there weren't good conditions to test it yet. :(
Just to be sure - do I understand right, that altitude control was rewritten and now P term is adjusted via GUI (Alt P)? Does it remaid only P or full PID regulator?
Thanks for explanation!
Roman

PatrikE
Posts: 1976
Joined: Tue Apr 12, 2011 6:35 pm
Location: Sweden
Contact:

Re: Airplane mode RTH

Post by PatrikE »

rbirdie001 wrote:Hi Patrik,
Just to be sure - do I understand right, that altitude control was rewritten and now P term is adjusted via GUI (Alt P)? Does it remaid only P or full PID regulator?
Roman


Use GUI PIDALT P for field adjustments.
Only P is integrated for altitude.

For navigation there is a full PID controlled by Gui NavR P I D.

Let's hope for better weather for testing.

/Patrik

aydineser
Posts: 8
Joined: Mon Jun 17, 2013 11:54 am

Re: Airplane mode RTH

Post by aydineser »

Hi Patrik,

I have noticed a few things in your code ...
Firstly roll compansation in gps.cpp

Code: Select all

 line 1478    GPS_angle[PITCH]+=(abs(att.angle[ROLL]) * ELEVATORCOMPENSATION /100); // Compensate elevator compared with rollAngle 

then later

Code: Select all

line 1546 // Compensate elevator compared with rollAngle
      GPS_angle[PITCH]-= ( abs(att.angle[ROLL]) * ELEVATORCOMPENSATION ) /100;

I am confused... Is booth lines true or necessary ?

end secondly in PID control loop

Code: Select all

line 1527 naverrorD += ((dif - oldif) *navPID_PARAM.kD) * gpsFreq;
line 1528 naverrorD =constrain(naverrorD,-MAX_D,MAX_D);

You have accumulated Differential error just like Integral ?

Best Regards
Aydin

PatrikE
Posts: 1976
Joined: Tue Apr 12, 2011 6:35 pm
Location: Sweden
Contact:

Re: Airplane mode RTH

Post by PatrikE »

Hi Aydin,

I know the ELEVATORCOMPENSATION is added twice.
I don't know at what point it became added the second time.
But since it seems to work as it is i haven't removed any of them.

I would test to remove the first to start with.(Before the constrains)

I actually don't know much about PID.
Any help on this is appreciated..;)

I think the PID is what's missing for launching it in public branch.

Greets
Patrik

aydineser
Posts: 8
Joined: Mon Jun 17, 2013 11:54 am

Re: Airplane mode RTH

Post by aydineser »

Hi patrik,

I am not good at PID theory too. :)
But as far as I know when you accumulate differantial error it becomes something else. Because differantial error
shows how quickly the system recovers the error and behaves like a brake.
I have lested with following line...

Code: Select all

line 1527 naverrorD = ((dif - oldif) *navPID_PARAM.kD) * gpsFreq; 


And gpsFreq, you are using 2Hz, Unless if you dont do it onpurpose, we should use higher, if you have higher rate GPS.
(for example I have UBlox 5Hz)

I know, Tuning PID controller without a proper logging is very difficult task ( for example naverror, integral error, differantial error )

For the elevator roll compensation, As I read from the code negative GPS_angle[PITCH] means climb, positive GPS_angle[PITCH] means dive,
So I will remove the line 1478, because it produces a dive command ( But I have not tested removing it yet )

Code: Select all

line 1478  GPS_angle[PITCH]+=(abs(att.angle[ROLL]) * ELEVATORCOMPENSATION /100); 


Aydin

rbirdie001
Posts: 178
Joined: Fri Apr 01, 2011 10:32 pm
Location: Czech Republic, Prague

Re: Airplane mode RTH

Post by rbirdie001 »

Hi,
I'm trying to follow your discussion but don't feel like having enough knowledge to join it. Because I see it's going close to altitude control which I'm still fighting with, maybe at least my observations could help you:
I tested FW_nav_131024 with commented out all additional conditions for altitude control except of altitude itself so this part of GPS.cpp was commented out:

Code: Select all

// Navigation while Altitude is higher than RTH Alt
/*        if (f.GPS_HOME_MODE && !f.CLIMBOUT_FW && GPS_AltErr >=0 ){           // While we are higher than RTH alt.
          if (GPS_distanceToHome >SAFE_DECSCEND_ZONE){ GPS_angle[PITCH]=0 ;} // RTH Nav Stage Use only ACC to maintain altitude
          else { rcData[THROTTLE]= IDLE_THROTTLE;}                           // RTH Descend only when within 100 meters
          if( f.FAILSAFE_RTH_ENABLE){
            if (GPS_distanceToHome <20  && GPS_AltErr <=5 ){f.ARMED = 0;}    // Home is within 20 meters DISARM and glide.
          }
        } */

I catched good weather and tested on flying field big enough to give me freedom in testing.
I set SAFE ALTITUDE to 90 m :!: and P coeficient for Alt control to 9 (because previously it looked that with smaller values Alt control didn't work at all but with last "for me working version" FW_Nav_130322 I could use only P=3 because higher values vere causing "jumping" and "wing breaking" effect :( http://www.youtube.com/watch?v=Ss67va4QxMk&
Result was that altitude control some way works for me at 131024 but very strange and not very good. After activating RTH plane started diving, then quite low (I guess at 20-30m) it got "kicked" by some control and started climb but was so teribly wobbling in PITCH, that if it wouldn't be my extra reinforced flying wing, it would break it's wing. After few circles it some way stabilized altitude and was circling around, but often was badly wobbling in PITCH.
I have implemented these two lines to reduce wobbles, but my wobles were obviously on PITCH axis (not on ROLL):

Code: Select all

      if (GPS_distanceToHome <=10) dif=0;  // fly straight over home
// Wrap Heading 180
      if (dif <= - 180) dif += 360;
      if (dif >= + 180) dif -= 360;
            if abs(dif > 160) dif = 160; // To resole wobbles turn left. Man's mind :)

IN normal GYRO or ACC mode is the plane stable and not wobbling even at high speed so it looks like wobbles are coming from navigation input.
I have UBLOX NEO 6M 5Hz GPS.
Any further improvement on Alt control would be great, maybe also introducing I term can allow to lower P term which can help reduce wobbles but keep reasonable altitude control.
I took yesterday some videos of that tests (from a hat camera ;) ) so if some of behaviour is visible there (not seen yet), I'll definitely post it for you to see what I'm trying to describe.
Thanks for your effort boys!
Regards
Roman

aydineser
Posts: 8
Joined: Mon Jun 17, 2013 11:54 am

Re: Airplane mode RTH

Post by aydineser »

Hi Roman,

I am using GPS_ALTCORR=3 and its quite sucessfull.
But there is another problem, when you used automatic control booth on throttle and elevator.
In some conditions, for example RTH against wind, your plane gain altitude rapidly, then autopilot reduce throttle ( even use IDDLE THROTTLE )
while commanding elevator down. As a result your plane slows down ( even stops in high winds ) When you are near stall speed, you can not expect
perfect command from the autopilot.

I am using manual throttle (with a switch) when necessary against the wind, It is the quick and dirty solution. But it works.
You can test with P=3 and manual throttle. Higher P value is not the solution. If your plane has speed, altitude control works well.

My plane has returned from a 9km flight while controlling altitude in max 10-15 meter error. - without manual throttle it can be much better, but it may never come home :)

Regards
Aydin

PatrikE
Posts: 1976
Joined: Tue Apr 12, 2011 6:35 pm
Location: Sweden
Contact:

Re: Airplane mode RTH

Post by PatrikE »

Hi Aydin,

You're right about elevator compensation.
If i remember correct i added it because i lost some altitude in turns.
Tested it and it became worse and couldn't understand why.(probably added the dive code)
Forgot about it and tested after a while and added it a second time correct this time.
problem solved (but forgot the first fix)!

I set 2 HZ to get bigger diff between readings.
I use a 10hz gps and don't see the need of that high update on a plane.
First i did run the code every loop.(even in FW_Nav_130322 )
Feel free to experiment.

One thing is for certain...
You become blind when staring at the code for a while!
Obvious errors become invisible.

Keep testing while weather allow.
/Patrik

PatrikE
Posts: 1976
Joined: Tue Apr 12, 2011 6:35 pm
Location: Sweden
Contact:

Re: Airplane mode RTH

Post by PatrikE »

@Roman

The autopilot is working as long as it possibly can to balance the plane.
But as Aydin say if the plane slows down to much the only way it goes is.... Down

Test to increase IDLE_THROTTLE.
Because together with a high SCALER_THROTTLE throttle can decr very fast.
It calculates ( Alt_error * SCALER_THROTTLE ).
Maybe you shouldn't fly slower than CRUICETHROTTLE

And since we don't check actual speed it can be potential problems.

I have also made a mod on the Mixtable for flyingWing.
To keep symmetric controls at full commands.

Code: Select all

   #define ROLLRATE 0.5
   #define PITCHRATE 0.5
    if (f.PASSTHRU_MODE) {    // do not use sensors for correction, simple 2 channel mixing
      servo[3] = (SERVODIR(3,1) * rcCommand[PITCH])*PITCHRATE + (SERVODIR(3,2) * rcCommand[ROLL])*ROLLRATE;
      servo[4] = (SERVODIR(4,1) * rcCommand[PITCH])*PITCHRATE + (SERVODIR(4,2) * rcCommand[ROLL])*ROLLRATE;
    } else {                  // use sensors to correct (gyro only or gyro+acc according to aux1/aux2 configuration
      servo[3] = (SERVODIR(3,1) * axisPID[PITCH])*PITCHRATE   + (SERVODIR(3,2) * axisPID[ROLL])*ROLLRATE;
      servo[4] = (SERVODIR(4,1) * axisPID[PITCH])*PITCHRATE   + (SERVODIR(4,2) * axisPID[ROLL])*ROLLRATE;
    }

rbirdie001
Posts: 178
Joined: Fri Apr 01, 2011 10:32 pm
Location: Czech Republic, Prague

Re: Airplane mode RTH

Post by rbirdie001 »

Hi guys,
thanks for so many ideas to think about!
I currently have little time for that because I have to complete some Iceland photos for Saturday presentation to friends, but then I'll read all again, study the video I took during last RTH test flight and hopefuly there will be visible some of strange behaviour I'm describing.
Just to clarify - I have set P for elevator to 9 (I did it because with smaller values was my plane circling lower and lower until I had to manually pull elevator just 2-3 meters above the ground). :shock:
SCALER_THROTTLE is 8. I have generaly quite strong thrust so stall isn't real problem, my plane flies quite fast (I set it higher exactly because of returning against the wind). Problem is kind of "flutter" which I also call "wobble" or "jumping" in some my posts. Generally it's the same - both elevons make big "wawes" up and down in approx 1 Hz period and because the plane have quite high speed, it causes big stress to wings which normal plane wouldn't survive.
It happens mostly close to home position and obviously comes from navigation code. Because I have aplied some measures to limit wobbles from "GPS heading chaos" close to home (see my previous post) and also I see, that wobles are pure in PITCH, not in ROLL, I gues it has to come from something else - probably altitude control loop. Generally I observed it always from the first versions I tested (FW_Nav_130322), now, after I replaced GPS from 10Hz Mediatek to 5Hz Ublox, oscillations seems to be faster. (But Ublox GPS have in reality faster altitude response than MTK). This also points to altitude control from GPS data.
Additional info: I have #define GPS_LEAD_FILTER, but commented out //#define GPS_FILTERING. Is it OK?
See you later!
Roman

rbirdie001
Posts: 178
Joined: Fri Apr 01, 2011 10:32 pm
Location: Czech Republic, Prague

Re: Airplane mode RTH

Post by rbirdie001 »

HI!
I watched videos I made using "head camera" during my last RTH tests and unfortunately I have to admit, that there is not much to see to show you my problems. Because I really want to make RTH working for me, I'm again reading the code, will try to do some changes and then do new tests (when weather allows). One sunny day I should win over it! :x
In the code I don't understand well some things. Patrik, can you please give me some info about it? (Do you know the advice, that to find mistake in your theory you should explain it to your cleaning lady? :D )

So here are lines in FW_nav_131024 GPS.cpp, where I'm in doubts:
line 1471

Code: Select all

 GPS_AltErr = GPS_altitude - GPS_hold[ALT]; // Negative Altitude error means your'e to low
GPS_altitude should be absolute over the sea level, so is the GPS_hold[ALT] also over the sea level? Where and how it's calculated?
I suppose it from the line 1475, where is the GPS_altitude used like if it's "over MSL".

Code: Select all

int16_t curr_Gps_Alt = GPS_home[ALT] - GPS_altitude;              // Calculate Altitude over home

Edit: Found, it's in MultiWii.cpp, line 1057, understood, looks OK.

line 1478

Code: Select all

GPS_angle[PITCH]+=(abs(att.angle[ROLL]) * ELEVATORCOMPENSATION /100); // Compensate elevator compared with rollAngle
I think, that this line is the wrong one (as previously discussed). It has wrong polarity and position (adding positive value pushes elevator down and all following corrections can affect it's influence) while similar line at the end (around 1550) is the right one (adding negative value pulls elevator up and it has always the same effect because it's behind all other corrections). I'll remove first line and keep second, OK?

Line 1488

Code: Select all

 if(GPS_AltErr < 0 && f.CLIMBOUT_FW && f.GPS_HOME_MODE ){ ... 
Is the flag f.CLIMBOUT_FW set to 1 always, if we get lower than safe alt, or only at the time of RTH activation and then never more while RTH remains active?

Thank you in advance! I want to do all possible corrections in the code and load it by this weekend just for the case there would be good weather at the weekend... ;)
BTW: I got my Orange Open LRS TX+RX, loaded kha's firmware, set everything and it seems to work really great. This should allow me to fly to bigger distances than before so RTH functionality would be REALLY usuefull! :mrgreen:
See you!
Best reagards
Roman

PatrikE
Posts: 1976
Joined: Tue Apr 12, 2011 6:35 pm
Location: Sweden
Contact:

Re: Airplane mode RTH

Post by PatrikE »

Hi Roman,

The flag f.CLIMBOUT_FW is set only when RTH is enabled.

I uploaded a new ver with all changes discussed in the thread fixed.
Tested and works fine on my plane.
-5 degrees and sunny today.. 8-)

Used P3 for Alt
and P2 : I=0.08 : D=0.045 for NavR

This is the changes i make in my config.

Code: Select all

// Settings for Fixedwing_RTH
#define AIRPLANE

#define GPS_PROMINI_SERIAL
#define GPS_BAUD   115200
#define NMEA

#define SERIAL_SUM_PPM         ROLL,PITCH,THROTTLE,YAW,AUX1,AUX2,AUX3,AUX4,8,9,10,11

#define MINTHROTTLE 1000
#define MAXTHROTTLE 2000

#define NO_FLASH_CHECK

// Make rearming in air possible/easier
#undef ONLYARMWHENFLAT
#define DONT_RESET_HOME_AT_ARM

#define MAG_DECLINATION  3.6f


The Nav Pids is not god Tuned because the plane can't really Get on course.
It's almost there But turns back before it's on course for a while.(I & D tuning!)

I also added a deadspan on +/- 1m on altitude!
should remove "flutter" on elevator.

I'll be working all weekend so no more flying for me :(

https://multiwii.googlecode.com/svn/bra ... 131122.rar

Greetings.
/PatrikE

rbirdie001
Posts: 178
Joined: Fri Apr 01, 2011 10:32 pm
Location: Czech Republic, Prague

Re: Airplane mode RTH

Post by rbirdie001 »

Hi Patrik,
I see there are many news in the code so I hope NOW it will start working also for me. :lol:
I made minimal necessary changes only and loaded into my wing. Tomorrow should be reasonable weather, so... ;)
Have as good working weekend as possible!
Roman

rbirdie001
Posts: 178
Joined: Fri Apr 01, 2011 10:32 pm
Location: Czech Republic, Prague

Re: Airplane mode RTH

Post by rbirdie001 »

Hi Patrik,
I hope you had peaceful weekend at work and all robots behaved well :D .
I tried to test new version FW_Nav_131122 but as I had several complications, so not much results :( .
I loaded it and firstly connected bluetooth module to the promini serial port. I did adjustment and servo trimming, test flight - that went OK. Then I plugged GPS into the promini serial, let GPS fix and wanted (as always) to save home by stick gesture but this didn't work :?: . I was trying it several times, reboot, different switch position, arm/disarm (that was normally possible), lower/increase THRO trim... but no gyro and acc calibration activation when PITCH and YAW at minimum. As it was quite windy and cold, I spent some 10 minutes with it and gave up...
I tried to activate RTH anyway and autothrottle started the motor so RTH was really active (home was probably saved when GPS got fix) but I didn't rely much to this "home" because altitude info from GPS could be quite inacurate at the time. Altitude control anyway didn't seem working well but there was too many abnormal conditions to take it seriously (unsure home and strong wind).
When I got back home into warm room, gyro calibration worked always - without GPS fix and with GPS fix as well so I don't understand what was before wrong.
I decided to use next time I2C GPS instead of promini serial because this will allow me to keep GUI connected and don't be so "blind". I have only BT module with range of ~10m. In worst case I should be able to run up and down hill with plane in one hand and notebook in the other but at least "see" inside MWI ;)
Because 131122 still not compile with I2C GPS setting, I'll use this patch: viewtopic.php?f=7&t=2456&start=330#p42557 ,with this it compiles OK.
I'll keep posting about my progress but also here is weather going worse and worse (at least for flying :( ) so it may take longer.
Regards
Roman

rbirdie001
Posts: 178
Joined: Fri Apr 01, 2011 10:32 pm
Location: Czech Republic, Prague

Re: Airplane mode RTH

Post by rbirdie001 »

Can anything ever work for me straightforward without days and weeks troubleshooting?
I prepared new I2C GPS board, modified FW_Nav_131122 config accordingly, uploaded, connected and it communicates but I have 31 I2C errors from the beginning. I aplied this patch: viewtopic.php?f=8&t=4246&start=30#p43393, which helped me in standard 2.3, but it doesn't help in FW_Nav_131122 - I'm still have I2C errors from the beginning. It will probably work anyway, but is anyone sees the solution, it would be better not to have I2C errors... ;)
Roman

PatrikE
Posts: 1976
Joined: Tue Apr 12, 2011 6:35 pm
Location: Sweden
Contact:

Re: Airplane mode RTH

Post by PatrikE »

With help from rbirdie001 with debugging and testing.
We have made progress with the code.

It's now ready to be tested .
https://multiwii.googlecode.com/svn/bra ... 131225.rar
Use Gui from V2.3

I added a textfile with recommendations in the Rar file.

The code uses
Gyro/Acc + Gps ( Mandatory )
If MAG is present it will be used to.
Baro is not used for navigation.

Reset from Gui when you have uploaded the code first time.
Setup servos from Gui.

Set desired altitude to return to with ALT_D in Gui (50 meters default)

Get out and fly.
But look out if Santa's flying low ;)

Happy hollidays

i3dm
Posts: 57
Joined: Tue Oct 01, 2013 4:48 pm

Re: Airplane mode RTH

Post by i3dm »

is this now a stable version for plane flying with RTH for Multiwii?

PatrikE
Posts: 1976
Joined: Tue Apr 12, 2011 6:35 pm
Location: Sweden
Contact:

Re: Airplane mode RTH

Post by PatrikE »

i3dm wrote:is this now a stable version for plane flying with RTH for Multiwii?

I can verify that it works on my plane.
It's safe to fly this version.

It just needs more flight testing and PID tuning.
All navigation stages for RTH works.

A Preflight check is important for Gps navigation!

Make sure You have GPS Lock.
Home position is reset when calibrating gyros.(Not reset at Arming)
Always calibrate gyros (Use stick command)
or reboot FC before takeoff!

Check gps lock
Activate RTH on ground.
Elevator will go up to reach RTH alt if home is set.
Motor will Run at climbThrottle value and not idle when throttle is applied.

Stages of RTH
#1
Set RTH altitude.
If plane is higher use current altitude.

#2
Start a Climbout in 2 stages if plane is to low.
-1: Below 20 meters Full climb with level wings.
-2: Below RTH-Alt Full climb but also start navigation.

#3
Navigate to home maintain altitude.

#4
Descend to the altitude set in Gui with ALT_D
And keep returning to home position until battery run flat or RTH is aborted.

If Failsafe is active.
Motor is disarmed after 1:st pass over home position. (or FAILSAFE_OFF_DELAY times out. Set high for longdistance)
And return altitude will be changed to Home altitude.
In next ver FAILSAFE_OFF_DELAY will be overridden by Fixedwing

I hope for some test reports.
/Patrik

User avatar
Chriss
Posts: 9
Joined: Mon Oct 21, 2013 9:03 pm
Location: Germany

Re: Airplane mode RTH

Post by Chriss »

Hi Patrik,

I have flashed new firmware to my Crius SE V2.5 in my Bixler2. Connect to GUI works fine, also the settings for switches and so on. I have only issues with servo settings. I cant save the settings (reversing) to my board. If I press "Read" (after "Save") its shows me the default settings! :(

FW: 131225
GUI: latest (2.3)

Any solutions?
Best wishes from Germany,
Chriss

P.S.: also BT connection fails with Android and GUI, connection is good, but in Android it shows me "no data received" and GUI dont show real data, only that the board is connected...

EDIT: use MW GUI 2.3pre4 and everythings work fine! ;) I will give a feedback, if I was in the air! ;)

msev
Posts: 186
Joined: Thu Apr 14, 2011 11:49 am

Re: Airplane mode RTH

Post by msev »

Btw are V-tail planes supported? Either vtail+dihedral wing or vtail+wing with ailerons.

Ubx protocol is supported right? (i just define it in config.h), since the notes mentions something about nmea.

i got a spare arduino mega and mpu6050&hmc5883 so I could maybe try it once i finish my testing platform.

Another thing for what is the magnetometer used? Maybe heading hold?

PatrikE
Posts: 1976
Joined: Tue Apr 12, 2011 6:35 pm
Location: Sweden
Contact:

Re: Airplane mode RTH

Post by PatrikE »

Hi msev.
You can use a Vtail plane as Ailerion/Elevator.
Vtail mix with ruddercontroll is NOT available.
It needs a specialmixtable.

Mag is used to get the heading of the plane and is optional.
RTH works just as fine with a mpu6050 & GPS.

This is the latest dev.
MultiWii_140109.rar

Dev is in sync with repository.
Every units in MWii is included in this dev.

rudyauction509
Posts: 1
Joined: Sat Jan 11, 2014 11:33 am

Re: Airplane mode RTH

Post by rudyauction509 »

Not wanting to read 30 pages and a search of the thread for "download" doesn't show anything the past few months, where do I get the code? Also will this combo from hobbyking work with it? http://www.hobbyking.com/hobbyking/stor ... odule.html

I'm looking for a backup RTH for my bixler 2 short/mid range (max 2-3 mile) FPV plane so if I go out of range it will turn around and fly back into range. I don't want to put $100+ into an RTH if this will work. Also I don't care if it lands in the field or maintains an exact altitude or anything, just that it keeps above the trees and flies in the general direction of the field until I can regain control.

PatrikE
Posts: 1976
Joined: Tue Apr 12, 2011 6:35 pm
Location: Sweden
Contact:

Re: Airplane mode RTH

Post by PatrikE »

Here's a link to the latest version.
MultiWii_140109.rar

The Pinout on this FC is not optimal for airplanes.
Some pin's aren't available.
But with some trix it can be fixed.

The code should suit your needs just fine.
RTH can be used as a flightmode activated by switch and FailsafeRTH.

FailsafeRTH will fly the plane home and "Land" at home.

User avatar
Chriss
Posts: 9
Joined: Mon Oct 21, 2013 9:03 pm
Location: Germany

Re: Airplane mode RTH

Post by Chriss »

Hi Patrik,

I will give you a feedback with my Bixler2 and your RTH MultiWii Code! :) I don't change the defaults PID's and with that it works very well! :) Stabilize and RTH works very well! :) Thank you very much for that piece of Software! :)

But I have a issue: if I connect the LiPo and the plane is not leveled, it seems it save this level. Is this right? I thought, I can level with GUI and don't level before each flight.

What changes you make in 140109? I have testet 131225.

Best wishes from Germany!
Chriss

PatrikE
Posts: 1976
Joined: Tue Apr 12, 2011 6:35 pm
Location: Sweden
Contact:

Re: Airplane mode RTH

Post by PatrikE »

Hi,
Good to hear it works.

Changes made since 1225.
Several overflow identified and corrected.
PID regulator. (still needs tuning)
Fully functional FailsafeRTH.

The weather have been flyable.
Help from rbirdie001 with debugging.

The only thing i can think of that affects Boot i've made is in def.h
Row 238 : #undef ONLYARMWHENFLAT.
Test to remove it.

It's there for making ReArm in air easier.

msev
Posts: 186
Joined: Thu Apr 14, 2011 11:49 am

Re: Airplane mode RTH

Post by msev »

PatrikE wrote:Hi msev.
You can use a Vtail plane as Ailerion/Elevator.
Vtail mix with ruddercontroll is NOT available.
It needs a specialmixtable.

Mag is used to get the heading of the plane and is optional.
RTH works just as fine with a mpu6050 & GPS.


Hi Patrik, do you have ez* with rudder+elevator+ailerons or without the ailerons? Option with rudder+elevator+dihedral wing(self stabilizing) would also work?

Any plans for vtail support, since that vtail looks sooo nice on a plane hehe :D ?

So mag "heading hold" mode does not work? It is used just to feed MSP for osd/telemetry? Or is it used also in the navigation routines if one has it defined?


It would be interesting to step by step implement features from your branch into baseflight, for example this was the latest commit regarding alt.hold: https://github.com/multiwii/baseflight/ ... 18f0a18f02

If you could provide some insights on how you do it here, I could relay the info to timecop on irc :), so this mode would work as good as yours. Then later maybe you could help implement some more stuff if possible (my dream would be aeroplane PH&RTH also on baseflight)...Think about it a 20$ acronaze+gps could be all what is needed, same price point like today arduino mega+mpu6050 but much smaller size :)

Post Reply