GPS integration

This forum is dedicated to software development related to MultiWii.
It is not the right place to submit a setup problem.
Software download
User avatar
Crashpilot1000
Posts: 631
Joined: Tue Apr 03, 2012 7:38 pm

Re: GPS integration

Post by Crashpilot1000 »

Hi!
From inspecting the MTK serial datastream in binary mode i found some problems wich the current readout in the I2C version, wich also exists in the apm code. The checksum B is not transmitted at all. I rewrote the binary readout for mtk. I omitted the single byte checksum, because i found it useless anyway. It can be added. I watched the data over minutes at 57K serial speed and 10Hz MTK updaterate and had no serial errors at all. Sorry for the simple code - but it works! Perhaps the binary mtk protocol can be re-enabled in the next DEV?

Code: Select all

bool GPS_MTK_newFrame(uint8_t data)
{
   static uint8_t pstep;                              // Parse Step
   static uint8_t lastbyte;                           // Last Byte for Sync detection
   static uint8_t LSLshifter;                         // Bitshiftvalue

   static int32_t lat;                                // MTK Dataset
   static int32_t lon;                                // MTK Dataset
   static int32_t alt;                                // MTK Dataset
   static int32_t grspeed;                            // MTK Dataset
   static int32_t grcourse;                           // MTK Dataset
   static uint8_t satn;                               // MTK Dataset
   int32_t tmp32;
   bool parsed;
   
   parsed = false;

   if (data == 0xdd && lastbyte == 0xd0) pstep = 100; // Detect Sync "0xD0,0xDD"
   lastbyte = data;

   switch(pstep) {
    case 0:                                           //  Special Case: Do Nothing
    break;
    case 100:                                         //  Special Case: Jump into decoding on next run
    pstep = 1;
    break;

    case 1:                                           //  Ignore Payload Byte (This is the first Byte after sync preamble)
    pstep++;
    break;

    case 2:                                           // Read Dataset Latitude
    lat = data;
    LSLshifter = 0;
    pstep++;
    break;
    case 3:
    LSLshifter = LSLshifter+8;
    tmp32 = data;
    tmp32 = tmp32<<LSLshifter;
    lat = lat | tmp32;
    if (LSLshifter == 24){lat = lat * 10; pstep++;}
    break;   

    case 4:                                           // Read Dataset Longitude
    lon = data;
    LSLshifter = 0;
    pstep++;
    break;
    case 5:
    LSLshifter = LSLshifter+8;
    tmp32 = data;
    tmp32 = tmp32<<LSLshifter;
    lon = lon | tmp32;
    if (LSLshifter == 24){lon = lon * 10; pstep++;}
    break;

    case 6:                                           // Read Dataset MSL Altitude
    alt = data;
    LSLshifter = 0;
    pstep++;
    break;
    case 7:
    LSLshifter = LSLshifter+8;
    tmp32 = data;
    tmp32 = tmp32<<LSLshifter;
    alt = alt | tmp32;
    if (LSLshifter == 24){alt = alt/100; pstep++;}
    break;

    case 8:                                           // Read Dataset Ground Speed
    grspeed = data;
    LSLshifter = 0;
    pstep++;
    break;
    case 9:
    LSLshifter = LSLshifter+8;
    tmp32 = data;
    tmp32 = tmp32<<LSLshifter;
    grspeed = grspeed | tmp32;
    if (LSLshifter == 24) pstep++;
    break;

    case 10:                                          // Read Dataset Heading
    grcourse = data;
    LSLshifter = 0;
    pstep++;
    break;
    case 11:
    LSLshifter = LSLshifter+8;
    tmp32 = data;
    tmp32 = tmp32<<LSLshifter;
    grcourse = grcourse | tmp32;
    if (LSLshifter == 24) pstep++;
    break;

    case 12:                                          // Read number of satellites in view
    satn = data;
    pstep++;
    break;
   
    case 13:                                          // Read Fix Type and finish readout, mwii does not need the rest
    if (data==1){                                     // No Fix
    i2c_dataset.status.gps2dfix = 0;
    i2c_dataset.status.gps3dfix = 0;}
    if (data==2){                                     // GPS 2D Fix
    i2c_dataset.status.gps2dfix = 1;
    i2c_dataset.status.gps3dfix = 0;}
    if (data==3){                                     // GPS 3D Fix
    i2c_dataset.status.gps2dfix = 1;
    i2c_dataset.status.gps3dfix = 1;}
    GPS_read[LAT] = lat;
    GPS_read[LON] = lon;
    i2c_dataset.altitude = alt;
    i2c_dataset.ground_speed = grspeed;
    i2c_dataset.ground_course = grcourse;
    i2c_dataset.status.numsats = satn;
    parsed = true;                                    // RDY
    pstep = 0;                                        // Do nothing with the next bytes
    break;
   }
 return parsed;
}



So long
Kraut Rob
Attachments
Standing copter on the ground for 5 minutes in a gps - difficult area.
Standing copter on the ground for 5 minutes in a gps - difficult area.

User avatar
Crashpilot1000
Posts: 631
Joined: Tue Apr 03, 2012 7:38 pm

Re: GPS integration

Post by Crashpilot1000 »

BTW: I omitted the Payload Byte for a reason. It is always $20!! And that is wrong, because with no sattelites a much shorter sentence is send!

Example sequence when no sats:

Code: Select all

D0DD            Dataset
20                Wrong Payloadbyte
84 35 01 C4
EA EB 8A 01
0F 27 34 AD

D0DD           Next Dataset
20               Wrong Payloadbyte
84 35 01 C4
EA 2B AA 01
0F 27 94 CD

Vaattari
Posts: 14
Joined: Tue Mar 27, 2012 8:17 am

Re: GPS integration

Post by Vaattari »

@Crashpilot1000

What GPS & FW version are you using?
I have MTK 1.6 from here: http://code.google.com/p/ardupilot/wiki/MediaTek
I do not think MTK FW 1.6 is supporting 57600 with bin mode, thus I'm using 115200 with 10Hz. With 57600 the GPS does not respond here :roll:
I could not see any benefit of 5Hz and I also disabled GPS filter.

How can I easily verify, if and how much, there are RS232 errors?

I'm happy to try the fix you found, when available in dev. :)

Thanks.
Janne

User avatar
Crashpilot1000
Posts: 631
Joined: Tue Apr 03, 2012 7:38 pm

Re: GPS integration

Post by Crashpilot1000 »

@Vaattari:

