Airplane mode

This forum is dedicated to software development related to MultiWii.
It is not the right place to submit a setup problem.
Software download
rubadub
Posts: 154
Joined: Mon Apr 28, 2014 2:36 am

Re: Airplane mode

Post by rubadub »

PatrikE wrote:In gps.h.
#define FAILSAFE // Enable RTH failsafe incl Auto DisARM at home to autoland

Comment that too.


aaaah, ok, that must have been it, the defines were all hidden in GPS.h.
Do you need approval to send them to config.h? It would be a lot more helpful if they were in the main config file ;)

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

Re: Airplane mode

Post by PatrikE »

I've just kept the defines separated while testing.
In the Config file is hard to see the trees because of the forrest!..

It should be merged in Config.h
Or even settable from gui.

rubadub
Posts: 154
Joined: Mon Apr 28, 2014 2:36 am

Re: Airplane mode

Post by rubadub »

questions about ROLLRATE and PITCHRATE constants for flying wing's.
What's the reasoning behind selecting the default values of 0.5 for these constants?
What effect would changing them have on flying wing performance?
- I read the code & can understand the algorithm, but I'm trying to get a real-world perspective on how & when these values should be modified for best performance.

What would need to be done in order for these items to be configurable via serial protocol/GUI? In order to test different values for these rates, you'd be forced to modify the code, re-compile & re-upload, which is very impractical.

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

Re: Airplane mode

Post by PatrikE »

What's the reasoning behind selecting the default values of 0.5 for these constants?

It's away to keep symmetrical throws on combinated full throws on Roll/Pitch.
If you apply Roll without the 0.5 constant it can use whole Servorange.
When you then apply elevator that servo can't move past the endpoint.
Then only one servo can move freely while the other is already at endpoint.

Using the constant will limit each RC function to use half the actual servo range.
Leaves room for both axis inside the endpoints and gives symmetrical throws.

Lot's of theory and it's only when you use large throws it will be noticeable.
I usually set it to 0.8 on my plane.

To adjust from Gui means quite some work.
And memory consuming on a 328.

rubadub
Posts: 154
Joined: Mon Apr 28, 2014 2:36 am

Re: Airplane mode

Post by rubadub »

PatrikE wrote:
What's the reasoning behind selecting the default values of 0.5 for these constants?

It's away to keep symmetrical throws on combinated full throws on Roll/Pitch.
If you apply Roll without the 0.5 constant it can use whole Servorange.
When you then apply elevator that servo can't move past the endpoint.
Then only one servo can move freely while the other is already at endpoint.

Using the constant will limit each RC function to use half the actual servo range.
Leaves room for both axis inside the endpoints and gives symmetrical throws.

Lot's of theory and it's only when you use large throws it will be noticeable.
I usually set it to 0.8 on my plane.

To adjust from Gui means quite some work.
And memory consuming on a 328.


thanks for the explanation.
so, how did you come to a value of 0.8 for your flying wing? what caused you to conclude that this value was adequate? How much trial&error did it require? Would you recommend 0.8 as a starting point, or should I simply stick with 0.5?

theailer
Posts: 49
Joined: Tue Sep 24, 2013 9:06 pm

Post by theailer »

It would be quite easy to determine. Just push full up on elevator and see if it's travels half of the servo range or if you have instructions from the manufacturer to determine max elevator deflection. And then do the same for aileron and lastly both together.

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

Re: Airplane mode

Post by PatrikE »

I tested 0.8 and the throws was close to recommendations in the manual for the plane.
It would be easier to be able to adjust from Gui..

In Baseflight version it can be set from CLI.

rubadub
Posts: 154
Joined: Mon Apr 28, 2014 2:36 am

Re: Airplane mode

Post by rubadub »

PatrikE wrote:I tested 0.8 and the throws was close to recommendations in the manual for the plane.
It would be easier to be able to adjust from Gui..

In Baseflight version it can be set from CLI.


ok, thanks.
yes, it would be great to have in the GUI or CLI, at least for the MEGA versions...

rubadub
Posts: 154
Joined: Mon Apr 28, 2014 2:36 am

Re: Airplane mode

Post by rubadub »

