Page 7 of 12

Re: Altitude Hold improvement solution

Posted: Thu Nov 08, 2012 3:01 pm
by vpb
Cant wait to test your new improvement, Mahowik! Throttle sticked with vertical velocity! now alt hold is very good in AP mode (ALTHOLD_FAST_THROTTLE_CHANGE commented out) but it's very slow to control height with throttle stick outside deadband.

And can I merge this code to my current r1177?

Re: Altitude Hold improvement solution

Posted: Thu Nov 08, 2012 6:42 pm
by mahowik
mahowik wrote:I'm going to add this code to my branch soon...

Done:

1) Vario PID controller implementation.

Code: Select all

/* In this mode, throttle stick position gives a desired vario. Regulation is divided into two parts, when throttle stick is inside ALT_HOLD_THROTTLE_NEUTRAL_ZONE, 
   * the current althold regulation is used. When throttle stick is out of deadband, it ascend or descend with a desired vario.
   *
   * but if it's commented: Smooth alt change routine is activated, for slow auto and aerophoto modes (in general solution from alexmos).
   * It's slowly increase/decrease altitude proportional to stick movement (+/-100 throttle gives about +/-50 cm in 1 second with cycle time about 3-4ms).
   */
  #define VARIO_ALT_CHANGE
  #define VARIO_P 20    // it's force to get desired vario
  #define VARIO_D 7     // regulate the speed of vario change and prevent oscillations of PID controller, e.g. if VARIO_D=0 it means that speed to get desired vario (by throttle stick) will be max

Try to play with VARIO_P and VARIO_D...

Max vertical speed limited about +/-3m/s. But I suppose you can get 4-5m/s because calculated vario (vertical velocity) based on accZ with deadband and during integration acceleration to velocity "part of that" will be lost and actually measured 100cm/s equal to real 130..160cm/s. Where algorithm works with the measured values with defined limitation of 3m/s which can be equal to real 4-5m/s...


And some features from my last B[x]-releases:
2) possibility to set predefined initial throttle for AltHold from GUI by setting MID (middle/hover) point of expo throttle.

Code: Select all

/*  Predefined initial throttle for AltHold will be calculated from MID (middle/hover) point of expo throttle from GUI 
   *  (BUT not taken from current throttle value on AltHold activation).
   *  I.e. pls. use GUI to set MID point of throttle expo as initial throttle.
   *  Note: Value specified by define it's additional compensation for battery consumption
   */
  //#define INITIAL_THROTTLE_HOLD_FROM_MID_EXPO_POINT 50 

3) protection from ARM if BARO activated
4) condition to keep "I" parts on throttle less then MINCHECK for acc, gyro if BARO activated. To avoid lost of the stability accumulated by "I" part of PID controller... It's related to stability of heading, acro, stable modes...

Pls. note that is not tested on the fly yet. Only some initial GUI night testing... So keep your finger on the switch... ;)

svn revision: http://code.google.com/p/multiwii/source/detail?r=1257

thx-
Alex

Re: Altitude Hold improvement solution

Posted: Thu Nov 08, 2012 6:43 pm
by mahowik
vpb wrote:now alt hold is very good in AP mode (ALTHOLD_FAST_THROTTLE_CHANGE commented out) but it's very slow to control height with throttle stick outside deadband.

In that solution vertical speed can be regulated by ALT D pid param. I suppose you used D>50. Try to use 30..40
In my config with ALT D=30 max speed was as desired about 2m/s...
Also to increase max vertical speed you can change delimiter here in MultiWii.ino:

Code: Select all

        // Slowly increase/decrease AltHold proportional to stick movement ( +100 throttle gives ~ +50 cm in 1 second with cycle time about 3-4ms)
        AltHoldCorr+= rcCommand[THROTTLE] - initialThrottleHold;
        if(abs(AltHoldCorr) > 500) {
          AltHold += AltHoldCorr/500;
          AltHoldCorr %= 500;
        }


e.g. 250 to get double speed, i.e. +100 throttle should give about +100cm/s

