v1.8

This forum is dedicated to software development related to MultiWii.
It is not the right place to submit a setup problem.
Software download
Alexinparis
Posts: 1630
Joined: Wed Jan 19, 2011 9:07 pm

v1.8

Post by Alexinparis »

Hi,

I hope there is not a lot of remaining bugs ;)
But I think it was time to release all the new improvements since the 1.7.
here is a summary (in change.txt too)

Code: Select all

MAIN SOFT: code modularization.
     There are now multiple .pde files
     The configuration should be changed only in config.h
     The files are opened with the Arduino IDE (open one file and the remaining files will follow)
     This change should ease more easily the extension of MultiWii project in the future

MAIN SOFT: due to the multiplication of multiwii hardware compatible boards
     a first try to manage automatically in config.h the definition of
   - sensors
   - orientation
   - I2C address
     for the moment:
   FFIMUv1          // first 9DOF+baro board from Jussi, with HMC5843              <- tested by Alex
   FFIMUv2          // second version of 9DOF+baro board from Jussi, with HMC5883  <- tested by Alex
   FREEIMUv1        // v0.1 & v0.2 & v0.3 version of 9DOF board from Fabio
   FREEIMUv035      // FreeIMU v0.3.5 no baro
   FREEIMUv035_MS   // FreeIMU v0.3.5_MS
   FREEIMUv035_BMP  // FreeIMU v0.3.5_MS
   PIPO             // 9DOF board from erazz
   QUADRINO         // full FC board 9DOF+baro board from witespy                  <- tested by Alex
   ALLINONE         // full FC board or standalone 9DOF+baro board from CSG_EU
   AEROQUADSHIELDv2 // the 9DOF version of aeroquad shield v2
   ATAVRSBIN1       // Atmel 9DOF (Contribution by EOSBandi). The board requires 3.3V power.
     It's still however possible to declare individual sensors for a different configuration
     If everything is commented (default conf), MultiWii assumes there is only a WMP or a WMP+NK connected.

MAIN SOFT: introduction of a deadband around the stick center
     via a #define DEADBAND. (commented by default)
     it might help to get some accuracy from RC TX with not accurate potentiometers
     however, as it introduces a central deadband, the TX trims are not efficient as before.

MAIN SOFT: new altitude hold
     there is now a working implementation :)
     thanks to ziss_dm, the estimation of the altitude is more precise.
     the Z ACC is integrated in the alt hold estimation and helps a lot to estimate short term variation
     how-to:
        the multi must be nearly altitude stable before the activation of altitude hold.
        a dead band is then created around the throttle value.
     at every moment, it's possible to still control the trhottle power when the throttle goes out of the deadband
     this is not the best implemetation as the multi needs to be quite static before the activation, but it's a good start.
     
     There are 2 PIDS which are separated ans which can be used separatly.
   ALT PID: better results are obtained with a P only term (P=4.7 I=0 D=0 is the default value)
   VEL PID: it stands for velocity PID, more info here: (P=I=D=0 is the default value)
            it should help to smooth every altitude varation
            http://www.multiwii.com/forum/viewtopic.php?f=7&t=363

GUI: altitude representation
     there is an autoscale feature in the GUI to see better the altitude variation.
     So, don't be surprised about the huge amplitude of altitude curve in the GUI.
     The altitude is displayed in meter in the GUI.
     A normal variation when the multi is not Z moving should be around 0.5m

ALL: thank to Hamburger, integration of a power meter estimator
     voltage reading (now available in GUI) and alarm set up.
     (see full description and manual in config.h file)
     more info here: http://www.multiwii.com/forum/viewtopic.php?f=8&t=167

MAIN SOFT: thank to Hamburger, integration of a LCD telemetry
     very convenient with the TEXT STAR LCD and it's 4 buttons
     for other LCDs with no button, implementation of a Telemetry autoswitching
     (see full description and manual in config.h file)

MAIN SOFT: thanks to ziss_dm hint, gyro are calculated with more software internal resolution.
     This should smooth the overall alttitude.
     might not be so good with very noisy WMP copies

