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
flyrobot
Posts: 73
Joined: Thu Apr 05, 2012 3:59 pm

Re: GPS integration

Post by flyrobot »

Hi Andras,

Im very glad to see you. The last try with last fw mwi im happy with the stability espesially altitude hold and loiter. Is it the right time for way point?

Thanks,

John

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

Re: GPS integration

Post by Crashpilot1000 »

@EOSBandi:

I used Arduino 1.0.1. I had sudden twitches out of nowhere so i found the uint_32 error here: http://code.google.com/p/arducopter/iss ... 0&sort=-id
From my understaning it isn't fixed in our current code. Just changing unsigned int frac_min = 0; to uint32_t frac_min = 0; helped a lot. But i did my own moving average "for idiots" using 64Bit and some new problems occured i couldn't explain from my simple code. The cure for this was the solution above. I am no programmer but i think there is a bug in current NMEA readout.

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:@EOSBandi:

I used Arduino 1.0.1. I had sudden twitches out of nowhere so i found the uint_32 error here: http://code.google.com/p/arducopter/iss ... 0&sort=-id
From my understaning it isn't fixed in our current code. Just changing unsigned int frac_min = 0; to uint32_t frac_min = 0; helped a lot. But i did my own moving average "for idiots" using 64Bit and some new problems occured i couldn't explain from my simple code. The cure for this was the solution above. I am no programmer but i think there is a bug in current NMEA readout.

So long
Kraut Rob


Well, there is one significant difference compared to the AP code. in MultiWii we parse only four digits for the fraction minutes (Since to almost all gps modules returns only four digits of fractional minutes in a format DDMM.MMMM. AP code assumes five digits after the decimal point.

Here is the code from AP

Code: Select all

// convert fractional minutes
// expect up to four digits, result is in
// ten-thousandths of a minute   
 if (*p == '.') {
         q = p + 1;
         for (int16_t i = 0; i < 5; i++) {
             frac_min = (int32_t)(frac_min * 10);
             if (isdigit(*q))
                 frac_min += *q++ - '0';
         }     
}     
ret = (int32_t)deg * (int32_t)1000000UL + (int32_t)((min * 100000UL + frac_min) / 6UL);     
return ret;
 


And this is the code in MultiWii

Code: Select all

  // convert fractional minutes
  // expect up to four digits, result is in
  // ten-thousandths of a minute
  if (*p == '.') {
    q = p + 1;
    for (i = 0; i < 4; i++) {
      frac_min *= 10;
      if (isdigit(*q))
        frac_min += *q++ - '0';
    }
  }
  return deg * 10000000UL + (min * 1000000UL + frac_min*100UL) / 6;


In MultiWii it is not possible to get a larger value in frac_min than 9999 which fits into an unsigned int (uint_16t).
In AP you can easily get a value larger than 65536. So frac_min have to be uint_32t.

So I still does not see a problem here with MultiWii code :(

Btw, could you share the coordinates where you experienced these glitches ?

EOSBandi

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

Re: GPS integration

Post by Crashpilot1000 »

Thank you very much for looking into this!!!
I send you the GPS coordinates via PN....

So long

Kraut Rob

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

Re: GPS integration

Post by Vaattari »

EOSBandi wrote:
Vaattari wrote:Hello,

Can someone please explain why GPS filtering is not needed in binary mode? I logged today the GPS data with WinGUI and there is few big errors coming in from the I2C GPS. The position jumps suddendly like 30+ meters and comes back with the next measurement. These are not filtered by the FC if filtering is disabled or is there a constrain somewhere to handle such jumps? If there is one, can it be tuned to give less room for big changes?

I'm pretty happy with the current GPS in position hold but it is not yet rock solid ;)
http://www.youtube.com/watch?v=TOPzr8Kbhyk

Thanks in advance,
Janne


30 meter jumps are unnacceptable, you either does not have enough sats in view or some other malfunctions are happening. You can mask these errors with filtering up to a certain extent, but it will not solve it.

Filtering is supposed to eliminate the relatively low position resolution of the NMEA protocol. With binary (either ublox or mtk) this kind of filtering is not required.
BTW, last time i checked the MTK binary protocol was acceptable only at 5Hz, and the same is true for ublox too.

EOS


Thanks EOSBandi for your reply. 5Hz change done :)

Even after change the update rate from 10Hz to 5Hz the static coordinate measurements were still going all over the place. Just to see the difference I then enabled the GPS filter in Config.h. It seems to do a lot.
We have -20C outside at the moment so I did not test fly. :|
These measurements were taken after 10 minutes of power on and duration is 15 minutes each. Is there any other issue than a delay in correction if wind push the copter away?

Thanks,
janne
Attachments
GPS filter enabled.
GPS filter enabled.
Without GPS filter:
Without GPS filter:

User avatar
NikTheGreek
Posts: 348
Joined: Thu Dec 08, 2011 4:17 pm
Location: Greece
Contact:

Re: GPS integration

Post by NikTheGreek »

@Vaattari

Which version of MW GUI you are using ?
Where i can find ?

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

Re: GPS integration

Post by Vaattari »

NikTheGreek wrote:@Vaattari

Which version of MW GUI you are using ?
Where i can find ?


Thanks to EOSBandi for this as well!
You can find the gui here: http://code.google.com/p/mw-wingui/downloads/list

Latest dev did not like WinGUI in my laptop. I can not get it working more than few minutes before the gui GPS side halts. With MW2.1 no probs ;)

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

Re: GPS integration

Post by Crashpilot1000 »

Thanks EOSBandi for your reply. 5Hz change done :)