Code: Select all

        // Slowly increase/decrease AltHold proportional to stick movement ( +100 throttle gives ~ +100 cm in 1 second with cycle time about 3-4ms)
        AltHoldCorr+= rcCommand[THROTTLE] - initialThrottleHold;
        if(abs(AltHoldCorr) > 250) {
          AltHold += AltHoldCorr/250;
          AltHoldCorr %= 250;
        }


vpb wrote:And can I merge this code to my current r1177?

yes, you can compare the sources and add the changes...

thx-
Alex

Re: Altitude Hold improvement solution

Posted: Sun Nov 11, 2012 2:35 pm
by diyboy
mahowik wrote:
mahowik wrote:I'm going to add this code to my branch soon...

Done:

1) Vario PID controller implementation.

Code: Select all

/* In this mode, throttle stick position gives a desired vario. Regulation is divided into two parts, when throttle stick is inside ALT_HOLD_THROTTLE_NEUTRAL_ZONE, 
   * the current althold regulation is used. When throttle stick is out of deadband, it ascend or descend with a desired vario.
   *
   * but if it's commented: Smooth alt change routine is activated, for slow auto and aerophoto modes (in general solution from alexmos).
   * It's slowly increase/decrease altitude proportional to stick movement (+/-100 throttle gives about +/-50 cm in 1 second with cycle time about 3-4ms).
   */
  #define VARIO_ALT_CHANGE
  #define VARIO_P 20    // it's force to get desired vario
  #define VARIO_D 7     // regulate the speed of vario change and prevent oscillations of PID controller, e.g. if VARIO_D=0 it means that speed to get desired vario (by throttle stick) will be max

Try to play with VARIO_P and VARIO_D...

Max vertical speed limited about +/-3m/s. But I suppose you can get 4-5m/s because calculated vario (vertical velocity) based on accZ with deadband and during integration acceleration to velocity "part of that" will be lost and actually measured 100cm/s equal to real 130..160cm/s. Where algorithm works with the measured values with defined limitation of 3m/s which can be equal to real 4-5m/s...

I also added useful feature: when you activate the althold, initial throttle taken from stick (or calculated from INITIAL_THROTTLE_HOLD_FROM_MID_EXPO_POINT, see below), but actually it's not precised throttle for hovering... after one-two second it's become stabilized by althold PID regulator and BaroPID it's correction for initial throttle... And when we start regulate altitude, initial throttle will be corrected for hovering...

Code: Select all

if (!isAltChanged) {
          // apply real initial throttle hover (it's stabilized when alt hold activated) here before changing the altitude
          initialThrottleHoldOutput = initialThrottleHoldOutput + BaroPID;
          isAltChanged = 1;
        }



And some features from my last B[x]-releases:
2) possibility to set predefined initial throttle for AltHold from GUI by setting MID (middle/hover) point of expo throttle.

Code: Select all

/*  Predefined initial throttle for AltHold will be calculated from MID (middle/hover) point of expo throttle from GUI 
   *  (BUT not taken from current throttle value on AltHold activation).
   *  I.e. pls. use GUI to set MID point of throttle expo as initial throttle.
   *  Note: Value specified by define it's additional compensation for battery consumption
   */
  //#define INITIAL_THROTTLE_HOLD_FROM_MID_EXPO_POINT 50 

3) protection from ARM if BARO activated
4) condition to keep "I" parts on throttle less then MINCHECK for acc, gyro if BARO activated. To avoid lost of the stability accumulated by "I" part of PID controller... It's related to stability of heading, acro, stable modes...

Pls. note that is not tested on the fly yet. Only some initial GUI night testing... So keep your finger on the switch... ;)

svn revision: http://code.google.com/p/multiwii/source/detail?r=1257
prepared archive: http://multiwii.googlecode.com/svn/bran ... _r1248.zip

thx-
Alex



Alex,

Thank you! Today I tested the r1248 with my 330frame X4 the BARO working fine.

DIY Boy

Re: Altitude Hold improvement solution

Posted: Sun Nov 11, 2012 4:57 pm
by mahowik
diyboy wrote:

Today I tested the r1248 with my 330frame X4 the BARO working fine.

Many thanks! I think you was first ;)

I hope you are talking about testing "prepared archive" or "svn revision" from links above? i.e. not just r1248, because it hasn't latest changes...