quick question:
from looking at the code, it appears that the MOTOR_STOP option doesn't have any effect on FLYING_WING mode.
I've made the following change, but I'm not sure what consequences it might have on Patrik's NAV code

Code: Select all

    /*****************************             FLYING WING                **************************************/
    if (!f.ARMED) {
      servo[7] = MINCOMMAND;  // Kill throttle when disarmed
    } else {
   #if defined(MOTOR_STOP)
      servo[7] = constrain(rcCommand[THROTTLE], MINCOMMAND, MAXTHROTTLE);
        #else
      servo[7] = constrain(rcCommand[THROTTLE], conf.minthrottle, MAXTHROTTLE);
        #endif
    }
    motor[0] = servo[7];


should this be ok, or will it interfere with other throttle-related functions?

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

Re: Airplane mode

Post by PatrikE »

MOTOR_STOP is handled later after all mixers.
And applies on all models.

rubadub
Posts: 154
Joined: Mon Apr 28, 2014 2:36 am

Re: Airplane mode

Post by rubadub »

PatrikE wrote:MOTOR_STOP is handled later after all mixers.
And applies on all models.


I was under the impression that this wasn't the case when using a servo pin for throttle. Also, FLYING_WING mode has a motor count of zero in def.h, which would it exclude it from the "motor normalization" section of the mixer. I've enabled MOTOR_STOP, armed it, and I'm still seeing the motor output jump to minThrottle instead of minCommand.

EDIT:
nevermind, I was using the 'THROTTLESERVO' option, which I just realized wasn't necessary.
So, it works fine with the normal motor[0] pin (D3 on the MEGA). The code still looks like it might have issues for anyone using the 'THROTTLESERVO' option. Unless I'm missing something, at no point is the MOTOR_STOP option handled for the servo outputs. It might be something to look into...

rubadub
Posts: 154
Joined: Mon Apr 28, 2014 2:36 am

Re: Airplane mode

Post by rubadub »