MAIN SOFT: more settings are avalaible for the ITG3200 gyro
     there was also a bug regarding the ITG3200 initialisation which is corrected => 2000deg/s setting is now used.

     thanks to EOSBandi: ITG3200 & ITG3205 Low pass filter setting. (see the according #define in the config.h file)
     In case you cannot eliminate all vibrations to the Gyro, you can try
     to decrease the LPF frequency, only one step per try. As soon as twitching gone, stick with that setting.
     It will not help on feedback wobbles, so change only when copter is randomly twiching and all dampening and
     balancing options ran out. Uncomment only one option!
     IMPORTANT! Change low pass filter setting changes PID behaviour, so retune your PID's after changing LPF.
     see config.h for the related #define

MAIN SOFT: New angle calculation by ziss_dm
     it's a completly new approach wich gives a constant cycle time
     and a representation in all attitude.
     there are some singularity when an angle reaches 90deg. It's normal.

MAIN SOFT: thanks to ziss_dm, there is another way to use the level mode.
     no overshoot is possible, but the reaction time is longer
     more info here: http://www.multiwii.com/forum/viewtopic.php?f=8&t=503

MAIN SOFT: code rework: RX rate/expo is now interpolated via a lookup table without any float.

GUI: thanks to shama, disparition of warning messages

MAIN SOFT: thanks to C2po , some more tuning on BMA180 I2C initialization.

ALL: 3 octo configs are now supported on mega boards: OCTOX8 (dual coax quadX), OCTOFLAT+, OCTOFLATX
     motor order: PIN 3,5,6,2,7,8,9,10
     OCTOX8:
         REAR_R , FRONT_R , REAR_L , FRONT_L , UNDER_REAR_R , UNDER_FRONT_R , UNDER_REAR_L , UNDER_FRONT_L
     OCTOFLATP:
         FRONT_L , FRONT_R , REAR_R , REAR_L , FRONT , RIGHT , REAR , LEFT
     OCTOFLATX:
         MIDFRONT_L , FRONT_R , MIDREAR_R , REAR_L , FRONT_L , MIDFRONT_R , REAR_R , MIDREAR_L
     one detail: the GUI is not yet adapted to display the 8 motors & the according 3D representation on the right

MAIN SOFT: PITCH&TILT camera compenstation with channel 7 & 8 is now working
     - must be used with SERVO_TILT option
     - TILT/ROLL inclination compensation is still trigged by CAMSTAB GUI checkbox option

GUI: improvment by Hamburger
     improvement to the devices list in the gui and that got me to tuning it a bit more.
       - list is still too short for my amount of known devices - some vertical space is unused,
          so longer box is possible
       - on mac, for each bt-device I get two device files:
          cu.name and tty.name. using the tty.name is recommended by arduino documentation,
          so do not add the cu.name devices to list
       - remove leading tty. from names to use limited space for readability.

LCD: improvment by Hamburger: exit without save from EEPROM menu
     You can use the LCD quite extensively for viewing values - especially with development versions.
     Therefore there is a need to exit the LCD config loop without doing a complete write to eeprom.
     The eeprom is limited to only 100.000 write cycles.

ALL: thanks to Cass3825, new optional arming procedure via an AUX switch
     this option is activated only if at least one checkbox is checked on the line "ARM"
     the motors won't arm if the copter is plugged while the tx switch is in the armed position.
     you must use the switch to disarm position then back to arm position in order to arm the motors.

     Another 'feature' worth mentioning is that changes in the switch position are only
     acknowledged when the throttle stick is all the way down.
     This prevents accidentally arming the motors at mid or full throttle.
     One downside is that the motors will not disarm unless the throttle stick is all the way down.

ALL: it's now possible to calibrate the MAG from the GUI (and mandatory for the first time)
   once activated, the LED will flash very fast for 30s
   you have exactly 30s to move the multi in all possible direction
   (one full turn on each axis is sufficient)
   There is no order to respect, but it is important to cover every directions.

GUI: introduction of MAG 3 axis raw values

MAIN SOFT: BI-COPTER PIN 6 servo correction

MAIN SOFT: thanks to jevermeister,
      the failsafe function of the PPM sum receiver was a little mofified and can handle better
      unusual signal patterns with short pulses.


and 3 videos to demonstrate the potential of this version:
http://www.youtube.com/watch?v=XB4hB5CPxeI
http://www.youtube.com/watch?v=F37SBwYPp1o
http://www.youtube.com/watch?v=FvNJzwRP8dw

oyibox
Posts: 5
Joined: Fri Aug 05, 2011 9:05 pm

Re: v1.8

Post by oyibox »

thanks Alexinparis, very good job !

i'm using the dead band and on the GUI, digits are still slightly moving up or down. is my hitec optic 6 causing this?

Alexinparis
Posts: 1630
Joined: Wed Jan 19, 2011 9:07 pm

Re: v1.8

Post by Alexinparis »

Hi,
What you see in the GUI are intermediate RC values, not the final ones involved in the computation.
The DEADBAND treatment is done after.
you should notice it on the stability of the motor bars

spagoziak
Posts: 171
Joined: Thu Jan 20, 2011 1:18 am

Re: v1.8

Post by spagoziak »

Wow video 3 is crazy! Marvelous recovery on those throws!

User avatar
captaingeek
Posts: 228
Joined: Fri Jan 28, 2011 6:42 pm

Re: v1.8

Post by captaingeek »

yahhoooo! cant wait to test.

spagoziak
Posts: 171
Joined: Thu Jan 20, 2011 1:18 am

Re: v1.8--Can't reverse my pitch gyro?

Post by spagoziak »

So here's a puzzler... I can't reverse my pitch gyro! I'm using an original WMP. Roll and yaw are correct in the GUI, but I can't seem to get the pitch gyro to reverse.

I've tried both a -Y and a normal Y under

Code: Select all

#if !defined(GYRO_ORIENTATION) 
  #define GYRO_ORIENTATION(X, Y, Z) {gyroADC[ROLL] = X; gyroADC[PITCH] = Y; gyroADC[YAW] = Z;}

which is in the Sensor tab.

I've also tried doing the same in this section, at the bottom of the config.h tab:

Code: Select all

//if you want to change to orientation of individual sensor
//#define ACC_ORIENTATION(X, Y, Z)  {accADC[ROLL]  =  Y; accADC[PITCH]  = -X; accADC[YAW]  = Z;}
//#define GYRO_ORIENTATION(X, Y, Z) {gyroADC[ROLL] = Y; gyroADC[PITCH] =  -X; gyroADC[YAW] = Z;}
//#define MAG_ORIENTATION(X, Y, Z)  {magADC[ROLL]  = X; magADC[PITCH]  = Y; magADC[YAW]  = Z;}


Certainly I'm doing something wrong... but I've changed the orientation via the -Y term in the sensor tab since the dev versions for 1.8 began! Can anyone see where I'm going wrong?

Has anyone noticed that the pitch variables are different between these two locations? One is X and one is Y...

Below are my config.h and the top snip of the sensor tab (only thing I've tried adjusting in that tab):

Code: Select all

// ************************************************************************************************************
// board orientation and setup
// ************************************************************************************************************
//default board orientation
#if !defined(ACC_ORIENTATION)
  #define ACC_ORIENTATION(X, Y, Z)  {accADC[ROLL]  = X; accADC[PITCH]  = Y; accADC[YAW]  = Z;}
#endif
#if !defined(GYRO_ORIENTATION)
  #define GYRO_ORIENTATION(X, Y, Z) {gyroADC[ROLL] = X; gyroADC[PITCH] = Y; gyroADC[YAW] = Z;}
#endif
#if !defined(MAG_ORIENTATION)
  #define MAG_ORIENTATION(X, Y, Z)  {magADC[ROLL]  = X; magADC[PITCH]  = Y; magADC[YAW]  = Z;}
#endif


And config.h:

Code: Select all

/*******************************/
/****CONFIGURABLE PARAMETERS****/
/*******************************/

/* Set the minimum throttle command sent to the ESC (Electronic Speed Controller)
   This is the minimum value that allow motors to run at a idle speed  */
//#define MINTHROTTLE 1300 // for Turnigy Plush ESCs 10A
//#define MINTHROTTLE 1120 // for Super Simple ESCs 10A
//#define MINTHROTTLE 1220
#define MINTHROTTLE 1100

/* The type of multicopter */
//#define GIMBAL
//#define BI
//#define TRI
//#define QUADP
#define QUADX
//#define Y4
//#define Y6
//#define HEX6
//#define HEX6X
//#define OCTOX8 //beta
//#define OCTOFLATP //beta
//#define OCTOFLATX //beta
//#define FLYING_WING //experimental

#define YAW_DIRECTION 1 // if you want to reverse the yaw correction direction
//#define YAW_DIRECTION -1

#define I2C_SPEED 100000L     //100kHz normal mode, this value must be used for a genuine WMP
//#define I2C_SPEED 400000L   //400kHz fast mode, it works only with some WMP clones

#define PROMINI  //Arduino type
//#define MEGA

//enable internal I2C pull ups
//#define INTERNAL_I2C_PULLUPS

//****** advanced users settings   *************

/* Pseudo-derivative conrtroller for level mode (experimental)
   Additional information: http://wbb.multiwii.com/viewtopic.php?f=8&t=503 */
//#define LEVEL_PDF

/* introduce a deadband around the stick center */
//#define DEADBAND

/* Failsave settings - added by MIS
   Failsafe check pulse on THROTTLE channel. If the pulse is OFF (on only THROTTLE or on all channels) the failsafe procedure is initiated.
   After FAILSAVE_DELAY time of pulse absence, the level mode is on (if ACC or nunchuk is avaliable), PITCH, ROLL and YAW is centered
   and THROTTLE is set to FAILSAVE_THR0TTLE value. You must set this value to descending about 1m/s or so for best results.
   This value is depended from your configuration, AUW and some other params.
   Next, afrer FAILSAVE_OFF_DELAY the copter is disarmed, and motors is stopped.
   If RC pulse coming back before reached FAILSAVE_OFF_DELAY time, after the small quard time the RC control is returned to normal.
   If you use serial sum PPM, the sum converter must completly turn off the PPM SUM pusles for this FailSafe functionality.*/
#define FAILSAFE                                  // Alex: comment this line if you want to deactivate the failsafe function
#define FAILSAVE_DELAY     10                     // Guard time for failsafe activation after signal lost. 1 step = 0.1sec - 1sec in example
#define FAILSAVE_OFF_DELAY 200                    // Time for Landing before motors stop in 0.1sec. 1 step = 0.1sec - 20sec in example
#define FAILSAVE_THR0TTLE  (MINTHROTTLE + 250)    // Throttle level used for landing - may be relative to MINTHROTTLE - as in this case


/* The following lines apply only for a pitch/roll tilt stabilization system
   On promini board, it is not compatible with config with 6 motors or more
   Uncomment the first line to activate it */
#define SERVO_TILT
#define TILT_PITCH_MIN    1020    //servo travel min, don't set it below 1020
#define TILT_PITCH_MAX    2000    //servo travel max, max value=2000
#define TILT_PITCH_MIDDLE 1500    //servo neutral value
#define TILT_PITCH_PROP   15      //servo proportional (tied to angle) ; can be negative to invert movement
#define TILT_ROLL_MIN     1020
#define TILT_ROLL_MAX     2000
#define TILT_ROLL_MIDDLE  1500
#define TILT_ROLL_PROP    10

/* if you use a specific sensor board:
   please submit any correction to this list.
     Note from Alex: I only own some boards
                     for other boards, I'm not sure, the info was gathered via rc forums, be cautious */
//#define FFIMUv1         // first 9DOF+baro board from Jussi, with HMC5843                   <- confirmed by Alex
//#define FFIMUv2         // second version of 9DOF+baro board from Jussi, with HMC5883       <- confirmed by Alex
//#define FREEIMUv1       // v0.1 & v0.2 & v0.3 version of 9DOF board from Fabio
//#define FREEIMUv035     // FreeIMU v0.3.5 no baro
//#define FREEIMUv035_MS  // FreeIMU v0.3.5_MS
//#define FREEIMUv035_BMP // FreeIMU v0.3.5_MS
//#define PIPO            // 9DOF board from erazz
//#define QUADRINO        // full FC board 9DOF+baro board from witespy                       <- confirmed by Alex
//#define ALLINONE        // full FC board or standalone 9DOF+baro board from CSG_EU
//#define AEROQUADSHIELDv2
//#define ATAVRSBIN1      // Atmel 9DOF (Contribution by EOSBandi). The board requires 3.3V power.

//if you use independent sensors
//leave it commented it you already checked a specific board above
/* I2C gyroscope */
//#define ITG3200
//#define L3G4200D

/* I2C accelerometer */
//#define ADXL345
//#define BMA020
//#define BMA180
//#define NUNCHACK  // if you want to use the nunckuk as a standalone I2C ACC without WMP
//#define LIS3LV02

/* I2C barometer */
#define BMP085
//#define MS561101BA  //non tested

/* I2C magnetometer */
//#define HMC5843
//#define HMC5883
//#define AK8975

/* ADC accelerometer */ // for 5DOF from sparkfun, uses analog PIN A1/A2/A3
//#define ADCACC

/* ITG3200 & ITG3205 Low pass filter setting. In case you cannot eliminate all vibrations to the Gyro, you can try
   to decrease the LPF frequency, only one step per try. As soon as twitching gone, stick with that setting.
   It will not help on feedback wobbles, so change only when copter is randomly twiching and all dampening and
   balancing options ran out. Uncomment only one option!
   IMPORTANT! Change low pass filter setting changes PID behaviour, so retune your PID's after changing LPF.*/
//#define ITG3200_LPF_256HZ     // This is the default setting, no need to uncomment, just for reference
//#define ITG3200_LPF_188HZ
//#define ITG3200_LPF_98HZ
//#define ITG3200_LPF_42HZ
//#define ITG3200_LPF_20HZ
//#define ITG3200_LPF_10HZ      // Use this only in extreme cases, rather change motors and/or props

/* The following lines apply only for specific receiver with only one PPM sum signal, on digital PIN 2
   IF YOUR RECEIVER IS NOT CONCERNED, DON'T UNCOMMENT ANYTHING. Note this is mandatory for a Y6 setup on a promini
   Select the right line depending on your radio brand. Feel free to modify the order in your PPM order is different */
//#define SERIAL_SUM_PPM         PITCH,YAW,THROTTLE,ROLL,AUX1,AUX2,CAMPITCH,CAMROLL //For Graupner/Spektrum
//#define SERIAL_SUM_PPM         ROLL,PITCH,THROTTLE,YAW,AUX1,AUX2,CAMPITCH,CAMROLL //For Robe/Hitec/Futaba
//#define SERIAL_SUM_PPM         PITCH,ROLL,THROTTLE,YAW,AUX1,AUX2,CAMPITCH,CAMROLL //For some Hitec/Sanwa/Others

/* The following lines apply only for Spektrum Satellite Receiver on MEGA boards only */ //not yet implemented
//#define SPEKTRUM

/* interleaving delay in micro seconds between 2 readings WMP/NK in a WMP+NK config
   if the ACC calibration time is very long (20 or 30s), try to increase this delay up to 4000
   it is relevent only for a conf with NK */
#define INTERLEAVING_DELAY 3000

/* for V BAT monitoring
   after the resistor divisor we should get [0V;5V]->[0;1023] on analog V_BATPIN
   with R1=33k and R2=51k
   vbat = [0;1023]*16/VBATSCALE */
#define VBAT              // comment this line to suppress the vbat code
#define VBATSCALE     131 // change this value if readed Battery voltage is different than real voltage
#define VBATLEVEL1_3S 107 // 10,7V
#define VBATLEVEL2_3S 103 // 10,3V
#define VBATLEVEL3_3S 99  // 9.9V
#define NO_VBAT       16 // Avoid beeping without any battery

/* when there is an error on I2C bus, we neutralize the values during a short time. expressed in microseconds
   it is relevent only for a conf with at least a WMP */
#define NEUTRALIZE_DELAY 100000

/* this is the value for the ESCs when they are not armed
   in some cases, this value must be lowered down to 900 for some specific ESCs */
#define MINCOMMAND 900

/* this is the maximum value for the ESCs at full power
   this value can be increased up to 2000 */
#define MAXTHROTTLE 1950

/* This is the speed of the serial interface. 115200 kbit/s is the best option for a USB connection.*/
#define SERIAL_COM_SPEED 115200

/* In order to save space, it's possibile to desactivate the LCD configuration functions
   comment this line only if you don't plan to used a LCD */
//#define LCD_CONF

/* to use Cat's whisker TEXTSTAR LCD, uncomment following line.
   Pleae note this display needs a full 4 wire connection to (+5V, Gnd, RXD, TXD )
   Configure display as follows: 115K baud, and TTL levels for RXD and TXD, terminal mode
   NO rx / tx line reconfiguration, use natural pins */
//#define LCD_TEXTSTAR
/* keys to navigate the LCD menu (preset to TEXTSTAR key-depress codes)*/
#define LCD_MENU_PREV 'a'
#define LCD_MENU_NEXT 'c'
#define LCD_VALUE_UP 'd'
#define LCD_VALUE_DOWN 'b'

/* motors will not spin when the throttle command is in low position
   this is an alternative method to stop immediately the motors */
#define MOTOR_STOP

/* some radios have not a neutral point centered on 1500. can be changed here */
#define MIDRC 1505

/* experimental
   camera trigger function : activated via Rc Options in the GUI, servo output=A2 on promini */
//#define CAMTRIG
#define CAM_SERVO_HIGH 2000  // the position of HIGH state servo
#define CAM_SERVO_LOW 1020   // the position of LOW state servo
#define CAM_TIME_HIGH 1000   // the duration of HIGH state servo expressed in ms
#define CAM_TIME_LOW 1000    // the duration of LOW state servo expressed in ms

/* you can change the tricopter servo travel here */
#define TRI_YAW_CONSTRAINT_MIN 1020
#define TRI_YAW_CONSTRAINT_MAX 2000
#define TRI_YAW_MIDDLE 1500

/* enable monitoring of the power consumption from battery (think of mAh) */
/* allows to set alarm value in GUI or via LCD */
/* Two options: */
/* 1 - soft: - (good results +-5% for plush and mystery ESCs @ 2S and 3S, not good with SuperSimple ESC */
/*      00. relies on your combo of battery type (Voltage, cpacity), ESC, ESC settings, motors, props and multiwii cycle time */
/*      01. set POWERMETER soft. Uses PLEVELSCALE = 50, PLEVELDIV = PLEVELDIVSOFT = 10000 */
/*      0. output is a value that linearily scales to power (mAh) */
/*      1. get voltage reading right first */
/*      2. start with freshly charged battery */
/*      3. go fly your typical flight (routine and duration) */
/*      4. at end connect to GUI or LCD and read the power value; write it down (example 4711)*/
/*      5. charge battery, write down amount of energy needed (example 722 mAh) */
/*      6. compute alarm value for desired power threshold (example 750 mAh : alarm = 4711 / 722 * 750) */
/*      7. set alarm value in GUI or LCD */
/*      8. enjoy your new battery alarm - possibly repeat steps 2 .. 7 */
/*      9. if you want the numbers to represent your mAh value, you must change PLEVELDIV */
/* 2 - hard: - (uses hardware sensor, after configuration gives reasonable results */
/*      00. uses analog pin 2 to read voltage output from sensor. */
/*      01. set POWERMETER hard. Uses PLEVELSCALE = 50 */
/*      02. install low path filter for 25 Hz to sensor input */
/*      1. compute PLEVELDIV for your sensor (see below for insturctions) */
/*      2. set PLEVELDIVSOFT to 10000 ( to use LOG_VALUES for individual motor comparison) */
/*      3. attach, set PSENSORNULL and  PINT2mA */
/*      4. configure, compile, upload, set alarm value in GUI or LCD */
/*      3. enjoy true readings of mAh consumed */
/* set POWERMETER to "soft" (1) or "hard" (2) depending on sensor you want to utilize */
//#define POWERMETER 1
//#define POWERMETER 2
/* the sum of all powermeters ranges from [0:60000 e4] theoretically. */
/* the alarm level from eeprom is out of [0:255], so we multipy alarm level with PLEVELSCALE and with 1e4 before comparing */
/* PLEVELSCALE is the step size you can use to set alarm */
#define PLEVELSCALE 50 // if you change this value for other granularity, you must search for comments in code to change accordingly
/* larger PLEVELDIV will get you smaller value for power (mAh equivalent) */
#define PLEVELDIV 10000 // default for soft - if you lower PLEVELDIV, beware of overrun in uint32 pMeter
#define PLEVELDIVSOFT PLEVELDIV // for soft always equal to PLEVELDIV; for hard set to 10000
//#define PLEVELDIV 1361L // to convert the sum into mAh divide by this value
/* amploc 25A sensor has 37mV/A */
/* arduino analog resolution is 4.9mV per unit; units from [0..1023] */
/* sampling rate 20ms, approx 19977 micro seconds */
/* PLEVELDIV = 37 / 4.9  * 10e6 / 19977  * 3600 / 1000  = 1361L */
/* set to analogRead() value for zero current */
#define PSENSORNULL 510 // for I=0A my sensor gives 1/2 Vss; that is approx 2.49Volt
#define PINT2mA 13 // for telemtry display: one integer step on arduino analog translates to mA (example 4.9 / 37 * 100

/* to monitor system values (battery level, loop time etc. with LCD enable this */
/* note: for now you must send single characters 'A', 'B', 'C', 'D' to request 4 different pages */
/* Buttons toggle request for page on/off */
/* The active page on the LCD does get updated automatically */
/* Easy to use with Terminal application or Textstar LCD - the 4 buttons are preconfigured to send 'A', 'B', 'C', 'D' */
/* The value represents the refresh interval in cpu time (micro seconds) */
//#define LCD_TELEMETRY 100011
/* to enable automatic hopping between 4 telemetry pages uncomment this. */
/* This may be useful if your LCD has no buttons or the sending is broken */
/* hopping is activated and deactivated in unarmed mode with throttle=low & roll=left & pitch=forward */
/* The value represents the hopping interval in cpu time (micro seconds) */
//#define LCD_TELEMETRY_AUTO 2000123
/* on telemetry page B it gives a bar graph which shows how much voltage battery has left. Range from 0 to 12 Volt is not very informative */
/* so we try do define a meaningful part. For a 3S battery we define full=12,6V and calculate how much it is above first warning level */
/* Example: 12.6V - VBATLEVEL1_3S  (for me = 126 - 102 = 24) */
#define VBATREF 24

/* to log values like max loop time and others to come */
/* logging values are visible via LCD config */
//#define LOG_VALUES
 
//****** end of advanced users settings *************

//if you want to change to orientation of individual sensor
//#define ACC_ORIENTATION(X, Y, Z)  {accADC[ROLL]  =  Y; accADC[PITCH]  = -X; accADC[YAW]  = Z;}
//#define GYRO_ORIENTATION(X, Y, Z) {gyroADC[ROLL] = Y; gyroADC[PITCH] =  -X; gyroADC[YAW] = Z;}
//#define MAG_ORIENTATION(X, Y, Z)  {magADC[ROLL]  = X; magADC[PITCH]  = Y; magADC[YAW]  = Z;}

/**************************************/
/****END OF CONFIGURABLE PARAMETERS****/
/**************************************/

User avatar
UndCon
Posts: 293
Joined: Mon Feb 21, 2011 2:10 pm

Re: v1.8

Post by UndCon »

Cool 1.8!

I have been waiting for this release.


GJ all involved
//UndCon

Magnetron
Posts: 124
Joined: Tue Jul 05, 2011 4:32 pm

Re: v1.8

Post by Magnetron »

Hi,
Alex,
I have trying the FreeIMU v.0.3.5_MS from Fabio Varesano.
I have discovered the correct axis orientation that was:
#if defined(FREEIMUv035) || defined(FREEIMUv035_MS) || defined(FREEIMUv035_BMP)
#define ITG3200
#define BMA180
// #define HMC5883
#define ACC_ORIENTATION(X, Y, Z) {accADC[ROLL] = X; accADC[PITCH] = Y; accADC[YAW] = Z;}
#define GYRO_ORIENTATION(X, Y, Z) {gyroADC[ROLL] = X; gyroADC[PITCH] = Y; gyroADC[YAW] = Z;}
#define MAG_ORIENTATION(X, Y, Z) {magADC[ROLL] = X; magADC[PITCH] = Y; magADC[YAW] = Z;}
#undef INTERNAL_I2C_PULLUPS
#if defined(FREEIMUv035_MS)
#define MS561101BA
#elif defined(FREEIMUv035_BMP)
#define BMP085
#endif
#endif

Is this version more stable? I have tryed the R207...

Alexinparis
Posts: 1630
Joined: Wed Jan 19, 2011 9:07 pm

Re: v1.8--Can't reverse my pitch gyro?

Post by Alexinparis »

Hi spag,

There was something not coherent about the orientation change for the WMP. (slow and fast mode was not correctly handle with the macro)
That's why GYRO_ORIENTATION has no more effect on it.
Instead, the best way is to change the orientation directly in the function: WMP_getRawADC


spagoziak wrote:So here's a puzzler... I can't reverse my pitch gyro! I'm using an original WMP. Roll and yaw are correct in the GUI, but I can't seem to get the pitch gyro to reverse.

I've tried both a -Y and a normal Y under

Code: Select all

#if !defined(GYRO_ORIENTATION) 
  #define GYRO_ORIENTATION(X, Y, Z) {gyroADC[ROLL] = X; gyroADC[PITCH] = Y; gyroADC[YAW] = Z;}

which is in the Sensor tab.

I've also tried doing the same in this section, at the bottom of the config.h tab:

Code: Select all

//if you want to change to orientation of individual sensor
//#define ACC_ORIENTATION(X, Y, Z)  {accADC[ROLL]  =  Y; accADC[PITCH]  = -X; accADC[YAW]  = Z;}
//#define GYRO_ORIENTATION(X, Y, Z) {gyroADC[ROLL] = Y; gyroADC[PITCH] =  -X; gyroADC[YAW] = Z;}
//#define MAG_ORIENTATION(X, Y, Z)  {magADC[ROLL]  = X; magADC[PITCH]  = Y; magADC[YAW]  = Z;}


Certainly I'm doing something wrong... but I've changed the orientation via the -Y term in the sensor tab since the dev versions for 1.8 began! Can anyone see where I'm going wrong?

Has anyone noticed that the pitch variables are different between these two locations? One is X and one is Y...

Below are my config.h and the top snip of the sensor tab (only thing I've tried adjusting in that tab):

Code: Select all

// ************************************************************************************************************
// board orientation and setup
// ************************************************************************************************************
//default board orientation
#if !defined(ACC_ORIENTATION)
  #define ACC_ORIENTATION(X, Y, Z)  {accADC[ROLL]  = X; accADC[PITCH]  = Y; accADC[YAW]  = Z;}
#endif
#if !defined(GYRO_ORIENTATION)
  #define GYRO_ORIENTATION(X, Y, Z) {gyroADC[ROLL] = X; gyroADC[PITCH] = Y; gyroADC[YAW] = Z;}
#endif
#if !defined(MAG_ORIENTATION)
  #define MAG_ORIENTATION(X, Y, Z)  {magADC[ROLL]  = X; magADC[PITCH]  = Y; magADC[YAW]  = Z;}
#endif


And config.h:

Code: Select all

/*******************************/
/****CONFIGURABLE PARAMETERS****/
/*******************************/

/* Set the minimum throttle command sent to the ESC (Electronic Speed Controller)
   This is the minimum value that allow motors to run at a idle speed  */
//#define MINTHROTTLE 1300 // for Turnigy Plush ESCs 10A
//#define MINTHROTTLE 1120 // for Super Simple ESCs 10A
//#define MINTHROTTLE 1220
#define MINTHROTTLE 1100

/* The type of multicopter */
//#define GIMBAL
//#define BI
//#define TRI
//#define QUADP
#define QUADX
//#define Y4
//#define Y6
//#define HEX6
//#define HEX6X
//#define OCTOX8 //beta
//#define OCTOFLATP //beta
//#define OCTOFLATX //beta
//#define FLYING_WING //experimental

#define YAW_DIRECTION 1 // if you want to reverse the yaw correction direction
//#define YAW_DIRECTION -1

#define I2C_SPEED 100000L     //100kHz normal mode, this value must be used for a genuine WMP
//#define I2C_SPEED 400000L   //400kHz fast mode, it works only with some WMP clones

#define PROMINI  //Arduino type
//#define MEGA

//enable internal I2C pull ups
//#define INTERNAL_I2C_PULLUPS

//****** advanced users settings   *************

/* Pseudo-derivative conrtroller for level mode (experimental)
   Additional information: http://wbb.multiwii.com/viewtopic.php?f=8&t=503 */
//#define LEVEL_PDF

/* introduce a deadband around the stick center */
//#define DEADBAND

/* Failsave settings - added by MIS
   Failsafe check pulse on THROTTLE channel. If the pulse is OFF (on only THROTTLE or on all channels) the failsafe procedure is initiated.
   After FAILSAVE_DELAY time of pulse absence, the level mode is on (if ACC or nunchuk is avaliable), PITCH, ROLL and YAW is centered
   and THROTTLE is set to FAILSAVE_THR0TTLE value. You must set this value to descending about 1m/s or so for best results.
   This value is depended from your configuration, AUW and some other params.
   Next, afrer FAILSAVE_OFF_DELAY the copter is disarmed, and motors is stopped.
   If RC pulse coming back before reached FAILSAVE_OFF_DELAY time, after the small quard time the RC control is returned to normal.
   If you use serial sum PPM, the sum converter must completly turn off the PPM SUM pusles for this FailSafe functionality.*/
#define FAILSAFE                                  // Alex: comment this line if you want to deactivate the failsafe function
#define FAILSAVE_DELAY     10                     // Guard time for failsafe activation after signal lost. 1 step = 0.1sec - 1sec in example
#define FAILSAVE_OFF_DELAY 200                    // Time for Landing before motors stop in 0.1sec. 1 step = 0.1sec - 20sec in example
#define FAILSAVE_THR0TTLE  (MINTHROTTLE + 250)    // Throttle level used for landing - may be relative to MINTHROTTLE - as in this case


/* The following lines apply only for a pitch/roll tilt stabilization system
   On promini board, it is not compatible with config with 6 motors or more
   Uncomment the first line to activate it */
#define SERVO_TILT
#define TILT_PITCH_MIN    1020    //servo travel min, don't set it below 1020
#define TILT_PITCH_MAX    2000    //servo travel max, max value=2000
#define TILT_PITCH_MIDDLE 1500    //servo neutral value
#define TILT_PITCH_PROP   15      //servo proportional (tied to angle) ; can be negative to invert movement
#define TILT_ROLL_MIN     1020
#define TILT_ROLL_MAX     2000
#define TILT_ROLL_MIDDLE  1500
#define TILT_ROLL_PROP    10

/* if you use a specific sensor board:
   please submit any correction to this list.
     Note from Alex: I only own some boards
                     for other boards, I'm not sure, the info was gathered via rc forums, be cautious */
//#define FFIMUv1         // first 9DOF+baro board from Jussi, with HMC5843                   <- confirmed by Alex
//#define FFIMUv2         // second version of 9DOF+baro board from Jussi, with HMC5883       <- confirmed by Alex
//#define FREEIMUv1       // v0.1 & v0.2 & v0.3 version of 9DOF board from Fabio
//#define FREEIMUv035     // FreeIMU v0.3.5 no baro
//#define FREEIMUv035_MS  // FreeIMU v0.3.5_MS
//#define FREEIMUv035_BMP // FreeIMU v0.3.5_MS
//#define PIPO            // 9DOF board from erazz
//#define QUADRINO        // full FC board 9DOF+baro board from witespy                       <- confirmed by Alex
//#define ALLINONE        // full FC board or standalone 9DOF+baro board from CSG_EU
//#define AEROQUADSHIELDv2
//#define ATAVRSBIN1      // Atmel 9DOF (Contribution by EOSBandi). The board requires 3.3V power.

//if you use independent sensors
//leave it commented it you already checked a specific board above
/* I2C gyroscope */
//#define ITG3200
//#define L3G4200D

/* I2C accelerometer */
//#define ADXL345
//#define BMA020
//#define BMA180
//#define NUNCHACK  // if you want to use the nunckuk as a standalone I2C ACC without WMP
//#define LIS3LV02

/* I2C barometer */
#define BMP085
//#define MS561101BA  //non tested

/* I2C magnetometer */
//#define HMC5843
//#define HMC5883
//#define AK8975

/* ADC accelerometer */ // for 5DOF from sparkfun, uses analog PIN A1/A2/A3
//#define ADCACC

/* ITG3200 & ITG3205 Low pass filter setting. In case you cannot eliminate all vibrations to the Gyro, you can try
   to decrease the LPF frequency, only one step per try. As soon as twitching gone, stick with that setting.
   It will not help on feedback wobbles, so change only when copter is randomly twiching and all dampening and
   balancing options ran out. Uncomment only one option!
   IMPORTANT! Change low pass filter setting changes PID behaviour, so retune your PID's after changing LPF.*/
//#define ITG3200_LPF_256HZ     // This is the default setting, no need to uncomment, just for reference
//#define ITG3200_LPF_188HZ
//#define ITG3200_LPF_98HZ
//#define ITG3200_LPF_42HZ
//#define ITG3200_LPF_20HZ
//#define ITG3200_LPF_10HZ      // Use this only in extreme cases, rather change motors and/or props

/* The following lines apply only for specific receiver with only one PPM sum signal, on digital PIN 2
   IF YOUR RECEIVER IS NOT CONCERNED, DON'T UNCOMMENT ANYTHING. Note this is mandatory for a Y6 setup on a promini
   Select the right line depending on your radio brand. Feel free to modify the order in your PPM order is different */
//#define SERIAL_SUM_PPM         PITCH,YAW,THROTTLE,ROLL,AUX1,AUX2,CAMPITCH,CAMROLL //For Graupner/Spektrum
//#define SERIAL_SUM_PPM         ROLL,PITCH,THROTTLE,YAW,AUX1,AUX2,CAMPITCH,CAMROLL //For Robe/Hitec/Futaba
//#define SERIAL_SUM_PPM         PITCH,ROLL,THROTTLE,YAW,AUX1,AUX2,CAMPITCH,CAMROLL //For some Hitec/Sanwa/Others

/* The following lines apply only for Spektrum Satellite Receiver on MEGA boards only */ //not yet implemented
//#define SPEKTRUM

/* interleaving delay in micro seconds between 2 readings WMP/NK in a WMP+NK config
   if the ACC calibration time is very long (20 or 30s), try to increase this delay up to 4000
   it is relevent only for a conf with NK */
#define INTERLEAVING_DELAY 3000

/* for V BAT monitoring
   after the resistor divisor we should get [0V;5V]->[0;1023] on analog V_BATPIN
   with R1=33k and R2=51k
   vbat = [0;1023]*16/VBATSCALE */
#define VBAT              // comment this line to suppress the vbat code
#define VBATSCALE     131 // change this value if readed Battery voltage is different than real voltage
#define VBATLEVEL1_3S 107 // 10,7V
#define VBATLEVEL2_3S 103 // 10,3V
#define VBATLEVEL3_3S 99  // 9.9V
#define NO_VBAT       16 // Avoid beeping without any battery

/* when there is an error on I2C bus, we neutralize the values during a short time. expressed in microseconds
   it is relevent only for a conf with at least a WMP */
#define NEUTRALIZE_DELAY 100000

/* this is the value for the ESCs when they are not armed
   in some cases, this value must be lowered down to 900 for some specific ESCs */
#define MINCOMMAND 900

/* this is the maximum value for the ESCs at full power
   this value can be increased up to 2000 */
#define MAXTHROTTLE 1950

/* This is the speed of the serial interface. 115200 kbit/s is the best option for a USB connection.*/
#define SERIAL_COM_SPEED 115200

/* In order to save space, it's possibile to desactivate the LCD configuration functions
   comment this line only if you don't plan to used a LCD */
//#define LCD_CONF

/* to use Cat's whisker TEXTSTAR LCD, uncomment following line.
   Pleae note this display needs a full 4 wire connection to (+5V, Gnd, RXD, TXD )
   Configure display as follows: 115K baud, and TTL levels for RXD and TXD, terminal mode
   NO rx / tx line reconfiguration, use natural pins */
//#define LCD_TEXTSTAR
/* keys to navigate the LCD menu (preset to TEXTSTAR key-depress codes)*/
#define LCD_MENU_PREV 'a'
#define LCD_MENU_NEXT 'c'
#define LCD_VALUE_UP 'd'
#define LCD_VALUE_DOWN 'b'

/* motors will not spin when the throttle command is in low position
   this is an alternative method to stop immediately the motors */
#define MOTOR_STOP

/* some radios have not a neutral point centered on 1500. can be changed here */
#define MIDRC 1505

/* experimental
   camera trigger function : activated via Rc Options in the GUI, servo output=A2 on promini */
//#define CAMTRIG
#define CAM_SERVO_HIGH 2000  // the position of HIGH state servo
#define CAM_SERVO_LOW 1020   // the position of LOW state servo
#define CAM_TIME_HIGH 1000   // the duration of HIGH state servo expressed in ms
#define CAM_TIME_LOW 1000    // the duration of LOW state servo expressed in ms

/* you can change the tricopter servo travel here */
#define TRI_YAW_CONSTRAINT_MIN 1020
#define TRI_YAW_CONSTRAINT_MAX 2000
#define TRI_YAW_MIDDLE 1500

/* enable monitoring of the power consumption from battery (think of mAh) */
/* allows to set alarm value in GUI or via LCD */
/* Two options: */
/* 1 - soft: - (good results +-5% for plush and mystery ESCs @ 2S and 3S, not good with SuperSimple ESC */
/*      00. relies on your combo of battery type (Voltage, cpacity), ESC, ESC settings, motors, props and multiwii cycle time */
/*      01. set POWERMETER soft. Uses PLEVELSCALE = 50, PLEVELDIV = PLEVELDIVSOFT = 10000 */
/*      0. output is a value that linearily scales to power (mAh) */
/*      1. get voltage reading right first */
/*      2. start with freshly charged battery */
/*      3. go fly your typical flight (routine and duration) */
/*      4. at end connect to GUI or LCD and read the power value; write it down (example 4711)*/
/*      5. charge battery, write down amount of energy needed (example 722 mAh) */
/*      6. compute alarm value for desired power threshold (example 750 mAh : alarm = 4711 / 722 * 750) */
/*      7. set alarm value in GUI or LCD */
/*      8. enjoy your new battery alarm - possibly repeat steps 2 .. 7 */
/*      9. if you want the numbers to represent your mAh value, you must change PLEVELDIV */
/* 2 - hard: - (uses hardware sensor, after configuration gives reasonable results */
/*      00. uses analog pin 2 to read voltage output from sensor. */
/*      01. set POWERMETER hard. Uses PLEVELSCALE = 50 */
/*      02. install low path filter for 25 Hz to sensor input */
/*      1. compute PLEVELDIV for your sensor (see below for insturctions) */
/*      2. set PLEVELDIVSOFT to 10000 ( to use LOG_VALUES for individual motor comparison) */
/*      3. attach, set PSENSORNULL and  PINT2mA */
/*      4. configure, compile, upload, set alarm value in GUI or LCD */
/*      3. enjoy true readings of mAh consumed */
/* set POWERMETER to "soft" (1) or "hard" (2) depending on sensor you want to utilize */
//#define POWERMETER 1
//#define POWERMETER 2
/* the sum of all powermeters ranges from [0:60000 e4] theoretically. */
/* the alarm level from eeprom is out of [0:255], so we multipy alarm level with PLEVELSCALE and with 1e4 before comparing */
/* PLEVELSCALE is the step size you can use to set alarm */
#define PLEVELSCALE 50 // if you change this value for other granularity, you must search for comments in code to change accordingly
/* larger PLEVELDIV will get you smaller value for power (mAh equivalent) */
#define PLEVELDIV 10000 // default for soft - if you lower PLEVELDIV, beware of overrun in uint32 pMeter
#define PLEVELDIVSOFT PLEVELDIV // for soft always equal to PLEVELDIV; for hard set to 10000
//#define PLEVELDIV 1361L // to convert the sum into mAh divide by this value
/* amploc 25A sensor has 37mV/A */
/* arduino analog resolution is 4.9mV per unit; units from [0..1023] */
/* sampling rate 20ms, approx 19977 micro seconds */
/* PLEVELDIV = 37 / 4.9  * 10e6 / 19977  * 3600 / 1000  = 1361L */
/* set to analogRead() value for zero current */
#define PSENSORNULL 510 // for I=0A my sensor gives 1/2 Vss; that is approx 2.49Volt
#define PINT2mA 13 // for telemtry display: one integer step on arduino analog translates to mA (example 4.9 / 37 * 100

/* to monitor system values (battery level, loop time etc. with LCD enable this */
/* note: for now you must send single characters 'A', 'B', 'C', 'D' to request 4 different pages */
/* Buttons toggle request for page on/off */
/* The active page on the LCD does get updated automatically */
/* Easy to use with Terminal application or Textstar LCD - the 4 buttons are preconfigured to send 'A', 'B', 'C', 'D' */
/* The value represents the refresh interval in cpu time (micro seconds) */
//#define LCD_TELEMETRY 100011
/* to enable automatic hopping between 4 telemetry pages uncomment this. */
/* This may be useful if your LCD has no buttons or the sending is broken */
/* hopping is activated and deactivated in unarmed mode with throttle=low & roll=left & pitch=forward */
/* The value represents the hopping interval in cpu time (micro seconds) */
//#define LCD_TELEMETRY_AUTO 2000123
/* on telemetry page B it gives a bar graph which shows how much voltage battery has left. Range from 0 to 12 Volt is not very informative */
/* so we try do define a meaningful part. For a 3S battery we define full=12,6V and calculate how much it is above first warning level */
/* Example: 12.6V - VBATLEVEL1_3S  (for me = 126 - 102 = 24) */
#define VBATREF 24

/* to log values like max loop time and others to come */
/* logging values are visible via LCD config */
//#define LOG_VALUES
 
//****** end of advanced users settings *************

//if you want to change to orientation of individual sensor
//#define ACC_ORIENTATION(X, Y, Z)  {accADC[ROLL]  =  Y; accADC[PITCH]  = -X; accADC[YAW]  = Z;}
//#define GYRO_ORIENTATION(X, Y, Z) {gyroADC[ROLL] = Y; gyroADC[PITCH] =  -X; gyroADC[YAW] = Z;}
//#define MAG_ORIENTATION(X, Y, Z)  {magADC[ROLL]  = X; magADC[PITCH]  = Y; magADC[YAW]  = Z;}

/**************************************/
/****END OF CONFIGURABLE PARAMETERS****/
/**************************************/

Alexinparis
Posts: 1630
Joined: Wed Jan 19, 2011 9:07 pm

Re: v1.8

Post by Alexinparis »

strange, this was not what was quoted by fabio.
can you confirm this in a real flight ?

Magnetron wrote:Hi,
Alex,
I have trying the FreeIMU v.0.3.5_MS from Fabio Varesano.
I have discovered the correct axis orientation that was:
#if defined(FREEIMUv035) || defined(FREEIMUv035_MS) || defined(FREEIMUv035_BMP)
#define ITG3200
#define BMA180
// #define HMC5883
#define ACC_ORIENTATION(X, Y, Z) {accADC[ROLL] = X; accADC[PITCH] = Y; accADC[YAW] = Z;}
#define GYRO_ORIENTATION(X, Y, Z) {gyroADC[ROLL] = X; gyroADC[PITCH] = Y; gyroADC[YAW] = Z;}
#define MAG_ORIENTATION(X, Y, Z) {magADC[ROLL] = X; magADC[PITCH] = Y; magADC[YAW] = Z;}
#undef INTERNAL_I2C_PULLUPS
#if defined(FREEIMUv035_MS)
#define MS561101BA
#elif defined(FREEIMUv035_BMP)
#define BMP085
#endif
#endif

Is this version more stable? I have tryed the R207...

User avatar
Hamburger
Posts: 2582
Joined: Tue Mar 01, 2011 2:14 pm
Location: air
Contact:

Re: v1.8

Post by Hamburger »

Alexinparis wrote:strange, this was not what was quoted by fabio.
can you confirm this in a real flight ?


I am very interested as I will have same IMU soon.
You need to check in flight sensor the orientation in acro mode, not in stable mode. I had orientation wrong for another sensor board and never noticed while flying in level mode.
To get you started how to verify sensor orientation you may find this helpful http://www.rcgroups.com/forums/showpost ... stcount=37

Cheers, Hamburger

User avatar
jevermeister
Posts: 708
Joined: Wed Jul 20, 2011 8:56 am
Contact:

Re: v1.8

Post by jevermeister »

Hi,
I already posted this in the RCGroups thread, but I think it will get lost:

When the Failsafe routine stops the motors after the 20 seconds, they keep on stuttering, you can see in the GUI that the throttle is alternating between failsafe throttle and 0.
I noticed that there is no mincommand in the failsafe anymore.


I also noticed, that the buzzerbeep for vbat arnings is very short, it is nearly unhearable. Something is stopping the buzzer right after it has been started,
I noticed that the bzzer relies on the micsor(), perhaps the code is faster now due to the fragmentation into different pde? so that the buzzer routine need other values??

Nils

User avatar
jevermeister
Posts: 708
Joined: Wed Jul 20, 2011 8:56 am
Contact:

Re: v1.8

Post by jevermeister »

ps.: is it possible, that the code is faster now? The buzzer of the vbat feature is beeping very very very short now



Okay i found that one.

The Buzzerpin is resetted by stablepin_off, with this feature we won't have voltage warning while in acro mode...

I think O got it:

Code: Select all

  #define STABLEPIN_OFF              PORTC &= ~1<<6;


should be like this:


Code: Select all

  #define STABLEPIN_OFF              PORTC &= ~(1<<6);


There are more like this where there are missing brakets
Last edited by jevermeister on Sun Aug 07, 2011 1:20 pm, edited 1 time in total.

spagoziak
Posts: 171
Joined: Thu Jan 20, 2011 1:18 am

Re: v1.8--Can't reverse my pitch gyro?

Post by spagoziak »

Alexinparis wrote:Hi spag,

There was something not coherent about the orientation change for the WMP. (slow and fast mode was not correctly handle with the macro)
That's why GYRO_ORIENTATION has no more effect on it.
Instead, the best way is to change the orientation directly in the function: WMP_getRawADC


Great Alex, thank you! I'll try this later today, after work.

spag

Alexinparis
Posts: 1630
Joined: Wed Jan 19, 2011 9:07 pm

Re: v1.8

Post by Alexinparis »

thanks man :)

hopefully, the bugs are not critical.
there are others in the MEGA part:
#define BUZZERPIN_OFF PORTC &= ~1<<5;
#define STABLEPIN_OFF PORTC &= ~1<<6;
#define DIGITAL_TILT_PITCH_LOW PORTC &= ~(1<<3);PORTL |= 1<<5;
#define DIGITAL_TILT_ROLL_LOW PORTC &= ~(1<<2);PORTL |= 1<<4;


jevermeister wrote:
ps.: is it possible, that the code is faster now? The buzzer of the vbat feature is beeping very very very short now



Okay i found that one.

The Buzzerpin is resetted by stablepin_off, with this feature we won't have voltage warning while in acro mode...

I think O got it:

Code: Select all

  #define STABLEPIN_OFF              PORTC &= ~1<<6;


should be like this:


Code: Select all

  #define STABLEPIN_OFF              PORTC &= ~(1<<6);


There are more like this where there are missing brakets

Alexinparis
Posts: 1630
Joined: Wed Jan 19, 2011 9:07 pm

Re: v1.8

Post by Alexinparis »

Hamburger wrote:
Alexinparis wrote:strange, this was not what was quoted by fabio.
can you confirm this in a real flight ?


I am very interested as I will have same IMU soon.
You need to check in flight sensor the orientation in acro mode, not in stable mode. I had orientation wrong for another sensor board and never noticed while flying in level mode.
To get you started how to verify sensor orientation you may find this helpful http://www.rcgroups.com/forums/showpost ... stcount=37

Cheers, Hamburger


I've just updated the faq accordingly: (the info was there, but without the MAG info)
http://www.multiwii.com/faq#How_should_ ... directions

User avatar
Hamburger
Posts: 2582
Joined: Tue Mar 01, 2011 2:14 pm
Location: air
Contact:

Re: v1.8

Post by Hamburger »

Alexinparis wrote:I've just updated the faq accordingly: (the info was there, but without the MAG info)
http://www.multiwii.com/faq#How_should_ ... directions


very fast, thanks.
You might want to add a link to the stick combinations cheat sheet at google rep to the faq.
Btw, does it need an update? any new stick combinations lately?

User avatar
captaingeek
Posts: 228
Joined: Fri Jan 28, 2011 6:42 pm

Re: v1.8

Post by captaingeek »

test flown this morning with the atmel i1. flew great with defaults. upped p's for pitch/roll. amazingly stable in level mode. adding a baro now.

Magnetron
Posts: 124
Joined: Tue Jul 05, 2011 4:32 pm

Re: v1.8

Post by Magnetron »

Alexinparis wrote:strange, this was not what was quoted by fabio.
can you confirm this in a real flight ?

Magnetron wrote:Hi,
Alex,
I have trying the FreeIMU v.0.3.5_MS from Fabio Varesano.
I have discovered the correct axis orientation that was:
#if defined(FREEIMUv035) || defined(FREEIMUv035_MS) || defined(FREEIMUv035_BMP)
#define ITG3200
#define BMA180
// #define HMC5883
#define ACC_ORIENTATION(X, Y, Z) {accADC[ROLL] = X; accADC[PITCH] = Y; accADC[YAW] = Z;}
#define GYRO_ORIENTATION(X, Y, Z) {gyroADC[ROLL] = X; gyroADC[PITCH] = Y; gyroADC[YAW] = Z;}
#define MAG_ORIENTATION(X, Y, Z) {magADC[ROLL] = X; magADC[PITCH] = Y; magADC[YAW] = Z;}
#undef INTERNAL_I2C_PULLUPS
#if defined(FREEIMUv035_MS)
#define MS561101BA
#elif defined(FREEIMUv035_BMP)
#define BMP085
#endif
#endif

Is this version more stable? I have tryed the R207...


Yes Alex, I confirm.
I asked Fabio also and him confirm me the axis orientation.
I tryed my quadcopter with FreeIMU v0.3.5_MS in acro mode.

angel008
Posts: 5
Joined: Fri Aug 05, 2011 6:31 pm

Re: v1.8

Post by angel008 »

is there any change since 1.7 with the aux 1/2 (and servo 1/2) usage

I would love to use aux 2 (and may b even the 2 servo channels) on my arduino mini.

is this possible now or is this a hardware/software issue as I read about some people being able to use more then 5 channels on a arduino mini.

would love to have another switch beside aux 1 aux 2 would be perfect.

I'm using a aurora 9 and a 9ch reciever so ppm is as far as I know not possible..

paddytfm
Posts: 8
Joined: Sun Aug 07, 2011 9:07 pm

Re: v1.8

Post by paddytfm »

Hi
I confirm Roll Acc_orientation as no effect compare to MultiWii_quadrino_20110725 previous version.
Waiting for a release.
Regards
Paddytfm

spagoziak
Posts: 171
Joined: Thu Jan 20, 2011 1:18 am

Re: v1.8

Post by spagoziak »

Alex, so this level of code editing is a bit over my head, but I think I found what you were referring to. Do I remove the - in the pitch line below to change how the gyro pitch is reported the the MWC? What about the second group, where pitch is mentioned again? (this excerpt is taken from the sensors tab, lines 888-899, v 1.8.

Code: Select all

// Wii Motion Plus Data
  if ( (rawADC[5]&0x03) == 0x02 ) {
    // Assemble 14bit data
    gyroADC[ROLL]  = - ( ((rawADC[5]>>2)<<8) | rawADC[2] ); //range: +/- 8192
    gyroADC[PITCH] = - ( ((rawADC[4]>>2)<<8) | rawADC[1] );
    gyroADC[YAW]  =  - ( ((rawADC[3]>>2)<<8) | rawADC[0] );
    GYRO_Common();
    // Check if slow bit is set and normalize to fast mode range
    gyroADC[ROLL]  = (rawADC[3]&0x01)     ? gyroADC[ROLL]/5  : gyroADC[ROLL];  //the ratio 1/5 is not exactly the IDG600 or ISZ650 specification
    gyroADC[PITCH] = (rawADC[4]&0x02)>>1  ? gyroADC[PITCH]/5 : gyroADC[PITCH]; //we detect here the slow of fast mode WMP gyros values (see wiibrew for more details)
    gyroADC[YAW]   = (rawADC[3]&0x02)>>1  ? gyroADC[YAW]/5   : gyroADC[YAW];   // this step must be done after zero compensation   
    return 1;

skygizmo
Posts: 6
Joined: Sat Jul 16, 2011 12:20 am

Re: v1.8

Post by skygizmo »

Hi
Tested 1.8 today and have been stumbling into some problems.
my hardware:
paris 3.0 with Allinone board.

Issue 1:
If I use the built-in code for Allinone, then it's no sensors.

problem 2:
in Code 1.7 will use bma180 address 0x82, but in 1.8 it does not have to use 0x80.
do I back 1.7 so works 0x82 as it should.

Problem 3:
has a text LCD star, this will not work, have set the settings in the LCD and in the code.

problem 4:
This is perhaps the biggest problem, my graph for ALT is all over the scale! What to do?

spagoziak
Posts: 171
Joined: Thu Jan 20, 2011 1:18 am

Re: v1.8

Post by spagoziak »

skygizmo wrote:problem 4:
This is perhaps the biggest problem, my graph for ALT is all over the scale! What to do?


I have no ideas for the other issues, but this last one is working as designed! He has the alt graph set to be scaled WAY in so you can see its fluctuations. It adjusts itself automatically to keep the line mostly within the graph window. It's normal!

spagoziak
Posts: 171
Joined: Thu Jan 20, 2011 1:18 am

Re: v1.8

Post by spagoziak »

spagoziak wrote:Alex, so this level of code editing is a bit over my head, but I think I found what you were referring to. Do I remove the - in the pitch line below to change how the gyro pitch is reported the the MWC? What about the second group, where pitch is mentioned again? (this excerpt is taken from the sensors tab, lines 888-899, v 1.8.

Code: Select all

// Wii Motion Plus Data
  if ( (rawADC[5]&0x03) == 0x02 ) {
    // Assemble 14bit data
    gyroADC[ROLL]  = - ( ((rawADC[5]>>2)<<8) | rawADC[2] ); //range: +/- 8192
    gyroADC[PITCH] = - ( ((rawADC[4]>>2)<<8) | rawADC[1] );
    gyroADC[YAW]  =  - ( ((rawADC[3]>>2)<<8) | rawADC[0] );
    GYRO_Common();
    // Check if slow bit is set and normalize to fast mode range
    gyroADC[ROLL]  = (rawADC[3]&0x01)     ? gyroADC[ROLL]/5  : gyroADC[ROLL];  //the ratio 1/5 is not exactly the IDG600 or ISZ650 specification
    gyroADC[PITCH] = (rawADC[4]&0x02)>>1  ? gyroADC[PITCH]/5 : gyroADC[PITCH]; //we detect here the slow of fast mode WMP gyros values (see wiibrew for more details)
    gyroADC[YAW]   = (rawADC[3]&0x02)>>1  ? gyroADC[YAW]/5   : gyroADC[YAW];   // this step must be done after zero compensation   
    return 1;


I haven't flight tested it yet (hopefully tomorrow), but the GUI responds accordingly when I removed the - from

Code: Select all

       gyroADC[PITCH] = - ( ((rawADC[4]>>2)<<8) | rawADC[1] );


Thanks for the hint Alex! Will some future version have a more accessible method for gyro reversal?

fax8
Posts: 61
Joined: Mon Feb 14, 2011 5:29 pm

Re: v1.8

Post by fax8 »

Yeah, I confirm that there are some problems in the sensor orientation within FreeIMU defines. I was actually working on fixing this but I've been quite busy lately so never dug as much as I wanted into the issue.

The correct orientation of FreeIMU v0.3.5 seems to be:

Code: Select all

#if defined(FREEIMUv035) || defined(FREEIMUv035_MS) || defined(FREEIMUv035_BMP)
  #define ITG3200
  #define BMA180
  #define HMC5883
  #define ACC_ORIENTATION(X, Y, Z)  {accADC[ROLL]  =  X; accADC[PITCH]  = Y; accADC[YAW]  = Z;}
  #define GYRO_ORIENTATION(X, Y, Z) {gyroADC[ROLL] =  X;  gyroADC[PITCH] = Y; gyroADC[YAW] = Z;}
  #define MAG_ORIENTATION(X, Y, Z)  {magADC[ROLL]  =  Y;  magADC[PITCH]  = -X; magADC[YAW]  = Z;}
  #undef INTERNAL_I2C_PULLUPS
  #if defined(FREEIMUv035_MS)
    #define MS561101BA
  #elif defined(FREEIMUv035_BMP)
    #define BMP085
  #endif
#endif


@Alex, Jussi should have sent you a FreeIMU v0.3.5_MS for testing.. did you receive it? If so would you mind to test the above?

fax8
Posts: 61
Joined: Mon Feb 14, 2011 5:29 pm

Re: v1.8

Post by fax8 »

Also, the support for MS5611-01BA is still too buggy to be enabled by default. Please make it disabled. I don't wanna people quads to crash in their heads!

Alexinparis
Posts: 1630
Joined: Wed Jan 19, 2011 9:07 pm

Re: v1.8

Post by Alexinparis »

Hamburger wrote:
Alexinparis wrote:I've just updated the faq accordingly: (the info was there, but without the MAG info)
http://www.multiwii.com/faq#How_should_ ... directions


very fast, thanks.
You might want to add a link to the stick combinations cheat sheet at google rep to the faq.
Btw, does it need an update? any new stick combinations lately?


Hi,
No more combination for the moment. It's enough complicated like this :)
Your stick combinations cheat would be perfect with the combination also for mode 1 :)

Alexinparis
Posts: 1630
Joined: Wed Jan 19, 2011 9:07 pm

Re: v1.8

Post by Alexinparis »

angel008 wrote:is there any change since 1.7 with the aux 1/2 (and servo 1/2) usage

I would love to use aux 2 (and may b even the 2 servo channels) on my arduino mini.

is this possible now or is this a hardware/software issue as I read about some people being able to use more then 5 channels on a arduino mini.

would love to have another switch beside aux 1 aux 2 would be perfect.

I'm using a aurora 9 and a 9ch reciever so ppm is as far as I know not possible..


no change about this:
pro mini: 5 channels max with a standard receiver, and 8 with a ppm sum receiver
mega boards: 8 channels with a standard receiver, and 8 with a ppm sum receiver

Alexinparis
Posts: 1630
Joined: Wed Jan 19, 2011 9:07 pm

Re: v1.8

Post by Alexinparis »

skygizmo wrote:Hi
Tested 1.8 today and have been stumbling into some problems.
my hardware:
paris 3.0 with Allinone board.

Issue 1:
If I use the built-in code for Allinone, then it's no sensors.

problem 2:
in Code 1.7 will use bma180 address 0x82, but in 1.8 it does not have to use 0x80.
do I back 1.7 so works 0x82 as it should.

I've no allinone board to test which is or which is not the default I2C address configuration or orientation.
I'm not even aware if there was several versions with different default jumper positions.
The final result in the gui should match this:
http://www.multiwii.com/faq#How_should_ ... directions
The best way if you are unsure about the board is to select each sensor individually and set up the correct I2C address and orientation.

Alexinparis
Posts: 1630
Joined: Wed Jan 19, 2011 9:07 pm

Re: v1.8

Post by Alexinparis »

spagoziak wrote:Thanks for the hint Alex! Will some future version have a more accessible method for gyro reversal?

yes maybe.
but for WMP, it's more untypical to have a different orientation.

Alexinparis
Posts: 1630
Joined: Wed Jan 19, 2011 9:07 pm

Re: v1.8

Post by Alexinparis »

fax8 wrote:@Alex, Jussi should have sent you a FreeIMU v0.3.5_MS for testing.. did you receive it? If so would you mind to test the above?

Hi,
Not yet. I think Jussi should be on holidays :)
But for sure, I will test it, and correct the orientation if needed. I would really like to compare it with the BMP085 baro is a real situation. Your results on your desk seems to be very accurate about it.

angel008
Posts: 5
Joined: Fri Aug 05, 2011 6:31 pm

Re: v1.8

Post by angel008 »

Alexinparis wrote:
angel008 wrote:is there any change since 1.7 with the aux 1/2 (and servo 1/2) usage

I would love to use aux 2 (and may b even the 2 servo channels) on my arduino mini.

is this possible now or is this a hardware/software issue as I read about some people being able to use more then 5 channels on a arduino mini.

would love to have another switch beside aux 1 aux 2 would be perfect.

I'm using a aurora 9 and a 9ch reciever so ppm is as far as I know not possible..


no change about this:
pro mini: 5 channels max with a standard receiver, and 8 with a ppm sum receiver
mega boards: 8 channels with a standard receiver, and 8 with a ppm sum receiver


ok i've seen a hardware converter for my receiver to ppm I will try that one.

another question I've read about the standard readings from the bma-020 wich should have a normal value of 200 on the Z axis but mine has one of 255-257 is this correct ? (haven't checked if this is 200 on 1.7 and i'm currently at work so can't check till later today..

User avatar
Hamburger
Posts: 2582
Joined: Tue Mar 01, 2011 2:14 pm
Location: air
Contact:

Re: v1.8

Post by Hamburger »

Alexinparis wrote:No more combination for the moment. It's enough complicated like this :)
Your stick combinations cheat would be perfect with the combination also for mode 1 :)


yes, we have gone a long way already. The cheat sheet just barely works as a two-sided credit card wrap around now.
As the 'source' document is available as well I guess a person interested and well versed in 'mode 1' could do the neccessary variation easily ;)
Can do (later).

User avatar
captaingeek
Posts: 228
Joined: Fri Jan 28, 2011 6:42 pm

Re: v1.8

Post by captaingeek »

after testing last night I'm still seeing some issues with level mode. I'm using an atmel i1 sensor board. hovers and flys great in acro mode. in level mode, i can set it so that it will hover perfectly level down close to the ground and that works good. but when I goto altitude to setup in hover in winds and have to fight to keep it in location I'll see the following issue.

Say the copter is facing the wind and im holding the pitch forward to keep it in a location for a few minutes, when I let go of the stick and go back to neutral the copter will want to fly off wildly in the opposite direction. It's as if after a few minutes of holding the stick its recalibrating the level point.

Is it just me? or my copter? I don't think the wind is really that strong but it is constean maybe 10mph. Pretty much all default pids. Maybe I have to increase the level rates a bit. Just curious if anyone else is seeing this? I havn't tested ziss_dm new level mode yet.

mooqray
Posts: 1
Joined: Mon Aug 08, 2011 6:46 pm

Re: v1.8

Post by mooqray »

Enjoying all the interesting links in the code comments. Looking forward to try the new version on my tricopter.

paddytfm
Posts: 8
Joined: Sun Aug 07, 2011 9:07 pm

Re: v1.8

Post by paddytfm »

Hi everybody
About reversing direction of sensor, changing sign of the proper axis , acc or gyro works fine.
// Assemble 14bit data
gyroADC[ROLL] = - ( ((rawADC[5]>>2)<<8) | rawADC[2] ); //range: +/- 8192
gyroADC[PITCH] = - ( ((rawADC[4]>>2)<<8) | rawADC[1] );
gyroADC[YAW] = - ( ((rawADC[3]>>2)<<8) | rawADC[0] );
GYRO_Common();
and
ACC_ORIENTATION( ( (rawADC[3]<<2) | ((rawADC[5]>>4)&0x02) ) ,
- ( (rawADC[2]<<2) | ((rawADC[5]>>3)&0x02) ) ,
( ((rawADC[4]>>1)<<3) | ((rawADC[5]>>5)&0x06) ) );
ACC_Common();
Both in sensor file
Assigning a different orientation not tested because not necessary on my different design
Just an idear why not implent those setup reverse or normal direction in GUI write procedure

Thank's to Alex for the positive results of wiicopter developments
Paddytfm

User avatar
Hamburger
Posts: 2582
Joined: Tue Mar 01, 2011 2:14 pm
Location: air
Contact:

Re: v1.8

Post by Hamburger »

captaingeek wrote:Say the copter is facing the wind and im holding the pitch forward to keep it in a location for a few minutes, when I let go of the stick and go back to neutral the copter will want to fly off wildly in the opposite direction. It's as if after a few minutes of holding the stick its recalibrating the level point.

me too, described it a bit earlier with different words but it is that same effect. Have had it since early v1.8 development.
Maybe it has to do with the Level I ? Never figured it out yet but it is annoying as I usually fly on an old airfield with strong wind and gusts.
Hamburger

mr.rc-cam
Posts: 457
Joined: Wed Jul 27, 2011 11:36 pm

Re: v1.8

Post by mr.rc-cam »

Say the copter is facing the wind and im holding the pitch forward to keep it in a location for a few minutes, when I let go of the stick and go back to neutral the copter will want to fly off wildly in the opposite direction. It's as if after a few minutes of holding the stick its recalibrating the level point.

Just a hunch, but it sounds like something related to the LEVEL's I-term value. Maybe a much lower value would provide some relief.

User avatar
jevermeister
Posts: 708
Joined: Wed Jul 20, 2011 8:56 am
Contact:

Re: v1.8

Post by jevermeister »

the errors in the pitch roll compensation lead to an non functional compensation if u use the flyduino board...

The lines should look like this:

Code: Select all

  #define DIGITAL_TILT_PITCH_HIGH    PORTC |= 1<<3;PORTL |= 1<<5;
  #define DIGITAL_TILT_PITCH_LOW     PORTC &= ~(1<<3);PORTL &= ~(1<<5);
  #define DIGITAL_TILT_ROLL_PINMODE  pinMode(35,OUTPUT);pinMode(45,OUTPUT); // 35 + 45
  #define DIGITAL_TILT_ROLL_HIGH     PORTC |= 1<<2;PORTL |= 1<<4;
  #define DIGITAL_TILT_ROLL_LOW      PORTC &= ~(1<<2);PORTL &

mr.rc-cam
Posts: 457
Joined: Wed Jul 27, 2011 11:36 pm

Re: v1.8

Post by mr.rc-cam »

Thanks for releasing V1.8! I've been using the earlier V1.8 (dev 20110714) on a piggish (50 ounce) Quad and wasn't having good success with the Altitude Hold. So the latest V1.8 definitely had me excited. But unfortunately after two days of PID experimentation the altitude hold is still not working well on my model. It is about the same as the earlier 1.8 dev version, which is unexpected because I can see some significant changes in the latest release's baro PID code.

For sure, If anyone with a large/heavy Quad is having alt-hold success then please share your baro PID secretes. :)

User avatar
captaingeek
Posts: 228
Joined: Fri Jan 28, 2011 6:42 pm

Re: v1.8

Post by captaingeek »

here's what im runnin currently... lowering I helped quite a bit for level mode. I noticed the cycle time bouncing from 3300 to 3800ms.

check out 3:08

http://www.youtube.com/watch?v=p9Nfp7LtURU
Attachments
baro 1.png

spagoziak
Posts: 171
Joined: Thu Jan 20, 2011 1:18 am

Re: v1.8

Post by spagoziak »

So far I've only flown 2 batteries through 1.8, but I've noticed that auto level needs a lot more P to get the results I'm used to. I still haven't tuned it fully yet because I'm chasing down a twitch on the FL/RR boom. Despite that, I've noticed that AL isn't crisp like it was in earlier versions. It seems like there's a bit of what the PDF filter was doing present in 1.8, where it would take a super long time to flatten out, or not at all if P was too low (and by low I mean less than 20).

Also, when moving from stationery to forward (or any other direction), the quad seems to sharply lurch into that direction, as though there were no expo for a moment. I haven't flown it FPV yet, but I'd bet that it'd be rather jarring to see in the goggles!

But... more tuning required, really. When something like this changes so much, it only makes sense that the MWC tuning needs to be updated.

spag

User avatar
jevermeister
Posts: 708
Joined: Wed Jul 20, 2011 8:56 am
Contact:

Re: v1.8

Post by jevermeister »

The sharp behavior is intended, the new approach in the level mode is designed to react to the very sensitive controls. The controls in hover and acro mode are the same now, I find i unusual in the beginning but got quite used to it after a few seconds - I like it now.

Nils

fax8
Posts: 61
Joined: Mon Feb 14, 2011 5:29 pm

Re: v1.8

Post by fax8 »

Correct orientation for FreeIMU v0.3.5 boards in MultiWii 1.8:

Code: Select all

#if defined(FREEIMUv035) || defined(FREEIMUv035_MS) || defined(FREEIMUv035_BMP)
  #define ITG3200
  #define BMA180
  #define HMC5883
  #define ACC_ORIENTATION(X, Y, Z)  {accADC[ROLL]  =  X; accADC[PITCH]  = Y; accADC[YAW]  = Z;}
  #define GYRO_ORIENTATION(X, Y, Z) {gyroADC[ROLL] =  X;  gyroADC[PITCH] = Y; gyroADC[YAW] = Z;}
  #define MAG_ORIENTATION(X, Y, Z)  {magADC[ROLL]  =  -Y;  magADC[PITCH]  = X; magADC[YAW]  = Z;}
  #undef INTERNAL_I2C_PULLUPS
  #if defined(FREEIMUv035_MS)
    #define MS561101BA
  #elif defined(FREEIMUv035_BMP)
    #define BMP085
  #endif
#endif


MultiWii also lacks support for v0.3 and v0.3.1 which used the ADXL346, ITG3200 and HMC5883L. The following add support for it.

Code: Select all

#if defined(FREEIMUv03)
  #define ITG3200
  #define ADXL345 // this is actually an ADXL346 but that's just the same as ADXL345
  #define HMC5883
  #define ACC_ORIENTATION(X, Y, Z)  {accADC[ROLL]  =  -Y; accADC[PITCH]  = X; accADC[YAW]  = Z;}
  #define GYRO_ORIENTATION(X, Y, Z) {gyroADC[ROLL] =  X;  gyroADC[PITCH] = Y; gyroADC[YAW] = Z;}
  #define MAG_ORIENTATION(X, Y, Z)  {magADC[ROLL]  =  -Y;  magADC[PITCH]  = X; magADC[YAW]  = Z;}
  #define ADXL345_ADDRESS 0xA6
  #undef INTERNAL_I2C_PULLUPS
#endif


Relevant board definine would became as the following in config.h:

Code: Select all

//#define FREEIMUv1       // v0.1 & v0.2 & v0.3 version of 9DOF board from Fabio
//#define FREEIMUv03       // FreeIMU v0.3 and v0.3.1
//#define FREEIMUv035     // FreeIMU v0.3.5 no baro
//#define FREEIMUv035_MS  // FreeIMU v0.3.5_MS
//#define FREEIMUv035_BMP // FreeIMU v0.3.5_MS


Alex, would you please merge this in the MultiWii code? Thanks.

MichalM_sk
Posts: 89
Joined: Wed Jun 15, 2011 5:04 pm
Location: Slovakia

Re: v1.8

Post by MichalM_sk »

Have someone tested v1.8 with WMP + NK in level mode ?
Thanks.

/Michal

alexmos
Posts: 108
Joined: Tue Aug 09, 2011 12:12 pm

Re: v1.8

Post by alexmos »

Uploaded last night v1.8, ALLINONE board all sensors works fine in GUI with default config. But model in hands feels more reactive to disturbance compared to v1.7. Will try to fly soon.

User avatar
shikra
Posts: 783
Joined: Wed Mar 30, 2011 7:58 pm

Re: v1.8

Post by shikra »

MichalM_sk wrote:Have someone tested v1.8 with WMP + NK in level mode ?
Thanks.

/Michal


Yes - with a tri only. I like it a lot. It is working VERY well for me on a signguy style tri

I have flown a few batteries with it now.
Some flights were with autolevel on for the entire flight !!

I did have to reduce the autolevel P down to 3 or 4 and I to half the default. I like it like this because it flies like autolevel is not on, but let go of sticks and it returns to level in about 1-2 secs.... Makes for very easy no thinking flying!



I did try the experimental Pseudo-derivative conrtroller for level mode. It is also very good for a stable hover, but don't try flying around with it enabled!! Don't ask why...

Alexinparis
Posts: 1630
Joined: Wed Jan 19, 2011 9:07 pm

Re: v1.8

Post by Alexinparis »

Ok, thanks, it's very clear like this.
it's now merged in the dev version.

fax8 wrote:Correct orientation for FreeIMU v0.3.5 boards in MultiWii 1.8:

Code: Select all

#if defined(FREEIMUv035) || defined(FREEIMUv035_MS) || defined(FREEIMUv035_BMP)
  #define ITG3200
  #define BMA180
  #define HMC5883
  #define ACC_ORIENTATION(X, Y, Z)  {accADC[ROLL]  =  X; accADC[PITCH]  = Y; accADC[YAW]  = Z;}
  #define GYRO_ORIENTATION(X, Y, Z) {gyroADC[ROLL] =  X;  gyroADC[PITCH] = Y; gyroADC[YAW] = Z;}
  #define MAG_ORIENTATION(X, Y, Z)  {magADC[ROLL]  =  -Y;  magADC[PITCH]  = X; magADC[YAW]  = Z;}
  #undef INTERNAL_I2C_PULLUPS
  #if defined(FREEIMUv035_MS)
    #define MS561101BA
  #elif defined(FREEIMUv035_BMP)
    #define BMP085
  #endif
#endif


MultiWii also lacks support for v0.3 and v0.3.1 which used the ADXL346, ITG3200 and HMC5883L. The following add support for it.

Code: Select all

#if defined(FREEIMUv03)
  #define ITG3200
  #define ADXL345 // this is actually an ADXL346 but that's just the same as ADXL345
  #define HMC5883
  #define ACC_ORIENTATION(X, Y, Z)  {accADC[ROLL]  =  -Y; accADC[PITCH]  = X; accADC[YAW]  = Z;}
  #define GYRO_ORIENTATION(X, Y, Z) {gyroADC[ROLL] =  X;  gyroADC[PITCH] = Y; gyroADC[YAW] = Z;}
  #define MAG_ORIENTATION(X, Y, Z)  {magADC[ROLL]  =  -Y;  magADC[PITCH]  = X; magADC[YAW]  = Z;}
  #define ADXL345_ADDRESS 0xA6
  #undef INTERNAL_I2C_PULLUPS
#endif


Relevant board definine would became as the following in config.h:

Code: Select all

//#define FREEIMUv1       // v0.1 & v0.2 & v0.3 version of 9DOF board from Fabio
//#define FREEIMUv03       // FreeIMU v0.3 and v0.3.1
//#define FREEIMUv035     // FreeIMU v0.3.5 no baro
//#define FREEIMUv035_MS  // FreeIMU v0.3.5_MS
//#define FREEIMUv035_BMP // FreeIMU v0.3.5_MS


Alex, would you please merge this in the MultiWii code? Thanks.

Nimzan
Posts: 11
Joined: Wed Jun 01, 2011 5:44 am
Location: Brisbane, Australia.

Re: v1.8

Post by Nimzan »

Great work!!
Looking forward to testing this. My Paris Board is the only part still working after my latest crash/test flight.

Post Reply