Also could you tell more details or probably you have video how VARIO controlled altitude change works?

thx-
Alex

Re: Altitude Hold improvement solution

Posted: Sun Nov 11, 2012 5:43 pm
by dramida
I just tested the latest archive release with vario. It works very good with default pids. The video will post this night. A must se video with gps hold and vario baro mode and autolanding.

Re: Altitude Hold improvement solution

Posted: Sun Nov 11, 2012 6:22 pm
by mahowik
dramida wrote:I just tested the latest archive release with vario. It works very good with default pids. The video will post this night. A must se video with gps hold and vario baro mode and autolanding.

Wow! Thanks a lot! Nice to hear that it works from first implementation attempt! :)
And yes, with vario controlled altitude ascend/descend it even doesn't required sonar for autolanding. I.e. talking about "ground effect" related to low altitudes and baro sensor, but with vario pid conroller only ACC used, where baro only corrects ACC errors... cool! :)

Re: Altitude Hold improvement solution

Posted: Sun Nov 11, 2012 9:49 pm
by dramida
And here is the video in witch the variation of altitude is controlled by throttle stick position, regardless of the mass and power of your copter like this:
Throttle at about 50%= altitude hold
Throttle more than 50%= altitude is increased at a rate proportional to throttle deviation from middle point
Throttle less than 50%= altitude is decreased at a controlled rate proportional to stick deviation from middle position (good for easy descending )

http://www.youtube.com/watch?v=7Sa-oyJ4Ljs

Using the default vario PIDs 20- 7 as suggested by Mahowik.

I think this implementation is very good for novices, its so easy to land as the descent speed is moderated according with throttle position. I even tried an autoland in gps position hold with absolutely no effort. A new failsafe routine shoud be implemented asap.

Re: Altitude Hold improvement solution

Posted: Sun Nov 11, 2012 10:09 pm
by copterrichie
Now it is time for waypoints. Nice..

Re: Altitude Hold improvement solution

Posted: Mon Nov 12, 2012 12:19 am
by alexia
copterrichie wrote:Now it is time for waypoints. Nice..



for this there are already apm2 ;)

Re: Altitude Hold improvement solution

Posted: Mon Nov 12, 2012 12:37 am
by mahowik
dramida wrote:And here is the video in witch the variation of altitude is controlled by throttle stick position

Many thanks for nice demo! ;)
Only one note here. Althold point/zone - it's where it's activated, but not center position.

So I will add VARIO code to MultiWii_shared branch and will reduce pids to 15-10 because it seems little bit rapid/sharp for default behaviour...

update: code was added to MultiWii_shared branch

thx-
Alex

Re: Altitude Hold improvement solution

Posted: Mon Nov 12, 2012 10:35 am
by Crashpilot1000
I wonder if your solution will do a decent job on keeping the altitude during movement (real flying).

So long
Kraut Rob

Re: Altitude Hold improvement solution

Posted: Mon Nov 12, 2012 1:28 pm
by dramida
I tested in-flight altitude hold and in does a far better job than previous R1170. For me was good enough the altitude hold behavior during fast flight. I can see it compensate the throttle when leaning also.

Improvement: setting hower throttle to the point where Alt Hold is activated is strange , i prefer 50% throttle. (or at least a define)
Why? because i want to know it keeps its altitude even if it's far above and i can't say if it is climbing or not and after some ups and downs you may be loosing the alt hold spot on your remote.... (aerial photos)

I hope you get my point.
Mihai.

Re: Altitude Hold improvement solution

Posted: Mon Nov 12, 2012 1:38 pm
by alexia
i could only say you felicitation for all you hard working!
baro mode seem to be far better than original code.i am not a coder but i am very happy to see that this great project become more and more famous and better..and that is thanks to you.
i know you take your free time for this and i hope lots of people are reconnaissant(i don t know how to say that in english..lol.french word ).

Re: Altitude Hold improvement solution

Posted: Mon Nov 12, 2012 2:21 pm
by diyboy
mahowik wrote:
diyboy wrote:

Today I tested the r1248 with my 330frame X4 the BARO working fine.