question:
what's the best practice for deciding on "servo rates"? It seems that the only effect they have is to multiply the PID factor by the specified percentage, so then couldn't the values simply be set to 100 and then have the throw controlled only by the PID term? Or, am I missing something? It seems like it would be easier to just dial the PID values up or down vs. having to recompile to experiment with the servo rates (I don't believe that they can be configured over MSP or can they?)...

Basically, what's the best way to go about configuring these values?
FYI, this is for a bixler1 airframe...

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

Re: Airplane mode

Post by PatrikE »

You can do most servo settings from the gui.
Look at the servo tab.

brewski
Posts: 483
Joined: Tue Apr 29, 2014 12:04 am
Location: Cleveland Qld Australia

Re: Airplane mode setup

Post by brewski »

I have a Crius SE V2.3 328P based FC as well as UBlox 6M sitting in my (good) junk box. I dug out my Bixler 1.1 the other day & after reading some posts/threads on MW Airplane Mode I thought I might give the old plane some intelligence.
Is there any guide on how to set up a 328P based FC running MW Airplane mode with a plane such as the Bixler that has ailerons, rudder & elevator?
Also with such a basic FC is GPS RTH possible?

Cheers..B

Hoppsan_84
Posts: 51
Joined: Thu Jul 10, 2014 2:13 pm

Re: Airplane mode

Post by Hoppsan_84 »

Short answer, Yes.
I use PatrikE firmware in my Easy Star with a Arduino Mini, and a neo6 gps.

Works perfectly with RTH, PH and Failsafe

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

Re: Airplane mode

Post by PatrikE »

Is there any guide on how to set up a 328P based FC running MW Airplane mode with a plane such as the Bixler that has ailerons, rudder & elevator?

http://fotoflygarn.blogspot.com/2012/03 ... -same.html
http://fotoflygarn.blogspot.com/2014/04 ... plane.html
Last edited by PatrikE on Thu Oct 02, 2014 10:25 am, edited 1 time in total.

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

Re: Airplane mode

Post by PatrikE »

Hoppsan_84 wrote:Short answer, Yes.
I use PatrikE firmware in my Easy Star with a Arduino Mini, and a neo6 gps.

Works perfectly with RTH, PH and Failsafe


Nice that you managed to get it working Hoppsan..

rubadub
Posts: 154
Joined: Mon Apr 28, 2014 2:36 am

Re: Airplane mode

Post by rubadub »

FYI, for anyone using FLYING_WING...

In case anyone wants to play with the rate settings for pitch&roll without having to recompile, here's what I did...

Code: Select all

//Output.cpp, mixTable() function
  #elif defined( FLYING_WING )
  #elif defined( FLYING_WING )
    /*****************************             FLYING WING                **************************************/
    if (!f.ARMED) {
      servo[7] = MINCOMMAND;  // Kill throttle when disarmed
    } else {
      servo[7] = constrain(rcCommand[THROTTLE], conf.minthrottle, MAXTHROTTLE);
    }
    motor[0] = servo[7];

   int8_t s3d=conf.servoConf[3].rate < 0 ? -1:1;
   int8_t s4d=conf.servoConf[4].rate < 0 ? -1:1;
   
   if (f.PASSTHRU_MODE) {   
      // do not use sensors for correction, simple 2 channel mixing
      servo[3] = (s3d*rcCommand[PITCH]*(int32_t)abs(conf.servoConf[3].rate)  - s3d*rcCommand[ROLL]*(int32_t)abs(conf.servoConf[4].rate))/100L;
      servo[4] = (s4d*rcCommand[PITCH]*(int32_t)abs(conf.servoConf[3].rate) + s4d*rcCommand[ROLL]*(int32_t)abs(conf.servoConf[4].rate))/100L;

   } else {                  // use sensors to correct (gyro only or gyro+acc according to aux1/aux2 configuration
      servo[3] = (s3d*axisPID[PITCH]*(int32_t)conf.servoConf[3].rate    -  s3d*axisPID[ROLL]*(int32_t)conf.servoConf[4].rate)/100L;
      servo[4] = (s4d*axisPID[PITCH]*(int32_t)conf.servoConf[3].rate   +  s4d*axisPID[ROLL]*(int32_t)conf.servoConf[4].rate)/100L;
   }
   
   servo[3] += get_middle(3);
   servo[4] += get_middle(4);

the integer math might stand to be cleaned up and a bit more optimized, but this seems to work ok for now & for my needs.

what that does is use the user-configurable rates for servos 3 & 4 in place of the PITCHRATE and ROLLRATE constants.

A negative number indicates an reversed servo.
On my teksumo wing, I have left servo set to -50 and right servo to 50.

use at your own risk, but this is working great for me.
I can configure the rates on the fly via ez-GUI's servo settings window, which is pretty cool...

Hoppsan_84
Posts: 51
Joined: Thu Jul 10, 2014 2:13 pm

Re: Airplane mode

Post by Hoppsan_84 »

PatrikE wrote:
Hoppsan_84 wrote:Short answer, Yes.
I use PatrikE firmware in my Easy Star with a Arduino Mini, and a neo6 gps.

Works perfectly with RTH, PH and Failsafe


Nice that you managed to get it working Hoppsan..



Works incredibly well. A bit boring almost. But it can be turned off if it gets too easy :D

brewski
Posts: 483
Joined: Tue Apr 29, 2014 12:04 am
Location: Cleveland Qld Australia

Re: Airplane mode

Post by brewski »

PatrikE wrote:
Is there any guide on how to set up a 328P based FC running MW Airplane mode with a plane such as the Bixler that has ailerons, rudder & elevator?

http://fotoflygarn.blogspot.com/2012/03 ... -same.html
http://fotoflygarn.blogspot.com/2014/04 ... plane.html


Wow this is fantastic! This is what Multiwii needs for multirotors.
Something like this professionally done blog would make it so much easier for noobies to MW & do away with the so out of date & un user friendly WiKi.
I am now determined & fully informed as how to setup my Bixler V1.1 & start to use it in FPV role with confidence.

rubadub
Posts: 154
Joined: Mon Apr 28, 2014 2:36 am

Re: Airplane mode

Post by rubadub »

before I scour google, I wanted to ask first...

is there currently a hack to enable control of pan/tilt servos for an FPV cam on a 4-servo AIRPLANE setup within MW & on a MEGA board? The last piece in my puzzle is controlling the PT gimbal from the MW, since I have a single, long lead from the RX to the FC (running PPM Sum). I'd like to use SERVO1 and SERVO2 for pan&tilt, and have the values simply pass through based on my specified channel inputs (channels 11 & 12).

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

Re: Airplane mode

Post by PatrikE »

I haven't tested but a wild guess.
If you don't enable camstab checkbox you should be able to assign a channel for manual control.

You're right about the need to be able to adjust Rates for Roll/Elevator from Gui.
Will look at it.

rubadub
Posts: 154
Joined: Mon Apr 28, 2014 2:36 am

Re: Airplane mode

Post by rubadub »

thinking about possibly doing the following...

Code: Select all

//config.h
  /***********************          FPV PAN TILT                       ***********************/   
   #define FPV_PTZ
   #define PAN_SERVO 1
   #define TILT_SERVO 2

   #define PAN_CHANNEL 11
   #define TILT_CHANNEL 12


Code: Select all

//Output.cpp, mixTable() function
  /************************************************************************************************************/
  /****************************                Cam stabilize Servos             *******************************/
...
  #if defined(FPV_PTZ)
    servo[PAN_SERVO-1] = rcData[PAN_CHANNEL-1];
    servo[TILT_SERVO-1] = rcData[TILT_CHANNEL-1]; 
  #endif
 


can't test today, so will test & know if it works or bombs tomorrow....
I first need to make sure that AIRPLANE config will also enable SERVO1 and SERVO2 outputs.
thoughts???

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

Re: Airplane mode

Post by PatrikE »

I think you need to add a define in def.h to increase the numbers of servos
At the end of the Airplane defines.

Code: Select all

...
  #endif
  #if defined(FPV_PTZ) 
    #define PRI_SERVO_FROM   PAN_SERVO
  #endif   
#elif defined(BI)
.....

Then it should work.
But maybe lock the servos to 1 & 2

rubadub
Posts: 154
Joined: Mon Apr 28, 2014 2:36 am

Re: Airplane mode

Post by rubadub »

PatrikE wrote:I think you need to add a define in def.h to increase the numbers of servos
At the end of the Airplane defines.

Code: Select all

...
  #endif
  #if defined(FPV_PTZ) 
    #define PRI_SERVO_FROM   PAN_SERVO
  #endif   
#elif defined(BI)
.....

Then it should work.
But maybe lock the servos to 1 & 2

thanks Patrik...
you're right, it might just be easier & more reliable to fix it to servos 1 & 2 for the pan&tilt motions.
hopefully, I'll get a chance to test tomorow...

this shouldn't interfere with the standard AIRPLANE servo configuration, or with any other parts of the PWM setup in MW, correct?

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

Re: Airplane mode

Post by PatrikE »

I added PTZ to test.
Codebase is the latest RTH code for planes.

Just be careful to not overload your ESC 5v BEC with too many servos.
Then the FC reboots and plane will go down!....
Don't ask how i know! ;)

MultiWii_PTZ.zip
PTZ is still untested but compiles.

brewski
Posts: 483
Joined: Tue Apr 29, 2014 12:04 am
Location: Cleveland Qld Australia

Re: Airplane mode

Post by brewski »

PatrikE wrote:
Is there any guide on how to set up a 328P based FC running MW Airplane mode with a plane such as the Bixler that has ailerons, rudder & elevator?

http://fotoflygarn.blogspot.com/2012/03 ... -same.html
http://fotoflygarn.blogspot.com/2014/04 ... plane.html


I downloaded the firmware via the link in blog (Ref. 140402) & when I either Verify or try to upload to my Crius SE V2.5 I get compile error & stops at
" conf.failsafe.throttle =failsafe throttle"
The only settings I changed in config.h were to set Airplane & board to Crius se V2.0. Is there something else I need to set before it will compile?

Another question. I normally clear EEProm before uploading new firmware, but EEProm clear is not shown in this customised IDE. I guess I can just clear it using standard Arduino IDE first.

rubadub
Posts: 154
Joined: Mon Apr 28, 2014 2:36 am

Re: Airplane mode

Post by rubadub »

PatrikE wrote:I added PTZ to test.
Codebase is the latest RTH code for planes.

Just be careful to not overload your ESC 5v BEC with too many servos.
Then the FC reboots and plane will go down!....
Don't ask how i know! ;)

MultiWii_PTZ.zip
PTZ is still untested but compiles.


I just wanted to let you know how the initial testing went...

I hooked everything up, configured the code, and powered up, but the PT servos wouldn't move no mater what I did. It took me a couple of hours of testing, checking connections, etc., before I figured out that servos 1 & 2 on pins 44 & 45 (for MEGA_HW_PWM) were using TIMER5. I'm running a CRIUS AIOP V2 which has a dedicated PPM pin on input PL1. However, the code for enabling PPM on PL1 also requires the use of TIMER5, so obviously there was a conflict. I ended up having to move the PPM signal over to A8 & the PT servos came alive.

So, it seems to be working fine. The real test will be in the air.

Another question:
I'm getting very close to ready for my maiden MW plane flight, and I'm a bit anxious about testing the NAV/RTH features. I was wondering if anyone here has any videos demonstrating the RTH features that Patrik has implemented? I'd just like to get a better idea of what to expect on my maiden flight. Also, if anyone has a working set of PID values for a Bixler/EZ-star/Sky Surfer that I can use as a starting point, I'd really appreciate it, thanks...

Hoppsan_84
Posts: 51
Joined: Thu Jul 10, 2014 2:13 pm

Re: Airplane mode

Post by Hoppsan_84 »

You can use the default pids, I do this on my easystar. Only pid I have changed is yaw I=0
When you activate RTH the plane can hesitate before it decides what direction to turn to.
When I had my GPS at 1Hz the plane navigated in a S shape but whit 5Hz it flyes/navigat really good.

rubadub
Posts: 154
Joined: Mon Apr 28, 2014 2:36 am

Re: Airplane mode

Post by rubadub »

update on the PTZ functionality testing.
The servo scaling on servos 1&2 needs to be disabled for PTZ
(it's used for gimbal, but not needed here since we want pure pass-thru from rc for pan/tilt servo control).

Output.cpp, mixTable() function

Code: Select all

/************************************************************************************************************/
  // add midpoint offset, then scale and limit servo outputs - except SERVO8 used commonly as Moror output
  // don't add offset for camtrig servo (SERVO3)
  #if defined(SERVO)
    for(i=SERVO_START-1; i<SERVO_END; i++) {

      #if !defined(FPV_PTZ)
      if(i < 2) {
        servo[i] = map(servo[i], 1020,2000, conf.servoConf[i].min, conf.servoConf[i].max);   // servo travel scaling, only for gimbal servos
      }
      #endif

    #if defined(HELICOPTER) && (YAWMOTOR)
      if(i != 5) // not limit YawMotor
    #endif
        servo[i] = constrain(servo[i], conf.servoConf[i].min, conf.servoConf[i].max); // limit the values
    }

brewski
Posts: 483
Joined: Tue Apr 29, 2014 12:04 am
Location: Cleveland Qld Australia

Re: Airplane mode

Post by brewski »

brewski wrote:
PatrikE wrote:
Is there any guide on how to set up a 328P based FC running MW Airplane mode with a plane such as the Bixler that has ailerons, rudder & elevator?

http://fotoflygarn.blogspot.com/2012/03 ... -same.html
http://fotoflygarn.blogspot.com/2014/04 ... plane.html


I downloaded the firmware via the link in blog (Ref. 140402) & when I either Verify or try to upload to my Crius SE V2.5 I get compile error & stops at
" conf.failsafe.throttle =failsafe throttle"
The only settings I changed in config.h were to set Airplane & board to Crius se V2.0. Is there something else I need to set before it will compile?

Another question. I normally clear EEProm before uploading new firmware, but EEProm clear is not shown in this customised IDE. I guess I can just clear it using standard Arduino IDE first.


Can anyone answer the above? If not I will move it to Config & setup.

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

Re: Airplane mode

Post by PatrikE »

There seems to be something mixed up in the defines for failsafe.
If you enable #define FAILSAFE in config it will work.
Or if you enable GPS as you probably intended since you use this dev code.

I need to check the names because it dont seem to be disabled everywhere.

brewski
Posts: 483
Joined: Tue Apr 29, 2014 12:04 am
Location: Cleveland Qld Australia

Re: Airplane mode

Post by brewski »

Hi Patrik
I'll give it a try. I really want to try it on my Bixler.

brewski
Posts: 483
Joined: Tue Apr 29, 2014 12:04 am
Location: Cleveland Qld Australia

Re: Airplane mode

Post by brewski »

I uncommented Failsafe as well as 12C GPS & it compiled & apparently uploaded. Blue LED flashed on Crius SE 2.5 & although loads of stuff showed in IDE download window(not normally seen) there were no apparent errors & IDE reported file size. When I connected to MW2.3 Config (I'm running 2.3 Eos Bandi B7) it still shows a quad & the Aux & other settings that had made when using this board on my quad previously.
Do I need to run a special version of MW2.3 for this Airplane 140402?

Update. I tried loading MW2.3 with modifications for Airplane instead of previous 140402 to see is this worked. I cleared EEProm first. I got AVRDude Sync error & when I went into MW Config 2.3 (normal) it was still a quad with my original settings..Crazy?

Update. I Googled the AVRDude Sync error & most likely cause is USB driver. I recall I had trouble connecting to the Crius SE using FTDI board initially (I'm running Win8.1) & I found that I needed special driver from FTDI. I recently reloaded Arduino IDE 1.5.4 which must have overwritten USB driver. I reloaded FTDI driver for Win7/Win8/Win8.1 & it looks good in Hardware, lights flash on board but still get AVRDude sync error ..I give up!

brewski
Posts: 483
Joined: Tue Apr 29, 2014 12:04 am
Location: Cleveland Qld Australia

Re: Airplane mode

Post by brewski »

SOLVED! I tried it on my old laptop running WInXP & still got sync error. I then rechecked all settings & board settings was on Uno. Selected Promini 16Mhz & it programmed ok.
Board now shows Airplane symbol & V231 in MW Config :D

As I already have a model created for the Bixler on my Spektrum DX7 I will use this. Any one out there who has modified a Bixler (or similar with ailerons) got any tips on suggested Aux settings, mixes PIDs etc for initial flight?
Also with the FC do you take off enabled or Passthru & what about landing?
Cheers..B

Hoppsan_84
Posts: 51
Joined: Thu Jul 10, 2014 2:13 pm

Re: Airplane mode

Post by Hoppsan_84 »

In the beginning I always had passthru at take off but not at landing, Now days i pretty mutch always has horison on.
Its like flying a train as Patrik put it.

universam
Posts: 14
Joined: Thu Nov 20, 2014 4:41 pm

Re: Airplane mode

Post by universam »

I'm using MWii on a glider now quite perfectly adjusted - gyro, horizon etc work so nice that I am really exited about this wonderful project! :D

Only one behavior is giving me headache, on acrobatic flying the gyro overshoots / continues although I release the sticks!
So for instance, when I make a roll 360° and I center the sticks, the plane continues to roll for another 0,5 to 1 second so making a roll of about 450° before is stops as expected. That doesnt happen on passthru mode.

On the ground I can see that behaviour too: When I make normal moves with gyro enabled, the servos follow my input normaly. But when I push the sticks to a corner the servos freeze in that position for about 0,7s.

Any idea what could be the reason?

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

Re: Airplane mode

Post by PatrikE »

Can you see if behaves the same in GUi?
You can test if it makes any difference to lower the throws a bit.

universam
Posts: 14
Joined: Thu Nov 20, 2014 4:41 pm

Re: Airplane mode

Post by universam »

Yes, in GUI you can see that servo goes full way 2000 and keeps it on while stick data is already back to 1500.
I've tested it on a 328P and also on a Crius Pro 2560, with your RTH version aswell as with the 2.3 original.

Does not to happen when i put the stick to ~1900. Looks like it is winding up somewhere.

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

Re: Airplane mode

Post by PatrikE »

The V2.3 Gui can only show 1000-2000 on rc inputs.
Maybe your TX send a value that exceeds the values.
Here is a modified Gui with 900 - 2100 range.
Modified MultiWiiConf

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

Re: Airplane mode

Post by PatrikE »

I have made tests on the bench.
I can get my radio to go Maximum 990 - 1014.
And i can't Get it to behave like you described..
Ensure your TX don't output to large throws..

universam
Posts: 14
Joined: Thu Nov 20, 2014 4:41 pm

Re: Airplane mode

Post by universam »

Thank you for verifying and the modded conf.
I checked the maximums, are around 1990.

Unfortunately I can't reproduce it again today, yesterday on flying field i had view witnesses :( Have this problem since ever.

What can be different?
First, yesterday was pretty cold, around 8C. Read somewhere that the MPU6050 gyro gets out of specification on extreme temperature :roll: There was also an empirical change recently done for the ITG for the same reason AFAIK...

Also at home I can't simulate the G's that happen during acrobatic flying. When I think twice, It happens not on small turns but on heavy double rolls like 720 degrees.
Could the LPF kick in here? I have 188 Hz set up.

Or another idea, if the roll rate is higher than the aircraft performs, would the calculation expect a further move than I was made?

Sorry for not having more precise results.

rubadub
Posts: 154
Joined: Mon Apr 28, 2014 2:36 am

Re: Airplane mode

Post by rubadub »

@PatrikE
any plans to setup some kind of 'cruise' mode (such as what the APM has) where you can point the plane on a specific heading and it'll hold that heading? I'm assuming that mag hold mode doesn't work for planes, though I haven't checked the code myself to verify this.

Any ideas on what would it take to get this to work?
Ideally, it seems like it would be best achieved by adding AIL/ELE(and THR?) & doing coordinated turns in order to make the flight corrections, instead of just rudder (which might not be strong enough to achieve it?). Any thoughts???

I believe the APM does it by setting up a temporary waypoint at some distance based on the current heading & then navigates toward it. I wonder if this would be the best way to achieve it, or if there's a simpler solution... thoughts?

universam
Posts: 14
Joined: Thu Nov 20, 2014 4:41 pm

Re: Airplane mode

Post by universam »

PatrikE wrote:I have made tests on the bench.

Today did further test and I can confirm it happens again but unfortunately only during flights :? So after some heavy rolls g.e. 720° it continues to roll 90°-150° further before it stops. I can see the ailerons keep on full scale.
I've also played with PID settings, didnt see any difference.

I have connected MWii via Sum PPM, will try other method.

Any idea - probably how to simulate that at home?

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

Re: Airplane mode

Post by PatrikE »

It's kind of hard to simulate the rotation on the bench.
Maybe it can be tested with HIL simulation.
viewtopic.php?f=8&t=5046
treym is the expert on HIL.

rubadub
Posts: 154
Joined: Mon Apr 28, 2014 2:36 am

Re: Airplane mode

Post by rubadub »

Does anyone see any possible problem with enabling ANGLE or HORIZON mode along with GPS_HOME mode within the MWC Plane code? It would be nice to simplify my AUX switch config and just set GPS_HOME to use a single AUX setting to enable both RTH+ANGLE.

I figured that I could just add it here:
Multiwii.cpp

Code: Select all

  #if GPS
    if ( (f.GPS_HOME_MODE || f.GPS_HOLD_MODE) && f.GPS_FIX_HOME ) {

      //enable angle mode   
      f.ANGLE_MODE=1;

      #if !defined(FIXEDWING)
...
/***************** Start of FixedWing Nav *****************/
      #else   // Navigation with Planes
// Navigation with Planes Separated from MWii Tab for Devlopment.
// Code is Moved to FX_Nav TAB.
        FW_NAV();
      #endif



EDIT:
also, another similar question: would it be ok to the enable the throttle while in passthru mode? I realize that it's meant as a safety feature, but it seems like kind of a waste to be forced to arm the board while in passthru. By definition, "passthru" mode seems to imply that all of the RC controls (throttle & surfaces) will be passed through to the plane. Any thoughts?

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

Re: Airplane mode

Post by PatrikE »

You can solve it like you did.
For next version i have made ACC atomatic with GPS modes.

The ARM function is a MWii standard for motors.
And is handled commonly after all mixers.
To make a mode-based Armed can be messy.

If it's powered up in PThru Arms..
Should it be disarmed if mode is switched later then?

In a GPS plane it would enter a RTH if you turn transmitter of by misstake etc.

rubadub
Posts: 154
Joined: Mon Apr 28, 2014 2:36 am

Re: Airplane mode

Post by rubadub »

PatrikE wrote:You can solve it like you did.
For next version i have made ACC atomatic with GPS modes.

The ARM function is a MWii standard for motors.
And is handled commonly after all mixers.
To make a mode-based Armed can be messy.

If it's powered up in PThru Arms..
Should it be disarmed if mode is switched later then?

In a GPS plane it would enter a RTH if you turn transmitter of by misstake etc.


ok, how about something like this?

Code: Select all

//Output.cpp, 
//apply same code below for "#elif defined(AIRPLANE)"

  #elif defined( FLYING_WING )
    /*****************************             FLYING WING                **************************************/
   if (f.ARMED || f.PASSTHRU_MODE) {
      servo[7] = constrain(rcCommand[THROTTLE], conf.minthrottle, MAXTHROTTLE);
   }else{
      servo[7] = MINCOMMAND;  // Kill throttle when disarmed
   }
   motor[0] = servo[7];

//further below in same function...
  /****************                normalize the Motors values                ******************/
    maxMotor=motor[0];
    for(i=1; i< NUMBER_MOTOR; i++)
...
//add passthru test, let the motor value(s) go through
      if (!f.ARMED
#if defined(FIXEDWING)
           && !f.PASSTHRU_MODE
#endif
){
        motor[i] = MINCOMMAND;
    }

do you see any obvious issues with something like that?

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

Re: Airplane mode

Post by PatrikE »

It can work...
Test!...

universam
Posts: 14
Joined: Thu Nov 20, 2014 4:41 pm

Re: Airplane mode

Post by universam »

Hi,
I would like to make a little contribution. We found out during flying that the current algorithm of Flaperons have an impact on flight characteristics, making the plane spongy with full flaps so decreasing effectiveness of the ailerons.

Currently the flaperons are added additive to ailerons which has 2 problems.

1. Given that flaps are on 400, when you add more than 100 scale for Roll, you hit the limit it gets constrained, the left 400 on Roll is ignored!
2. The other wing, where you should now have 400 + -500 = 900 path the servo will take only 500 ==> -100, so not using the remaining path.

Practically in flying we noticed that the last 50% of servo scale have much less reaction than the first.
What would be the goal?

The idea is to always propotional use the remaining servo path that is still available (which was not consumed by flaps).
For instance, on flap 400, the roll of 250 (50%) would be (full scale 500 - flaps 400) = left 100 * propotional Roll 50% == add 50 to 400.
In that example Wing 1 ==450 and Wing 2 (50% of 900 (400 + -500) == -450 ) == -50.

That means, you will always have full Aileron Roll reaction, regardless if you have full flaps or not! :D Honestly, on full Roll you basically dont have flaps function - but that situation is an emergency situation where you desparetely need roll and forget about flap.
To better understand the difference here is a comparison attached.

This is the current implementation:

Code: Select all

    if(f.PASSTHRU_MODE){   // Direct passthru from RX
      servo[3] = rcCommand[ROLL] + flapperons[0];     //   Wing 1
      servo[4] = rcCommand[ROLL] + flapperons[1];     //   Wing 2


This is my proposed algorithm:

Code: Select all

    if(f.PASSTHRU_MODE){   // Direct passthru from RX
        servo[3] = (rcCommand[ROLL]*(500.0-(rcCommand[ROLL]<0 ? -flapperons[0]: flapperons[0])))/500.0 + flapperons[0];     //   Wing 1
        servo[4] = (rcCommand[ROLL]*(500.0-(rcCommand[ROLL]<0 ? -flapperons[1]: flapperons[1])))/500.0 + flapperons[1];     //   Wing 2   


I've tested it and it works nicely. The same applies of course for gyro mode. I'm currently thinking about making it faster with integer calculation.

I hope that of some use and would appreciate any comment.

Sam

EDIT:

Here is the integer version, it gives the same results but I think it should be faster:

Code: Select all

if(f.PASSTHRU_MODE){   // Direct passthru from RX
    servo[3] = (int32_t) rcCommand[ROLL] * (500 - (rcCommand[ROLL]<0 ? -flapperons[0]: flapperons[0])) / 500 + flapperons[0];     //   Wing 1
    servo[4] = (int32_t) rcCommand[ROLL] * (500 - (rcCommand[ROLL]<0 ? -flapperons[1]: flapperons[1])) / 500 + flapperons[1];     //   Wing 2
Attachments
comparison.jpg

Post Reply