Thank you for your interest! I use the eos bandi recommended FW AXN1.51_2722_3329_384.1151100.5.bin (http://code.google.com/p/i2c-gps-nav/do ... p&can=2&q=). The change of the baudrates is not accessible in config.h you have to change it in the code directly. I monitored the traffic between arduino and the gps with an ftdi adapter and the free terminal software "PUTTY". Afterwards i analyzed the log file with hexedit (shareware). I will have to change the code from above to sort out gps positions wich produce the syncword... but stay tuned. I think using mtk in binary mode (like ublox) is the way to go.

So long
Kraut Rob

wilco1967
Posts: 156
Joined: Thu Aug 18, 2011 6:04 pm
Location: Winterswijk, Netherlands

Re: GPS integration

Post by wilco1967 »

am I correct in assuming that MTK binary protocol is only available in I2C GPS, an not for the serial GPS (directly to Mega) ?

Is binary really soo much better than NEMA ?

Currently using a flyduino with 3329 GPS.... it works fine, but pos hold still rather poor (upto 10 meters drifting off). Perhaps binary mode will improve that, but find it difficult to believe...

User avatar
Crashpilot1000
Posts: 631
Joined: Tue Apr 03, 2012 7:38 pm

Re: GPS integration

Post by Crashpilot1000 »

@wilco1967: Your assumption is correct.
I don't know if it is so much better, but it is better than NMEA.
I improved the mtk binary read out from the last post. Since the preamble "D0 DD" is always followed by $20 i took this value as further preamblebyte. So this bytesequence is used for sync now: "D0 DD 20". The next problem is the damn inconstant size of a complete dataset whether sattelites are available or not. The next problem is, that the sync could be generated by lat/lon data so i disabled sync search while lat/lon aquisition.
Here is my next code proposal for MTK binary parsing:

Code: Select all

bool GPS_MTK_newFrame(uint8_t data)
{
   static uint8_t pstep;                              // Parse Step
   static uint8_t lastbyte;                           // Last Byte for Sync detection
   static uint8_t LSLshifter;                         // Bitshiftvalue

   static int32_t lat;                                // MTK Dataset
   static int32_t lon;                                // MTK Dataset
   static int32_t alt;                                // MTK Dataset
   static int32_t grspeed;                            // MTK Dataset
   static int32_t grcourse;                           // MTK Dataset
   static uint8_t satn;                               // MTK Dataset
   int32_t tmp32;
   bool parsed;
   
   parsed = false;

   if(pstep == 0 || pstep>5){                         // Only search for Sync when idle or lat and lon already decoded.
    if (data == 0xdd && lastbyte == 0xd0) pstep = 100;// Detect Sync "0xD0,0xDD"
   }
   lastbyte = data;

   switch(pstep) {
    case 0:                                           // Special Case: Do Nothing
    break;
    case 100:                                         // Special Case: Jump into decoding on next run
    pstep = 1;
    break;

    case 1:                                           // Payload Byte is always $20! (This is the first Byte after sync preamble)
    if (data == 0x20) pstep++;                        // Since it is always $20 we take it as extended, undocumented syncword "preamble3"
     else pstep =0;
    break;

    case 2:                                           // Read Dataset Latitude
    lat = data;
    LSLshifter = 0;
    pstep++;
    break;
    case 3:
    LSLshifter = LSLshifter+8;
    tmp32 = data;
    tmp32 = tmp32<<LSLshifter;
    lat = lat | tmp32;
    if (LSLshifter == 24){lat = lat * 10; pstep++;}
    break;   

    case 4:                                           // Read Dataset Longitude
    lon = data;
    LSLshifter = 0;
    pstep++;
    break;
    case 5:
    LSLshifter = LSLshifter+8;
    tmp32 = data;
    tmp32 = tmp32<<LSLshifter;
    lon = lon | tmp32;
    if (LSLshifter == 24){lon = lon * 10; pstep++;}
    break;

    case 6:                                           // Read Dataset MSL Altitude
    alt = data;
    LSLshifter = 0;
    pstep++;
    break;
    case 7:
    LSLshifter = LSLshifter+8;
    tmp32 = data;
    tmp32 = tmp32<<LSLshifter;
    alt = alt | tmp32;
    if (LSLshifter == 24){alt = alt/100; pstep++;}
    break;

    case 8:                                           // Read Dataset Ground Speed
    grspeed = data;
    LSLshifter = 0;
    pstep++;
    break;
    case 9:
    LSLshifter = LSLshifter+8;
    tmp32 = data;
    tmp32 = tmp32<<LSLshifter;
    grspeed = grspeed | tmp32;
    if (LSLshifter == 24) pstep++;
    break;

    case 10:                                          // Read Dataset Heading
    grcourse = data;
    LSLshifter = 0;
    pstep++;
    break;
    case 11:
    LSLshifter = LSLshifter+8;
    tmp32 = data;
    tmp32 = tmp32<<LSLshifter;
    grcourse = grcourse | tmp32;
    if (LSLshifter == 24) pstep++;
    break;

    case 12:                                          // Read number of satellites in view
    satn = data;
    pstep++;
    break;
   
    case 13:                                          // Read Fix Type and finish readout, mwii does not need the rest
    if (data==1){                                     // No Fix
    i2c_dataset.status.gps2dfix = 0;
    i2c_dataset.status.gps3dfix = 0;}
    if (data==2){                                     // GPS 2D Fix
    i2c_dataset.status.gps2dfix = 1;
    i2c_dataset.status.gps3dfix = 0;}
    if (data==3){                                     // GPS 3D Fix
    i2c_dataset.status.gps2dfix = 1;
    i2c_dataset.status.gps3dfix = 1;}
    GPS_read[LAT] = lat;
    GPS_read[LON] = lon;
    i2c_dataset.altitude = alt;
    i2c_dataset.ground_speed = grspeed;
    i2c_dataset.ground_course = grcourse;
    i2c_dataset.status.numsats = satn;
    parsed = true;                                    // RDY
    pstep = 0;                                        // Do nothing with the next bytes
    break;
   }
 return parsed;
}



So long

Rob

User avatar
EOSBandi
Posts: 802
Joined: Sun Jun 19, 2011 11:32 am
Location: Budapest, Hungary
Contact:

Re: GPS integration

Post by EOSBandi »

Hi Rob,
Can you check with MinGPS that you successfully upgraded the firmware on your gps ? I just made a quick test with a PA6B module and AXN 1.51 2722. I got a normal $20 long response without satelite lock too.

Code: Select all

D0DD20000000000000000084350000000000000000000001013C3D0100AE512C0C0F27C2A1
D0DD20000000000000000084350000000000000000000001013C3D010096552C0C0F27AE25
D0DD20000000000000000084350000000000000000000001013C3D01007E592C0C0F279AA9
D0DD20000000000000000084350000000000000000000001013C3D0100665D2C0C0F27862D
D0DD20000000000000000084350000000000000000000001013C3D01004E612C0C0F2772B1
D0DD20000000000000000084350000000000000000000001013C3D010036652C0C0F275E35
D0DD20000000000000000084350000000000000000000001013C3D01001E692C0C0F274AB9
D0DD20000000000000000084350000000000000000000001013C3D0100066D2C0C0F27363D
D0DD20000000000000000084350000000000000000000001013C3D0100EE702C0C0F2721BC
D0DD20000000000000000084350000000000000000000001013C3D0100D6742C0C0F270D40
D0DD20000000000000000084350000000000000000000001013C3D0100BE782C0C0F27F9C4
D0DD20000000000000000084350000000000000000000001013C3D0100A67C2C0C0F27E548


This is consistent with the current parser and documentation.
What module are you using ?

EOS

User avatar
EOSBandi
Posts: 802
Joined: Sun Jun 19, 2011 11:32 am
Location: Budapest, Hungary
Contact:

Re: GPS integration

Post by EOSBandi »

Crashpilot1000 wrote:@Vaattari:

Thank you for your interest! I use the eos bandi recommended FW AXN1.51_2722_3329_384.1151100.5.bin (http://code.google.com/p/i2c-gps-nav/do ... p&can=2&q=). The change of the baudrates is not accessible in config.h you have to change it in the code directly. I monitored the traffic between arduino and the gps with an ftdi adapter and the free terminal software "PUTTY". Afterwards i analyzed the log file with hexedit (shareware). I will have to change the code from above to sort out gps positions wich produce the syncword... but stay tuned. I think using mtk in binary mode (like ublox) is the way to go.

So long
Kraut Rob


Well, it seems that your capture setup is somehow omits zeroes from the output... try using realterm instead of putty and hexedit....

User avatar
Crashpilot1000
Posts: 631
Joined: Tue Apr 03, 2012 7:38 pm

EPIC FAIL!!!

Post by Crashpilot1000 »

@EOS Bandi:

You are right! That was an epic fail of me. But somehow i don't feel to shabby because i rechecked putty. It was set to "Logging: All session output", and the zero bytes in the datasets with satfix were transmitted, but somehow it decides when to much zero bytes occur to cut them out! Your tip of using Realterm was the key! Now all datasets are displayed correctly! This confusion has one upside: Now i have my own working and reliable mtk binary parser. It might be obsolete now but i post it anyway, maybe it is of some use for somebody.

Code: Select all

bool GPS_MTK_newFrame(uint8_t data)
{
   static uint8_t pstep;                              // Parse Step
   static uint8_t lastbyte;                           // Last Byte for Sync detection
   static uint8_t LSLshifter;                         // Bitshiftvalue
   static uint8_t chkA,count;

   static int32_t lat;                                // MTK Dataset
   static int32_t lon;                                // MTK Dataset
   static int32_t alt;                                // MTK Dataset
   static int32_t grspeed;                            // MTK Dataset
   static int32_t grcourse;                           // MTK Dataset
   static uint8_t satn,fixtype;                       // MTK Dataset
   int32_t tmp32;
   bool parsed;
   
   parsed = false;

   if (pstep == 0 && data == 0xdd && lastbyte == 0xd0) pstep = 100; // Detect Sync "0xD0,0xDD" Only search for Sync when not already decoding
   lastbyte = data;

   switch(pstep) {
    case 0:                                           // Special Case: Do Nothing
    break;
    case 100:                                         // Special Case: Prepare next decoding run
    pstep = 1;                                        // Jump into decoding on next run
    chkA = 0; count = 0;                              // Reset values
    break;

    case 1:                                           // Payload Byte is always $20! (This is the first Byte after sync preamble)
    if (data == 0x20) pstep++;                        // Since it is always $20 we take it as extended, undocumented syncword "preamble3"
     else pstep =0;                                   // Error! Wait for sync
    chkA = chkA + data;
    count ++;
    break;

    case 2:                                           // Read Dataset Latitude
    lat = data;
    LSLshifter = 0;
    pstep++;
    chkA = chkA + data;
    count ++;
    break;
    case 3:
    LSLshifter = LSLshifter+8;
    tmp32 = data;
    tmp32 = tmp32<<LSLshifter;
    lat = lat | tmp32;
    if (LSLshifter == 24){lat = lat * 10; pstep++;}
    chkA = chkA + data;
    count ++;
    break;   

    case 4:                                           // Read Dataset Longitude
    lon = data;
    LSLshifter = 0;
    pstep++;
    chkA = chkA + data;
    count ++;
    break;
    case 5:
    LSLshifter = LSLshifter+8;
    tmp32 = data;
    tmp32 = tmp32<<LSLshifter;
    lon = lon | tmp32;
    if (LSLshifter == 24){lon = lon * 10; pstep++;}
    chkA = chkA + data;
    count ++;
    break;

    case 6:                                           // Read Dataset MSL Altitude
    alt = data;
    LSLshifter = 0;
    pstep++;
    chkA = chkA + data;
    count ++;
    break;
    case 7:
    LSLshifter = LSLshifter+8;
    tmp32 = data;
    tmp32 = tmp32<<LSLshifter;
    alt = alt | tmp32;
    if (LSLshifter == 24){alt = alt/100; pstep++;}
    chkA = chkA + data;
    count ++;
    break;

    case 8:                                           // Read Dataset Ground Speed
    grspeed = data;
    LSLshifter = 0;
    pstep++;
    chkA = chkA + data;
    count ++;
    break;
    case 9:
    LSLshifter = LSLshifter+8;
    tmp32 = data;
    tmp32 = tmp32<<LSLshifter;
    grspeed = grspeed | tmp32;
    if (LSLshifter == 24) pstep++;
    chkA = chkA + data;
    count ++;
    break;

    case 10:                                          // Read Dataset Heading
    grcourse = data;
    LSLshifter = 0;
    pstep++;
    chkA = chkA + data;
    count ++;
    break;
    case 11:
    LSLshifter = LSLshifter+8;
    tmp32 = data;
    tmp32 = tmp32<<LSLshifter;
    grcourse = grcourse | tmp32;
    if (LSLshifter == 24) pstep++;
    chkA = chkA + data;
    count ++;
    break;

    case 12:                                          // Read number of satellites in view
    satn = data;
    pstep++;
    chkA = chkA + data;
    count ++;
    break;
   
    case 13:                                          // Read Fix Type
    fixtype = data;
    pstep++;
    chkA = chkA + data;
    count ++;
    break;

    case 14:                                          // Wait for cheksum A
    if (count == 33){                                 // 33 = 0x21
      if (chkA == data) pstep++;                      // ChecksumA reached. Correct? than go on
       else pstep = 0;                                // Error?
    }else{
      chkA = chkA + data;
      count ++;}
    break;

    case 15:                                          // Dataset RDY !! Cheksum B omitted, ChkA was OK
    if (fixtype==1){                                  // No Fix
    i2c_dataset.status.gps2dfix = 0;
    i2c_dataset.status.gps3dfix = 0;}
    if (fixtype==2){                                  // GPS 2D Fix
    i2c_dataset.status.gps2dfix = 1;
    i2c_dataset.status.gps3dfix = 0;}
    if (fixtype==3){                                  // GPS 3D Fix
    i2c_dataset.status.gps2dfix = 1;
    i2c_dataset.status.gps3dfix = 1;}
    GPS_read[LAT] = lat;
    GPS_read[LON] = lon;
    i2c_dataset.altitude = alt;
    i2c_dataset.ground_speed = grspeed;
    i2c_dataset.ground_course = grcourse;
    i2c_dataset.status.numsats = satn;
    parsed = true;                                    // RDY
    pstep = 0;                                        // Do nothing
    break;
   }
 return parsed;
}


BTW: I use MTK 3329 with your recommended FW AXN1.51_2722_3329_384.1151100.5.bin. It is called LZ-GPS (http://www.wii-copter.de/lz-gps.html)

So long
Kraut
Rob

User avatar
Crashpilot1000
Posts: 631
Joined: Tue Apr 03, 2012 7:38 pm

Re: GPS integration

Post by Crashpilot1000 »

@EOS Bandi:
Do you have any documentation for the AXN1.51_2722_3329_384.1151100.5.bin? I can't find it. It would be interesting to know what is turned on after switching to binary mode by default. From what i see here SBAS and 10HZ in binary is no-go: viewtopic.php?f=6&t=1881&start=10#p19325.

So long
Kraut Rob

User avatar
EOSBandi
Posts: 802
Joined: Sun Jun 19, 2011 11:32 am
Location: Budapest, Hungary
Contact:

Re: GPS integration

Post by EOSBandi »

Crashpilot1000 wrote:@EOS Bandi:
Do you have any documentation for the AXN1.51_2722_3329_384.1151100.5.bin? I can't find it. It would be interesting to know what is turned on after switching to binary mode by default. From what i see here SBAS and 10HZ in binary is no-go: viewtopic.php?f=6&t=1881&start=10#p19325.

So long
Kraut Rob

It is unknown. the AXN 1.51 is a customized firmware and the settings depends on how this form (http://www.trenz-electronic.de/fileadmi ... 120828.pdf) was filled out by the company who ordered this customization. GlobalTek unfortunately does not disclose details of customized firmwares :(

User avatar
Crashpilot1000
Posts: 631
Joined: Tue Apr 03, 2012 7:38 pm

Re: GPS integration

Post by Crashpilot1000 »

@EOS Bandi: I understand.
Sorry to bother you again but do you think the mysterious AXN1.51_2722_3329_384.1151100.5.bin ("Sergey")is better than the original DIY Drones 1.6 (AXN1.30_2389_3329_384.1151100.1_v16.bin "3DRobotics")? At least for the 3drobotics fw the correct initialisation sequence is known.

So long

Kraut Rob

User avatar
EOSBandi
Posts: 802
Joined: Sun Jun 19, 2011 11:32 am
Location: Budapest, Hungary
Contact:

Re: GPS integration

Post by EOSBandi »

Crashpilot1000 wrote:@EOS Bandi: I understand.
Sorry to bother you again but do you think the mysterious AXN1.51_2722_3329_384.1151100.5.bin ("Sergey")is better than the original DIY Drones 1.6 (AXN1.30_2389_3329_384.1151100.1_v16.bin "3DRobotics")? At least for the 3drobotics fw the correct initialisation sequence is known.

So long

Kraut Rob

According to this faq: http://forum.trenz-electronic.de/index. ... a49ffd8b27
With the firmware update from version AXN1.30 to AXN1.50, the navigation performance has been improved in terms of accuracy and consistency for the following unfavorable conditions:
•weak signal condition under a viaduct
•weak signal condition in deep urban areas
•weak signal condition in dense forest
•static drifting reduction

User avatar
dramida
Posts: 473
Joined: Mon Feb 28, 2011 12:58 pm
Location: Bucharest
Contact:

Re: GPS integration

Post by dramida »

Hello EosBandi, please bring Santa earlier this year and write a single way-point (x-y-alt) implementation with WinGui.

albertoLG
Posts: 57
Joined: Fri Sep 07, 2012 8:14 am

Re: GPS integration

Post by albertoLG »

EOSBandi wrote:
Crashpilot1000 wrote:@EOS Bandi: I understand.
Sorry to bother you again but do you think the mysterious AXN1.51_2722_3329_384.1151100.5.bin ("Sergey")is better than the original DIY Drones 1.6 (AXN1.30_2389_3329_384.1151100.1_v16.bin "3DRobotics")? At least for the 3drobotics fw the correct initialisation sequence is known.

So long

Kraut Rob

According to this faq: http://forum.trenz-electronic.de/index. ... a49ffd8b27
......
•static drifting reduction


I have a strange problem with my GPS module, MT3329, and I think is because of this.... I can read the coordinates, then move(walk) 10 meters away and the coords are still the same, then after some more time they will change, with my gps's phone they change as soon as i move... probably is a feature of this firmware, but I think in the position hold it can give some problems if the multirotor move slow from his position and the multiwii reading the coords think is still in the same position, am I wrong? anyway I ordered an U-BLOX module, the CN-06 V2, hope will be better

User avatar
Crashpilot1000
Posts: 631
Joined: Tue Apr 03, 2012 7:38 pm

Re: GPS integration

Post by Crashpilot1000 »

@EOS Bandi: Thank you for your reply and the link!

@Alberto: Difficult to say, because your phone could do a integration of gps data with the imu data to detect movement and direction. But the FW 1.51 feature "static drifting reduction" could be a problem for PH. Without insight into the function it is difficult to say. I just did GPS tests with static copter (gps-difficult area) and with the FW 1.51 the Position is reported more precise and it gets more sats in a shorter time. Could you do a comparison with the 3drobotics FW in motion (before your ublox arrives :) )??

So long
Kraut Rob

albertoLG
Posts: 57
Joined: Fri Sep 07, 2012 8:14 am

Re: GPS integration

Post by albertoLG »

Crashpilot1000 wrote:@EOS Bandi: Thank you for your reply and the link!

@Alberto: Difficult to say, because your phone could do a integration of gps data with the imu data to detect movement and direction. But the FW 1.51 feature "static drifting reduction" could be a problem for PH. Without insight into the function it is difficult to say. I just did GPS tests with static copter (gps-difficult area) and with the FW 1.51 the Position is reported more precise and it gets more sats in a shorter time. Could you do a comparison with the 3drobotics FW in motion (before your ublox arrives :) )??

So long
Kraut Rob

i'll reflash my gps with diydrones firmware AXN1.30_2389_3329_384.1151100.1_v16.bin is this right? in a couple of hours i'll report back

edit:
flashed, max refresh rate is 5Hz with this firmware, need to wait for my notebook to test outside and see if changed something :geek:

albertoLG
Posts: 57
Joined: Fri Sep 07, 2012 8:14 am

Re: GPS integration

Post by albertoLG »

Ok, tested it, 8/9 satellites, nothing has changed.... still don't update the data after 10/20 meters, in the car it works fine if moving... shelved it and waiting for the U-BLOX to arrive and do more tests

User avatar
EOSBandi
Posts: 802
Joined: Sun Jun 19, 2011 11:32 am
Location: Budapest, Hungary
Contact:

Re: GPS integration

Post by EOSBandi »

albertoLG wrote:Ok, tested it, 8/9 satellites, nothing has changed.... still don't update the data after 10/20 meters, in the car it works fine if moving... shelved it and waiting for the U-BLOX to arrive and do more tests


It seems that the nav threshold setting is active on your gps. Check it with $PMTK447*35<CR><LF> is must be 0.0
Regards,
EOS

albertoLG
Posts: 57
Joined: Fri Sep 07, 2012 8:14 am

THAT FIXED IT!!!

Post by albertoLG »

EOSBandi wrote:
albertoLG wrote:Ok, tested it, 8/9 satellites, nothing has changed.... still don't update the data after 10/20 meters, in the car it works fine if moving... shelved it and waiting for the U-BLOX to arrive and do more tests


It seems that the nav threshold setting is active on your gps. Check it with $PMTK447*35<CR><LF> is must be 0.0
Regards,
EOS


THAT FIXED IT!!

I modified the GPS.INO adding this line

previous

Code: Select all

// at this point we have GPS working at selected (via #define GPS_BAUD) baudrate
      SerialOpen(GPS_SERIAL,GPS_BAUD);
      SerialGpsPrint(PSTR("$PMTK314,0,1,0,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0*28\r\n")); // only GGA and RMC sentence
      SerialGpsPrint(PSTR("$PMTK220,200*2C\r\n"));           // 5 Hz update rate


new

Code: Select all

// at this point we have GPS working at selected (via #define GPS_BAUD) baudrate
      SerialOpen(GPS_SERIAL,GPS_BAUD);
      SerialGpsPrint(PSTR("$PMTK314,0,1,0,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0*28\r\n")); // only GGA and RMC sentence
      SerialGpsPrint(PSTR("$PMTK220,200*2C\r\n"));           // 5 Hz update rate
      SerialGpsPrint(PSTR("$PMTK397,0.2*3F\r\n"));           // Set threshold to 0.2


now it update the coordinates at every little movement.... thanks EOSBandi

User avatar
Crashpilot1000
Posts: 631
Joined: Tue Apr 03, 2012 7:38 pm

Re: GPS integration

Post by Crashpilot1000 »

@EOS Bandi: Yes! Thank you for this info!
I did nearly the same thing like albertoLG with the same good result on 3drobotics FW(1.6). But i set the threshold to 0 with the command:

Code: Select all

  #define MTK_NAVTHRES_OFF      "$PMTK397,0*23\r\n"  // Turn off Navthreshold for sure, so every GPS is send


So long

Kraut Rob

albertoLG
Posts: 57
Joined: Fri Sep 07, 2012 8:14 am

Re: GPS integration

Post by albertoLG »

Crashpilot1000 wrote:@EOS Bandi: Yes! Thank you for this info!
I did nearly the same thing like albertoLG with the same good result on 3drobotics FW(1.6). But i set the threshold to 0 with the command:

Code: Select all

  #define MTK_NAVTHRES_OFF      "$PMTK397,0*23\r\n"  // Turn off Navthreshold for sure, so every GPS is send


So long

Kraut Rob


hhmm.. shouldn't be

Code: Select all

$PMTK397,0*3F\r\n


to zero threshold or I'm wrong?

User avatar
Crashpilot1000
Posts: 631
Joined: Tue Apr 03, 2012 7:38 pm

Re: GPS integration

Post by Crashpilot1000 »

Nope! The number after " * " is the checksum. You can calculate it here: http://www.hhhh.org/wiml/proj/nmeaxor.html

albertoLG
Posts: 57
Joined: Fri Sep 07, 2012 8:14 am

Re: GPS integration

Post by albertoLG »

Crashpilot1000 wrote:Nope! The number after " * " is the checksum. You can calculate it here: http://www.hhhh.org/wiml/proj/nmeaxor.html


sorry but it gives me 3F as checksum in the link you posted, and in the GlobalTop PMTK command packet document http://www.adafruit.com/datasheets/PMTK_A08.pdf , page 14, the samples is

Code: Select all

$PMTK397,0.2*3F<CR><LF> (threshold to 0.2ms)?
$PMTK397,2.0*3F<CR><LF> (threshold to 2ms)?

so the 3F is always there

edit:
you are right, sorry

User avatar
Crashpilot1000
Posts: 631
Joined: Tue Apr 03, 2012 7:38 pm

Re: GPS integration

Post by Crashpilot1000 »

@EOS Bandi:
I took your code http://code.google.com/p/i2c-gps-nav/do ... p&can=2&q= and did my crazy changes to it. I want to post it "as it is" perhaps it is of some use perhaps an example of how not to do it...
The changes:
I put the multiwii serial part into your code, eliminating the arduino "Serial.begin" etc stuff. The inbuffer is set to 256 Bytes. The whole serial part is modular under the Tab "Serial". I implemented an experimental spikefilter wich i documented here (http://diydrones.com/forum/topics/perha ... pikefilter) it can be turned on/off in the config.h with #define SPIKEFILTER. It sits after the gps data aquisition and before your moving average filter. While playing around with your moving averagefilter i found it useful to be able to turn it off without recompiling the whole mwii code (since your filter is only recommended for 10Hz NMEA data). So i added "#define AFALWAYSOFF" in the config.h to turn off the averagefilter. Than i fiddled around to eliminate the sudden breakouts of the copter during PH etc. So far i couldn't test it because of the wheather. Here is what i did: In case of low sat count (default 5) the nav parameters are reset. In that case i set last_longitude and last_latitude to zero to force the velocity calculation to reset. I am not sure if it is done already. The next thing i did was to make the minimal sat number for gps functions accessible in the config.h "#define MINSAT 7" i set it to 7 because with 5 satellites i see errors in th 30+m range. So no breakouts due to wacky gps positions. I set this nmea parsing variable to unit_32 - i know that a positive effect is doubtful but it can not harm anyway...
Than i replaced the DIY Drones binary protocol parser with my own. Because i had it already done and wanted to put it to use:). I changed the initialization of MTK (binary mode) to the original apm sequence. I stumbled upon a crazy WAAS_ON sequence (http://diydrones.com/forum/topics/myste ... k-common-h). I let it in, perhaps it's some undocumented 3drobotics magic code. Currently i set the MTK to this:
Binary, 57K Baud, 5Hz, SBAS, WAAS, Navthreshold: OFF

The config.h looks like this now (example config for mtk in binary and experimental spikefilter):

Code: Select all

// *********************************** GENERAL GPS TYPE
//#define NMEA
//#define UBLOX
#define MTK                            // Defined: Binary, 57K Baud, 5Hz, SBAS, WAAS, Navthreshold: OFF

// *********************************** GENERAL FILTER VALUES
#define SPIKEFILTER                    // Turn on experimental spikefilter
#define AFALWAYSOFF                    // Always turn off the moving average filter("AF"), doesn't matter whats in mwii config.h defined

// *********************************** GENERAL GPS VALUES
#define MINSAT 7                       // 5 is default minimal number of sats for gps functions, i found valid data with 7 sats

// *********************************** MTK BINARY SPECIAL (FW:AXN1.51_2722_3329_384.1151100.5.bin)
//#define MTK10HZ                      // According to this post: http://www.multiwii.com/forum/viewtopic.php?f=6&t=1881&start=10#p19325
                                       // when enabeling 10HZ in mtk binary mode, you will loose SBAS functionality!! That will just work at 5Hz (default).


So long
Kraut Rob
Attachments
Test03.zip
(31.06 KiB) Downloaded 355 times

User avatar
EOSBandi
Posts: 802
Joined: Sun Jun 19, 2011 11:32 am
Location: Budapest, Hungary
Contact:

Re: GPS integration

Post by EOSBandi »

Crashpilot1000 wrote:@EOS Bandi:
I took your code http://code.google.com/p/i2c-gps-nav/do ... p&can=2&q= and did my crazy changes to it. I want to post it "as it is" perhaps it is of some use perhaps an example of how not to do it...
The changes:
I put the multiwii serial part into your code, eliminating the arduino "Serial.begin" etc stuff. The inbuffer is set to 256 Bytes. The whole serial part is modular under the Tab "Serial". I implemented an experimental spikefilter wich i documented here (http://diydrones.com/forum/topics/perha ... pikefilter) it can be turned on/off in the config.h with #define SPIKEFILTER. It sits after the gps data aquisition and before your moving average filter. While playing around with your moving averagefilter i found it useful to be able to turn it off without recompiling the whole mwii code (since your filter is only recommended for 10Hz NMEA data). So i added "#define AFALWAYSOFF" in the config.h to turn off the averagefilter. Than i fiddled around to eliminate the sudden breakouts of the copter during PH etc. So far i couldn't test it because of the wheather. Here is what i did: In case of low sat count (default 5) the nav parameters are reset. In that case i set last_longitude and last_latitude to zero to force the velocity calculation to reset. I am not sure if it is done already. The next thing i did was to make the minimal sat number for gps functions accessible in the config.h "#define MINSAT 7" i set it to 7 because with 5 satellites i see errors in th 30+m range. So no breakouts due to wacky gps positions. I set this nmea parsing variable to unit_32 - i know that a positive effect is doubtful but it can not harm anyway...
Than i replaced the DIY Drones binary protocol parser with my own. Because i had it already done and wanted to put it to use:). I changed the initialization of MTK (binary mode) to the original apm sequence. I stumbled upon a crazy WAAS_ON sequence (http://diydrones.com/forum/topics/myste ... k-common-h). I let it in, perhaps it's some undocumented 3drobotics magic code. Currently i set the MTK to this:
Binary, 57K Baud, 5Hz, SBAS, WAAS, Navthreshold: OFF

The config.h looks like this now (example config for mtk in binary and experimental spikefilter):

Code: Select all

// *********************************** GENERAL GPS TYPE
//#define NMEA
//#define UBLOX
#define MTK                            // Defined: Binary, 57K Baud, 5Hz, SBAS, WAAS, Navthreshold: OFF

// *********************************** GENERAL FILTER VALUES
#define SPIKEFILTER                    // Turn on experimental spikefilter
#define AFALWAYSOFF                    // Always turn off the moving average filter("AF"), doesn't matter whats in mwii config.h defined

// *********************************** GENERAL GPS VALUES
#define MINSAT 7                       // 5 is default minimal number of sats for gps functions, i found valid data with 7 sats

// *********************************** MTK BINARY SPECIAL (FW:AXN1.51_2722_3329_384.1151100.5.bin)
//#define MTK10HZ                      // According to this post: http://www.multiwii.com/forum/viewtopic.php?f=6&t=1881&start=10#p19325
                                       // when enabeling 10HZ in mtk binary mode, you will loose SBAS functionality!! That will just work at 5Hz (default).


So long
Kraut Rob


I did not reviewed it yet, but what I know that $PSRF sentences are for the SIRF chipset, so the "mystery" init sequence very likely some leftover from transferring code segments between gps implementations. MTK chipsets definitely will not understand that.

User avatar
Crashpilot1000
Posts: 631
Joined: Tue Apr 03, 2012 7:38 pm

Re: GPS integration

Post by Crashpilot1000 »

Ahh, thats why i couldn't find the command in the MTK reference. That might solve the PH issues with MTK and APM. I corrected the APM libs and posted them here http://diydrones.com/forum/topics/myste ... k-common-h.
Thanks a lot!

Cheers

Kraut
Rob

wilco1967
Posts: 156
Joined: Thu Aug 18, 2011 6:04 pm
Location: Winterswijk, Netherlands

Re: GPS integration

Post by wilco1967 »

EOSBandi wrote:
albertoLG wrote:Ok, tested it, 8/9 satellites, nothing has changed.... still don't update the data after 10/20 meters, in the car it works fine if moving... shelved it and waiting for the U-BLOX to arrive and do more tests


It seems that the nav threshold setting is active on your gps. Check it with $PMTK447*35<CR><LF> is must be 0.0
Regards,
EOS


I suspected this could possibly be my problem as well..... Also noticed the GPS update seems slugish when walking long time ago.... (can see with FrSky telemetry from MWii when walking around.... could also be it does not update when not armed :? )

So I connected my 3329 to realterm..... set it to 10 seconds of logging
then I send $PMTK447*35 with +CR and +LF ticked..... (is this correct) ?

Between all the data received, it seems I get a extra line $PMTK527,0.00*00 for each time I send the $PMTK447*35<CR><LF> string. This line never shows up if I dont send.....

Is this the 0.0 response I should be looking for?... So 0.0 means I should not have this problem ?
If I understand this correct http://forum.trenz-electronic.de/index.php?topic=44.0, I guess this is not my issue after all :cry:


My flyduino has a broken serial port... the Tx is not connected, only RX, so cannot use the INIT_MTK_GPS init script currently :( (still need to repair).

User avatar
Crashpilot1000
Posts: 631
Joined: Tue Apr 03, 2012 7:38 pm

Re: GPS integration

Post by Crashpilot1000 »

@wilco67: "..So 0.0 means I should not have this problem..." You are right, $PMTK527,0.00*00 is the expected answer. Your assumptions are correct.

Cheers
Kraut Rob

wilco1967
Posts: 156
Joined: Thu Aug 18, 2011 6:04 pm
Location: Winterswijk, Netherlands

Re: GPS integration

Post by wilco1967 »

Crashpilot1000 wrote:@wilco67: "..So 0.0 means I should not have this problem..." You are right, $PMTK527,0.00*00 is the expected answer. Your assumptions are correct.

Cheers
Kraut Rob


OK... thanks a lot for confirming.....


Now I still need to find out why my copter is drifting soo much in PH....... :roll:
for a moment I thought this would be the solution..... we'll find it sooner or later though 8-) ....

Thanks !

BTW: which firmware are you guys using (on NMEA that is....) ?
I'm using MTK3329_A1.5E_20110118_10Hz_115200.bin (which defaults to 115200 / 10 Hz)

copterrichie
Posts: 2261
Joined: Sat Feb 19, 2011 8:30 pm

Re: GPS integration

Post by copterrichie »

I was browsing YouTube and come upon this video. Seems someone has Waypoints working.

http://www.youtube.com/watch?v=WQ9t10BtYZI

User avatar
EOSBandi
Posts: 802
Joined: Sun Jun 19, 2011 11:32 am
Location: Budapest, Hungary
Contact:

Re: GPS integration

Post by EOSBandi »

Yeah, implementing waypoint nav is not a big deal. BUT before that, we need a solid MAG and BARO implementation. I'm working on the MAG right now since the current calibration is a joke, and I saw some interesting movements on the BARO part too. Adding new features without making simple functions solid is for the Ardu guys... :D

copterrichie
Posts: 2261
Joined: Sat Feb 19, 2011 8:30 pm

Re: GPS integration

Post by copterrichie »

Glad you are Back. :D

alexia
Posts: 85
Joined: Sun Jun 17, 2012 10:23 pm
Contact:

Re: GPS integration

Post by alexia »

EOSBandi wrote:Yeah, implementing waypoint nav is not a big deal. BUT before that, we need a solid MAG and BARO implementation. I'm working on the MAG right now since the current calibration is a joke, and I saw some interesting movements on the BARO part too. Adding new features without making simple functions solid is for the Ardu guys... :D



i am FULLY agree with you
we have an example with ardu code..so many features but too many bugs..so nothing interessing! we need to move step by step

scrat
Posts: 925
Joined: Mon Oct 15, 2012 9:47 am
Location: Slovenia

Re: GPS integration

Post by scrat »

EOSBandi wrote:Yeah, implementing waypoint nav is not a big deal. BUT before that, we need a solid MAG and BARO implementation. I'm working on the MAG right now since the current calibration is a joke, and I saw some interesting movements on the BARO part too. Adding new features without making simple functions solid is for the Ardu guys... :D


@EOSBandi: what do you mean with "current cal. is a joke"? How will we then calibrate MAG with your code? Do you mean it will be no dancing?

User avatar
EOSBandi
Posts: 802
Joined: Sun Jun 19, 2011 11:32 am
Location: Budapest, Hungary
Contact:

Re: GPS integration

Post by EOSBandi »

Mag calibration is a threefold process.
1. normalize the gain on each axis
2. adjust the zero offsets for each axis.
3. compensate hard and soft iron disturbances.

Visually when you plot the x,y,z values from the mag (rotated on each axis) without calibration you will got a nice potato :D After calibration this potato must become a perfect sphere.

In current code the gain normalization is faulty (wrong gain setting and not enough samples). The offset adjusting is more or less ok (this is the dance part). However it does not adjust the disturbances, so eventually you got an ellipsoid instead of a sphere.

I'm experimenting with the algorithm used in Fabio's FreeIMU_GUI program, which is a nice implementation of an ellipsoid to sphere transformation. I think we will need a separated program for calibration which will either write the data into eeprom or generate a .h file which could be included in the multiwii code.

So is will look like this :
1. load calibration program
2. do the dance, got visual feedback and you can decide that the calibration was successful or not.
3. Write a calibration.h file
4. load Multiwii
5. fly

User avatar
dramida
Posts: 473
Joined: Mon Feb 28, 2011 12:58 pm
Location: Bucharest
Contact:

Re: GPS integration

Post by dramida »

Hello Eos, a while ago someone called Mahowik achived to control the variation of altitude with a P-D loop.

Here is the result http://www.youtube.com/watch?v=7Sa-oyJ4Ljs

The code used is in this archive:

download/file.php?id=1663

User avatar
EOSBandi
Posts: 802
Joined: Sun Jun 19, 2011 11:32 am
Location: Budapest, Hungary
Contact:

Re: GPS integration

Post by EOSBandi »

dramida wrote:Hello Eos, a while ago someone called Mahowik achived to control the variation of altitude with a P-D loop.

Here is the result http://www.youtube.com/watch?v=7Sa-oyJ4Ljs

The code used is in this archive:

download/file.php?id=1663


On step at a time... I saw some very promising baro code lately in the repo....

User avatar
Crashpilot1000
Posts: 631
Joined: Tue Apr 03, 2012 7:38 pm

Re: GPS integration

Post by Crashpilot1000 »

@EOS Bandi: Improving the Mag is a terrific idea. Your approach seems to be a little bit too much action for the average user, but it is very reasonable. I am def. looking forward to this!
BTW: Did you risk an eye on my code? Is it pure crap or is there something of use? What is - from your experience - a safe delaytime between commands send to mtk without reading out it's returnmessage (@57KBaud). I am currently working with 1 sec...

Greetings
Kraut Rob

User avatar
EOSBandi
Posts: 802
Joined: Sun Jun 19, 2011 11:32 am
Location: Budapest, Hungary
Contact:

Re: GPS integration

Post by EOSBandi »

Crashpilot1000 wrote:@EOS Bandi: Improving the Mag is a terrific idea. Your approach seems to be a little bit too much action for the average user, but it is very reasonable. I am def. looking forward to this!
BTW: Did you risk an eye on my code? Is it pure crap or is there something of use? What is - from your experience - a safe delaytime between commands send to mtk without reading out it's returnmessage (@57KBaud). I am currently working with 1 sec...

Greetings
Kraut Rob


Perhaps it is too much, but this is the only way if we still want to use AtMega processors, the processing power is quite limited so sophisticated onboard algorithms are out of the question.


Regarding your code I took a quick look, not bad, I'll have to mix it with the ublox init which is quite sophisticated in the current multiwii_shared trunk. I would not wait more than 200ms between commands, that must be enough.

User avatar
Crashpilot1000
Posts: 631
Joined: Tue Apr 03, 2012 7:38 pm

Re: GPS integration

Post by Crashpilot1000 »

@EOS Bandi:
Hi!
Thank you very much for your reply!
I did another version. This time i improved the documentation in the maincode and config.h. Besides this i figured that a different minimum sat-count for different gps functions could be a good idea. PosHold is more a luxury feature so a higher satcount can be set. RTH is a more emergency function where a bigger error/lower satcount is OK. I made these variables accessible in the config.h

Code: Select all

#define MINSATPH 7                     // 5 is default minimal number of sats for gps PosHold, i found valid data with 7 sats. Since PH is luxury we want more sats..
#define MINSATRTH 5                    // 5 is default minimal number of sats for gps Return to Home since this is more an emergency function a 20m error doesn't matter

Concerning the MTK Binary mode i activated everything beneficial i could find. The most of it will be probably already on. The delay between commands is still set to 500 ms :) .....
The simple spikefilter seems to be very usable on 5Hz data.
Keep up your outstanding work !!!

Cheers

Kraut Rob
Attachments
Test04.zip
(31.67 KiB) Downloaded 332 times

User avatar
Crashpilot1000
Posts: 631
Joined: Tue Apr 03, 2012 7:38 pm

Re: GPS integration

Post by Crashpilot1000 »

Oops ! Something went wrong. Test03 is better than test04 i am not sure if it is the modified ini sequence for the mtk or the satcount thing.

User avatar
EOSBandi
Posts: 802
Joined: Sun Jun 19, 2011 11:32 am
Location: Budapest, Hungary
Contact:

Re: GPS integration

Post by EOSBandi »

I just committed some rework on the HMC5883L gain calibration (init). The code is based on Fabio's FreeIMU code and I think this is as good now as it could be on this platform. After some experimenting I decided to keep the current offset calibration method (MAG DANCE) since the ellipsoid to sphere method did not gave significantly better results, but added difficulty to the calibration process. I tested it but i would appriciate if somebody will took a look.

vpb
Posts: 231
Joined: Mon Jul 23, 2012 4:09 pm

Re: GPS integration

Post by vpb »

Hi EOSBandi, I see your new commit on latest r1284 dev. "No changes in the mag calibration dance, gain calibration is done automatically
at every startup". I want to test that new MAG calibration code, does the procedure change?

Thank you!

doppler
Posts: 64
Joined: Wed Sep 26, 2012 1:35 pm

Re: GPS integration

Post by doppler »

EOSBandi wrote:I just committed some rework on the HMC5883L gain calibration (init). The code is based on Fabio's FreeIMU code and I think this is as good now as it could be on this platform. After some experimenting I decided to keep the current offset calibration method (MAG DANCE) since the ellipsoid to sphere method did not gave significantly better results, but added difficulty to the calibration process. I tested it but i would appriciate if somebody will took a look.


Trying it now, seems fine, I didn't do any additional calibrations or anything, is there something special needed?


I do have a question about the magnometer it may be specific to the HMC5883L (I don't have any other ones). On a flat surface I have it indicating north when the IMU is pointing north, and when I spin the IMU around the indicator points correctly due to that spin. So far so good. But if I angle the board (pitch or roll), any amount, and hold the board in all other directions the compass starts to head elsewhere, this is best demonstrated when pointing the board East or West. I was playing with Headhold today (build 1240) and was watching my quad yaw every time i took it off being level to go in a direction, as you would expect from my description, the quad didn't go where it was supposed to. Left the quad level itself again (Angle mode on) and the quad returns to the direction I had it held too..... this seems to me to make mag hold, useless, I suspect headfree would be just as useless. Shouldn't there be some fancy math involving the ACC and/or GYRO's so that the X, Y, and Z are used to offset the changes the mag is experiencing?

I would expect this to completely break when doing flips, so I would only think it should work when MAG and ANGLE are used for instance.

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

Re: GPS integration

Post by crashlander »

Hello EOSBandi!
Nice to have you back.

Regarding baro code...
EOSBandi wrote:On step at a time... I saw some very promising baro code lately in the repo....

...that last published (and than removed but accessible as zip in forum) code from Mahovik actually works very good (and at least in my case stable) but I believe it is not included in official _shared. And since it includes variometric (constant speed) climb and descend based on TH stick offset from set-point it is probably very good start into GPS point to point navigation.

Best Regards
Andrej

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

Re: GPS integration

Post by fax8 »

I also saw the magnetometer calibration implemented by EOSBandi .. while that is surely better than before, you should really have a look at my new code for ellipsoid into sphere approximation.. check out the FreeIMU GUI: http://www.varesano.net/blog/fabio/free ... ersion-out
It's been discussed also here but people didn't seem much interested.. viewtopic.php?f=8&t=2175

Ideally, the FreeIMU GUI code has been written with the idea of supporting different serial protocols.. so far it only supports the FreeIMU library code, but adding support for the MultiWii shouldn't be difficult.

User avatar
EOSBandi
Posts: 802
Joined: Sun Jun 19, 2011 11:32 am
Location: Budapest, Hungary
Contact:

Re: GPS integration

Post by EOSBandi »

fax8 wrote:I also saw the magnetometer calibration implemented by EOSBandi .. while that is surely better than before, you should really have a look at my new code for ellipsoid into sphere approximation.. check out the FreeIMU GUI: http://www.varesano.net/blog/fabio/free ... ersion-out
It's been discussed also here but people didn't seem much interested.. viewtopic.php?f=8&t=2175

Ideally, the FreeIMU GUI code has been written with the idea of supporting different serial protocols.. so far it only supports the FreeIMU library code, but adding support for the MultiWii shouldn't be difficult.


Hi Fabio,
I spent quite a time and even implemented a calibration using calibration.h from FreeIMU GUI. At the end of the day, it seemed to me that the outcome was not significantly different from results of the current offset calibration method. I admit that the current method does not address soft iron distorsions, but the question is that do we really need soft iron calibration ? Or with the current precision of the other elements of MultiWii it is just fine...

BTW, my gain calibration code is vastly based on your code, so credits goes to you !

EOS

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

Re: GPS integration

Post by shikra »

Hi - very quick drop in as been tied up with new job...

FWIW, I think the current Mag calib is good enough for what we need - other bits need improving first really.

What I have noticed is that if the copter is moved correctly during calib it makes abig difference. Smooth mag readings as rotate, rather than fast in some directions and slow in others. Also less deviation when copter is tilted.

In hold/RTH, I've not really seen any issues due to mag deviation.

User avatar
Crashpilot1000
Posts: 631
Joined: Tue Apr 03, 2012 7:38 pm

Re: GPS integration

Post by Crashpilot1000 »

Help!

Sorry to interrupt here, but i am still struggeling with the MTK 3329 module the AXN1.51_2722_3329_384.1151100.5.bin and a valid DGPS fix. I connected the modul directly (via FTDI) to realterm (very good tip - thanks to EOS Bandi :) ) and let it put out NMEA strings (not turned to binary mode) at just 1Hz and observed the GGA strings. I got 10 Sats but never a DGPS fix. I threw every command at it that could possibly activate waas/sbas - nothing. Has anyone DGPS fix running on a binary capable Firmware?
Any help would be very appreciated!
Probably some simple methodical error?

Cheers

Kraut Rob

List of acknowledged commands but without success:

Code: Select all

  #define MTK_SBAS_INTEGRITYMODE"$PMTK319,1*24\r\n"    // TEST:ACK 
  #define MTK_NAVTHRES_OFF      "$PMTK397,0*23\r\n"    // TEST:ACK Threshold was 1.00m before (PMTK447 returns 0.0 NOW)
  #define MTK_SBAS_ON      "$PMTK313,1*2E\r\n"    // Enable search SBAS sat // TEST:ACK
  #define MTK_WAAS_ON           "$PMTK301,2*2E\r\n"    // DGPS MODE WAAS // TEST:ACK


List of commands described in the A11 revision of the MTK commandset but returned "ERROR UNSUPPORTED COMMAND"

Code: Select all

  #define MTK__DT_NAVTHRES_OFF  "$PMTK527,0.00*00\r\n" // Turn off Navthreshold // TEST: ERROR UNSUPPORTED COMMAND
  #define MTK__DT_NAVTHRES_OFF  "$PMTK527,0*2E\r\n" // Turn off Navthreshold // TEST: ERROR UNSUPPORTED COMMAND
  #define MTK_DT_SBAS_ENABLED   "$PMTK513,1*28\r\n"  // Enable Search for SBAS Sats // TEST: ERROR UNSUPPORTED COMMAND
  #define MTK_DT_DGPS_WAAS      "$PMTK501,2*28\r\n"  // DGPS data source mode: WAAS // TEST: ERROR UNSUPPORTED COMMAND

Post Reply