Many thanks! I think you was first ;)

I hope you are talking about testing "prepared archive" or "svn revision" from links above? i.e. not just r1248, because it hasn't latest changes...

Also could you tell more details or probably you have video how VARIO controlled altitude change works?

thx-
Alex



Hi Alex
I just tested the prepared archive "http://multiwii.googlecode.com/svn/branches/Mahowik/MultiWii_varioPID_based_on_r1248.zip".

My testing process: (Using the default vario PIDs)
1. Quadx fly to 5M high
2. Throttle at about 50% then active Baro, the QuadX hold on about 5M.
3. Throttle move up to 70%, the quadX goes up
4. Throttle return to 50%, the quadx hold on it's height
5. Throttle move down to 30%, the quadx goes down.
6. Throttle return to 50% the quadx hold on it's height

I also test Baro+GPS hold with about process.

But I haven't taken video.

DIY Boy

Re: Altitude Hold improvement solution

Posted: Mon Nov 12, 2012 3:39 pm
by vpb
Crashpilot1000 wrote:I wonder if your solution will do a decent job on keeping the altitude during movement (real flying).

So long
Kraut Rob


Hi Rob, I use Mahowik alt-hold 100% the time I fly arround, solid height holding, I just use left stick to yaw.

Re: Altitude Hold improvement solution

Posted: Mon Nov 12, 2012 4:47 pm
by mahowik
Crashpilot1000 wrote:I wonder if your solution will do a decent job on keeping the altitude during movement (real flying).

In my 2.1_B[x] releases I tried to play with with solutions (my own and from alexmos)for throttle angle correction:
(+) it works for fast forward flight
(-) it make a big jumps (3-5m) when you change rapidly the direction of the flight

So we can introduce this feature with define to have a choice...

vpb wrote:I use Mahowik alt-hold 100% the time I fly arround, solid height holding, I just use left stick to yaw.

Actually the issue with reducing altitude exist when you start to move with inclination about >20degrees, but it's can be critical only on low altitudes...

thx-
Alex

Re: Altitude Hold improvement solution

Posted: Mon Nov 12, 2012 4:54 pm
by Crashpilot1000
@vpb @mahowik

Thank you for the info!
I guess i will have to test it myself :)

So long
Kraut Rob

Re: Altitude Hold improvement solution

Posted: Mon Nov 12, 2012 6:11 pm
by mahowik
dramida wrote:I tested in-flight altitude hold and in does a far better job than previous R1170. For me was good enough the altitude hold behavior during fast flight. I can see it compensate the throttle when leaning also.

Improvement: setting hower throttle to the point where Alt Hold is activated is strange , i prefer 50% throttle. (or at least a define)
Why? because i want to know it keeps its altitude even if it's far above and i can't say if it is climbing or not and after some ups and downs you may be loosing the alt hold spot on your remote.... (aerial photos)


In first attempt the main goal was to check VARIO pid controller works or not. And of course now we can improve and add some features there ;)

Let's discuss and sort out possible solutions, because i have too much points in my mind on this :)

Current implementation:
(+) when you activate the althold it will keep altitude immediately, i.e. it can be used to safe your copter during the activation
(+) initial throttle, i.e. throttle for hovering is taken as current throttle value on althold activation
(-) center is not 50% throttle, but if you need to have this in center, you can just reactivate the althold. I.e. just set the throttle stick to desired position and turn off/on the switch of althold quickly.
(-) as for now, predefined "throttle expo curve" also used for setting desired rate/vario and it's good if you activate the althold at the MID expo point (it's set in GUI and in right tuned config it equals to hover point, i.e. value of the initial throttle for hovering)
BUT if althold activated in point of throttle which in diff with MID expo point, it will be not usefull for vario regulation, e.g. MID_expo=40% and althold_activation=60%, it means ascending will be too fast, descending will be too low, because you are not in the center of expo curve...