Even after change the update rate from 10Hz to 5Hz the static coordinate measurements were still going all over the place. Just to see the difference I then enabled the GPS filter in Config.h. It seems to do a lot.
We have -20C outside at the moment so I did not test fly. :|
These measurements were taken after 10 minutes of power on and duration is 15 minutes each. Is there any other issue than a delay in correction if wind push the copter away?

Thanks,
janne


BTW the Filter is only active in Pos.Hold mode.
From what i figured out the main problem seems to be the solid dataaquisition. I played around with different modes(NMEA/Binary) and baud rates(115K,57K) and refresh rates(5,10HZ) on my MTK. At the end of the day i think doing 115k on the serial produces drop outs or some weird dataproblems. Maybe it is a Buffer thing or the Serial.read() is somehow wacky at that speed. I got good results with the mtk binary protocol (the firmware recommended by eos bandi: AXN1.51_2722_3329_384.1151100.5.bin - on his d/l page) at 57K serial speed and 10Hz update rate. It seems strange but that worked best. Perhaps the serial readout of the original mwii code is more reliable than the on used in the I2C solution? I don't know. With the nice infos from this post viewtopic.php?f=8&t=649&start=40#p4085 the codechange was very easy. If somebody else wants to try it:

Original:

Code: Select all

....
#if defined(MTK)
/* Using the AXN 1.51 firmware which defaults at 1Hz/38400 but supports binary protocol
 * First connect to it with 38400, then set the speed to 115200
 * and set the update rate to 10Hz
 * and finally switch to Binary mode
 */

Serial.begin(38400);
delay(1500); //let it init
Serial.write("$PMTK251,115200*1F\r\n");
delay(300);
Serial.end();

Serial.begin(115200);
Serial.write("$PGCMD,16,0,0,0,0,0*6A\r\n");
delay(1000);
Serial.write("$PGCMD,16,0,0,0,0,0*6A\r\n");
delay(300);
Serial.write("$PMTK220,100*2F\r\n");
#else
  //open serial port at 115200
  Serial.begin(GPS_SERIAL_SPEED);
#endif
....


To:

Code: Select all

....
#if defined(MTK)
/* Using the AXN 1.51 firmware which defaults at 1Hz/38400 but supports binary protocol
 * First connect to it with 38400, then set the speed to 57600
 * and set the update rate to 10Hz
 * and finally switch to Binary mode
 */

Serial.begin(38400);                          // Handshake
delay(1500); //let it init
Serial.write("$PMTK251,57600*2C\r\n");     // Go down to 57K for data integrity
delay(1000);
Serial.end();
delay(500);
Serial.begin(57600);
Serial.write("$PGCMD,16,0,0,0,0,0*6A\r\n");
delay(1000);
Serial.write("$PGCMD,16,0,0,0,0,0*6A\r\n");
delay(300);
Serial.write("$PMTK220,100*2F\r\n");
#else
  //open serial port at 115200
  Serial.begin(GPS_SERIAL_SPEED);
#endif
....


Anyway while browsing the code i found another question i would like to ask.
There is a part in the code "we does not have 3d fix or numsats less than 5 , stop navigation" (line 1356) than this is executed:

Code: Select all

{      // we does not have 3d fix or numsats less than 5 , stop navigation
                 nav_lat = 0;
                 nav_lon = 0;
                 GPSMode = GPSMODE_NONAV;
                 nav_mode = NAV_MODE_NONE;
                 wp_distance = 0;
                 i2c_dataset.distance_to_home = 0;
                 i2c_dataset.home_to_copter_bearing = 0;
                 GPS_update_i2c_dataset();
               }


Wouldn't it make sense to reset the "static void GPS_calc_velocity" variables "last_longitude" and "last_latitude" also like this:

Code: Select all

{      // we does not have 3d fix or numsats less than 5 , stop navigation
                 last_longitude = 0;               //Crashpilot Reset Velocity LON
                 last_latitude  = 0;               //Crashpilot Reset Velocity LAT
                 nav_lat = 0;
                 nav_lon = 0;
                 GPSMode = GPSMODE_NONAV;
                 nav_mode = NAV_MODE_NONE;
                 wp_distance = 0;
                 i2c_dataset.distance_to_home = 0;
                 i2c_dataset.home_to_copter_bearing = 0;
                 GPS_update_i2c_dataset();
               }


Just another 2 cents, i hope i don't bother everyone here..

So long
Kraut Rob

User avatar
mbrak
Posts: 136
Joined: Sat Dec 03, 2011 8:08 pm
Location: Germany, Lemgo

Re: GPS integration

Post by mbrak »

hi robert

would this file AXN1.51_2722_3329_384.1151100.5.bin also work with the flyduino gps (FMP04) ?

thx kraut michael :)

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

Re: GPS integration

Post by Crashpilot1000 »

Hi mbrak!
I wouldn't flash until you have a save fallback. From what i can read in the shop description they don't publish the current flashed FW. BTW perhaps the FW is compatible to the binary protocol, ask flyduino. In that case you could use #define MTK and alter the main code:

Code: Select all

....
#if defined(MTK)
/* Using the AXN 1.51 firmware which defaults at 1Hz/38400 but supports binary protocol
* First connect to it with 38400, then set the speed to 115200
* and set the update rate to 10Hz
* and finally switch to Binary mode
*/

Serial.begin(38400);

to

Code: Select all

....
#if defined(MTK)
/* Using the AXN 1.51 firmware which defaults at 1Hz/38400 but supports binary protocol
* First connect to it with 38400, then set the speed to 115200
* and set the update rate to 10Hz
* and finally switch to Binary mode
*/

Serial.begin(115200);
...


I would ask flyduino what the "WAAS" enabled FW can do for you in europe since we have SBAS sattelites....

Grüsse

Rob

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 356 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.

Post Reply