Desired implementation:
1) center is 50% throttle
2) max rate/vario set with define
3) to have a beeps/light signaling during ascend/descend altitude OR best choice to have feedback/telemetry from flight controller to pilot (i'm experimenting with frsky downlink telemetry to have beeps on my TX)
4) need to predefine own expo curve with 50% center OR probably we don't need expo for rate/vario stick controlling at all, if all range about +/-3..5m/s?
5) (not obligatory but nice to have) safe function when althold deactivated... e.g. when you turn off the althold, throttle will be changed smoothly (in 2-3 seconds) from last althold's throttle to current throttle value to have time to react and adapt throttle after althold deactivation...

(+) proportional stick movement to have the same ascend/descend rate
(-) you need to tune initial throttle, i.e. throttle for hovering, because with this approach you should have possibility to activate althold with any thottle stick position. E.g. with #define INITIAL_THROTTLE_HOLD_FROM_MID_EXPO_POINT (Predefined initial throttle for AltHold will be calculated from MID (middle/hover) point of expo throttle from GUI).
But probable it has more advantage than disadvantage :)
(-) visible disadvantage - it will required to move stick to center after activation

Pls. provide you thoughts on this. I.e. we need to collect requirements before the next implementation step ;)

thx-
Alex

Re: Altitude Hold improvement solution

Posted: Mon Nov 12, 2012 8:39 pm
by scrat
Hi guys.

If I download mahowik's zip file: http://code.google.com/p/multiwii/sourc ... _r1248.zip

Is it ok to use it or it's not good. Then which MultiWii Conf to use with it?

Thx!

Re: Altitude Hold improvement solution

Posted: Mon Nov 12, 2012 10:09 pm
by dramida
It works fine that release. One point to mention, i observed in this last version that arming the copter with yaw right in not always working.
Sometimes when i try to arm the copter, i hear a very short beep and green led from Crius AIOP blinks also shortly. Nothing happens after. After several atempts, copter arms. I checked all EPA of remote and the signals are right, between 1000 and 1100us for left and 1900 and 2000us for right yaw.
Needless to say that when i upload old R1177, things comes back to normal. Anyone has the same issue?

Issue: I was able to disarm copter on the ground in baro mode. So if you put throttle down, yaw left, even in Baro mode, copter disarms.

Another issue/bug not regarding Mahowik branch: I can't change the voltage prescaller in software so regardless what VbatSCALE value i wrote, the voltage shown in GUI stays the same. Am i missingng something? What it does VBATNOMINAL...is it really necessary? Do i have to erase eeprom to change the scale? Wouldn't be straight forward to have in GUI a box to enter the scale for voltage sensor (voltage divider) and current also?

Code: Select all

#define VBAT              // uncomment this line to activate the vbat code
    #define VBATSCALE     58 // change this value if readed Battery voltage is different than real voltage
    #define VBATNOMINAL   168 //
    #define VBATLEVEL1_3S 140 //
    #define VBATLEVEL2_3S 132 //
    #define VBATLEVEL3_3S 125  //
    #define VBATLEVEL4_3S 120  // if vbat ever goes below this value, permanent alarm is triggered
    #define NO_VBAT       60 // Avoid beeping without any battery

Re: Altitude Hold improvement solution

Posted: Mon Nov 12, 2012 10:14 pm
by mahowik
dramida wrote:It works fine that release. One point to mention, i observed in this last version that arming the copter with yaw right in not always working.
Sometimes when i try to arm the copter, i hear a very short beep and green led from Crius AIOP blinks also shortly. Nothing happens after. After several atempts, copter arms. I checked all EPA of remote and the signals are right, between 1000 and 1100us for left and 1900 and 2000us for right yaw.
Needless to say that when i upload old R1177, things comes back to normal. Anyone has the same issue?

Probably because of 3rd point from viewtopic.php?f=8&t=2371&start=320#p26473 ;)
i.e.:
3) protection from ARM if BARO activated

Re: Altitude Hold improvement solution

Posted: Mon Nov 12, 2012 10:20 pm
by dramida
mahowik wrote:
dramida wrote:It works fine that release. One point to mention, i observed in this last version that arming the copter with yaw right in not always working.
Sometimes when i try to arm the copter, i hear a very short beep and green led from Crius AIOP blinks also shortly. Nothing happens after. After several atempts, copter arms. I checked all EPA of remote and the signals are right, between 1000 and 1100us for left and 1900 and 2000us for right yaw.
Needless to say that when i upload old R1177, things comes back to normal. Anyone has the same issue?

Probably because of 3rd point from viewtopic.php?f=8&t=2371&start=320#p26473 ;)
i.e.:
3) protection from ARM if BARO activated


I think something works not as expected in this protection routine, i can assure i wasn't in baro mode and all i had to do was to try a few times and then armed...

Re: Altitude Hold improvement solution

Posted: Mon Nov 12, 2012 10:26 pm
by mahowik
dramida wrote:I think something works not as expected in this protection routine, i can assure i wasn't in baro mode and all i had to do was to try a few times and then armed...

ok... thanks... I will re-check at home...

BTW what do you think on this viewtopic.php?f=8&t=2371&start=330#p26627?
we need to gather requirements ;)

Re: Altitude Hold improvement solution

Posted: Tue Nov 13, 2012 8:39 am
by vpb
dramida wrote:It works fine that release. One point to mention, i observed in this last version that arming the copter with yaw right in not always working.
Sometimes when i try to arm the copter, i hear a very short beep and green led from Crius AIOP blinks also shortly. Nothing happens after. After several atempts, copter arms. I checked all EPA of remote and the signals are right, between 1000 and 1100us for left and 1900 and 2000us for right yaw.
Needless to say that when i upload old R1177, things comes back to normal. Anyone has the same issue?


I dont have that issues, but with new code, I cannot trim ACC :-|, led doesnot flash each time I trim via the combo. :|

Re: Altitude Hold improvement solution

Posted: Tue Nov 13, 2012 10:16 pm
by dramida
mahowik wrote:
dramida wrote:I tested in-flight altitude hold and in does a far better job than previous R1170. For me was good enough the altitude hold behavior during fast flight. I can see it compensate the throttle when leaning also.

Improvement: setting hower throttle to the point where Alt Hold is activated is strange , i prefer 50% throttle. (or at least a define)
Why? because i want to know it keeps its altitude even if it's far above and i can't say if it is climbing or not and after some ups and downs you may be loosing the alt hold spot on your remote.... (aerial photos)


In first attempt the main goal was to check VARIO pid controller works or not. And of course now we can improve and add some features there ;)

Let's discuss and sort out possible solutions, because i have too much points in my mind on this :)

Current implementation:
(+) when you activate the althold it will keep altitude immediately, i.e. it can be used to safe your copter during the activation
(+) initial throttle, i.e. throttle for hovering is taken as current throttle value on althold activation
(-) center is not 50% throttle, but if you need to have this in center, you can just reactivate the althold. I.e. just set the throttle stick to desired position and turn off/on the switch of althold quickly.
(-) as for now, predefined "throttle expo curve" also used for setting desired rate/vario and it's good if you activate the althold at the MID expo point (it's set in GUI and in right tuned config it equals to hover point, i.e. value of the initial throttle for hovering)
BUT if althold activated in point of throttle which in diff with MID expo point, it will be not usefull for vario regulation, e.g. MID_expo=40% and althold_activation=60%, it means ascending will be too fast, descending will be too low, because you are not in the center of expo curve...

Desired implementation:
1) center is 50% throttle
2) max rate/vario set with define
3) to have a beeps/light signaling during ascend/descend altitude OR best choice to have feedback/telemetry from flight controller to pilot (i'm experimenting with frsky downlink telemetry to have beeps on my TX)
4) need to predefine own expo curve with 50% center OR probably we don't need expo for rate/vario stick controlling at all, if all range about +/-3..5m/s?
5) (not obligatory but nice to have) safe function when althold deactivated... e.g. when you turn off the althold, throttle will be changed smoothly (in 2-3 seconds) from last althold's throttle to current throttle value to have time to react and adapt throttle after althold deactivation...

(+) proportional stick movement to have the same ascend/descend rate
(-) you need to tune initial throttle, i.e. throttle for hovering, because with this approach you should have possibility to activate althold with any thottle stick position. E.g. with #define INITIAL_THROTTLE_HOLD_FROM_MID_EXPO_POINT (Predefined initial throttle for AltHold will be calculated from MID (middle/hover) point of expo throttle from GUI).
But probable it has more advantage than disadvantage :)
(-) visible disadvantage - it will required to move stick to center after activation

Pls. provide you thoughts on this. I.e. we need to collect requirements before the next implementation step ;)
Please check
thx-
Alex

The desired implementation is what I need. If anyone thinks different, let's hear a second oppinion plea
se.
About disarming in baro mode- bad things could happen thie way.
About arming in baro mode could be ok for your desired implementation.
Right now i have issues with arming the copter ...i wrote earlier about this.

Re: Altitude Hold improvement solution

Posted: Tue Nov 13, 2012 10:53 pm
by mahowik
dramida wrote:Right now i have issues with arming the copter ...i wrote earlier about this.

I have not reproduced this issue with my AIO...

Re: Altitude Hold improvement solution

Posted: Wed Nov 14, 2012 6:22 am
by vpb
I've tried new alt-hold in 1268dev, it's ok, still not strictly test cause I cannot trim acc. But it's a bit unconfortable when I cannot arm with baro on.

Re: Altitude Hold improvement solution

Posted: Wed Nov 14, 2012 7:01 am
by vpb
+1 on feedback via frsky telemetry. I'm using that feature now and always keep my eyes on alt-info.

Re: Altitude Hold improvement solution

Posted: Wed Nov 14, 2012 10:06 am
by Shogun
mahowik wrote:
dramida wrote:Right now i have issues with arming the copter ...i wrote earlier about this.

I have not reproduced this issue with my AIO...

I have the same arming issues and need to do this via switch. Have this since r1240, r1177 was OK.

Re: Altitude Hold improvement solution

Posted: Wed Nov 14, 2012 11:13 am
by vpb
Hi, maybe you should hold the arming-stick longer than before. That way I can trim ACC now.

Re: Altitude Hold improvement solution

Posted: Wed Nov 14, 2012 11:18 am
by vpb
@Mahowik: About % throttle at the hover point, how about hard-coded mid RC throttle value? Will it be more precise than percentage? With frsky telemetry we can read the throttle value at hover point.

Re: Altitude Hold improvement solution

Posted: Fri Nov 16, 2012 8:36 am
by dramida
Hello, I noticed that latest MWC zip file that i previously tested it was removed from Mahowik branch due to some unresolved "issues". Do we have anything new to test this coming weekend?

Re: Altitude Hold improvement solution

Posted: Fri Nov 16, 2012 9:14 am
by vpb
On r1271, mahowik has rolled back with log message: "rollback changes as not stable yet...".
I'm still flying ok, hello Mahowik?

Re: Altitude Hold improvement solution

Posted: Sat Nov 17, 2012 9:00 am
by wilco1967
no issues here also on version just before rollback..... flies just fine (better then ever before in fact...).

What where the issues ?

Re: Altitude Hold improvement solution

Posted: Sat Nov 17, 2012 1:16 pm
by dramida
The altitude control works very good, the only issues where about arming/disarming that could be inherited from main trunk.Specifically, on Crius AIO PRO board, quad mode with camstab, buzzer, GPS, Vbat- enabled, i couldn't arm the copter from the first time, i had to try several times. Also in Altitude control mode, i was able to disarm the copter with yaw right.
But i repeat, the main objectives where achieved, meaning a better altitude control. I would be very happy that MWC 2.2 prerelease could include these new features

Re: Altitude Hold improvement solution

Posted: Mon Nov 19, 2012 9:51 pm
by dramida
I don't get it:

After successfully implementation of altitude variation control by Mahowik almost two weeks ago, the shared trunk code remains the same. Let me remind you how nice the altitude control works, here is the video:

http://www.youtube.com/watch?v=7Sa-oyJ4Ljs

And in case the code is no longer availabe on Mahowik branch, i attached a zip file with the MWC source code you see flying in video above.

Re: Altitude Hold improvement solution

Posted: Mon Nov 19, 2012 10:26 pm
by jevermeister
hi,
there is a list of people who can alter code over at the google code repository. I looked into my mqilbox today and found no mail regarding this.
I did not follow this thread closely enough to feel adressed to upload this code.

I would suggest to contact one of the devs to merge the code. How should those guys know
about that. There was no command to do so.
Do you expect them to sit and wait for every idea and development to be ready to merge?

please contact one of the devs directly and wait for negative or positive feedback.
I can only speak for myself here: I always have a hard time merging code that is to complicated for me to understand. I could fuck up the code without knowing why and how should I fix thise bugs...

Nils
ps.: I do not want to rant, just want you to understand some devs. ;-)

pps.:I like your fantastic work - If only I could understand these algorythms :-\

Re: Altitude Hold improvement solution

Posted: Tue Nov 20, 2012 7:03 am
by vpb
dramida wrote:I don't get it:

And in case the code is no longer availabe on Mahowik branch, i attached a zip file with the MWC source code you see flying in video above.


Hi dramida, if you want a merged version that Mahowik did on the main trunk, just checkout the version before he removed it

Code: Select all

svn co http://multiwii.googlecode.com/svn/trunk/MultiWii_shared -r 1268


And mahowik branch, with the zip file ;)

Code: Select all

svn co http://multiwii.googlecode.com/svn/branches/Mahowik -r 1268


It's always there.

Re: Altitude Hold improvement solution

Posted: Tue Nov 20, 2012 7:27 am
by vpb
jevermeister wrote:I can only speak for myself here: I always have a hard time merging code that is to complicated for me to understand. I could fuck up the code without knowing why and how should I fix thise bugs...


You merge the code manually by hand? without the confliction code, you can always merge code by command.

Re: Altitude Hold improvement solution

Posted: Tue Nov 20, 2012 10:44 am
by jevermeister
I am not merging by hand but I want to understand the code I contribute. I wanted to say, that I have a bad feeling everytime I commit something for someone I do not fully understand.

nils

Re: Altitude Hold improvement solution

Posted: Tue Nov 20, 2012 5:42 pm
by mahowik
Hi guys,

Sorry for delays... My plans was little bit changed...
To be honest I did enough for the mwii project and comunity and it's time to do something for myself...
So now I'm trying to copy naza behaviour related to AH functions and altitude ascend/descend and going to distribute (individually) the firmware in *.hex format with flash tool/script...

I hope for your understanding...

thx-
Alex

Re: Altitude Hold improvement solution

Posted: Tue Nov 20, 2012 5:47 pm
by copterrichie
I am not surprised, wish you well.

Re: Altitude Hold improvement solution

Posted: Tue Nov 20, 2012 5:52 pm
by mahowik
what you are not surprised?! You know me very well? :)

Re: Altitude Hold improvement solution

Posted: Tue Nov 20, 2012 5:53 pm
by copterrichie
I am not surprised at your course of action, nothing else to say.

Re: Altitude Hold improvement solution

Posted: Tue Nov 20, 2012 6:23 pm
by alexia
mahowik wrote:Hi guys,

Sorry for delays... My plans was little bit changed...
To be honest I did enough for the mwii project and comunity and it's time to do something for myself...
So now I'm trying to copy naza behaviour related to AH functions and altitude ascend/descend and going to distribute (individually) the firmware in *.hex format with flash tool/script...

I hope for your understanding...

thx-
Alex



thanks for you hard working.
i understand if you want working for yourself.you are already made lots of for the communauty
thanks again
alexia

Re: Altitude Hold improvement solution

Posted: Tue Nov 20, 2012 6:29 pm
by vpb
You've done a big improvement Mahowik, I guess dramida will miss you much :P. Have luck with your plan!

Re: Altitude Hold improvement solution

Posted: Tue Nov 20, 2012 6:47 pm
by kataventos
What a f :o k is happenning here? :shock: Can someone explain?

Re: Altitude Hold improvement solution

Posted: Tue Nov 20, 2012 7:06 pm
by alexia
nothing..just mahowick want to use is free time for other things
i hope that he doesn t move out of this incredible project

Re: Altitude Hold improvement solution

Posted: Tue Nov 20, 2012 7:14 pm
by kipkool
That's a pity but it's your choice of course.

As Multiwii is GPL, binary distribution without source is not an option, does this means you will develop a new flightcontroller code from scratch ?