Crius GPS and I2C_GPS_NAV
Posted: Tue Jul 24, 2012 11:06 am
I begin this thread because subject is discussed often in GPS integration thread here: viewtopic.php?f=8&t=649 and it seems that many people doesn't read so long threads and ask again and again about the same things.
Situation overview: Crius GPS board utilises u/blox NEO-6M module without non-volatile storage for configuration. Therefore, configuration are lost very often. Another issue with default hardware configuration is, that module after power-on does not send navigation data, has to be switched off and on again. My observation is, that hardware configuration with grounded pin 14 is free of described issue. Secondary plus is, that default COM speed in this configuration is 38400 Bd, what is good enough for that binary data volume.
So, my solution consist of these steps:
1. Hardware modification of Crius GPS board - easy task, just short pins 13 and 14 on GPS module by small drop of solder. Thanks for image to Krystal:
2. Software modification of EOSBandi's I2C_GPS_NAV.ino (ver. 2.1), put this code just after "void setup() {"
This code send all initialization commands to GPS, there is no more necessary to configure GPS board manualy in case of config data lost.
3. don't forget edit config.h of I2C_GPS_NAV and set #define UBLOX and #define GPS_SERIAL_SPEED 38400, upload it to I2C_GPS_NAV board.
That's all, I hope that my poor english is clear enough Any feedback will be appreciated.
Situation overview: Crius GPS board utilises u/blox NEO-6M module without non-volatile storage for configuration. Therefore, configuration are lost very often. Another issue with default hardware configuration is, that module after power-on does not send navigation data, has to be switched off and on again. My observation is, that hardware configuration with grounded pin 14 is free of described issue. Secondary plus is, that default COM speed in this configuration is 38400 Bd, what is good enough for that binary data volume.
So, my solution consist of these steps:
1. Hardware modification of Crius GPS board - easy task, just short pins 13 and 14 on GPS module by small drop of solder. Thanks for image to Krystal:
2. Software modification of EOSBandi's I2C_GPS_NAV.ino (ver. 2.1), put this code just after "void setup() {"
Code: Select all
delay(3000); //lets some time to GPS module to init
Serial.begin(38400);
delay(1000);
PROGMEM prog_uchar conf2[]={0xB5, 0x62, 0x06, 0x08, 0x06, 0x00, 0xC8, 0x00, 0x01, 0x00, 0x01, 0x00, 0xDE, 0x6A}; //set rate to 5Hz
Serial.write (conf2,sizeof(conf2));
delay(300);
PROGMEM prog_uchar conf3[]={0xB5, 0x62, 0x06, 0x03, 0x1C, 0x00, 0x02, 0x03, 0x10, 0x18, 0x14, 0x05, 0x00, 0x3C, 0x3C, 0x14, 0xE8, 0x03, 0x00, 0x00, 0x00, 0x17, 0xFA, 0x00, 0xFA, 0x00, 0x64, 0x00, 0x2C, 0x01, 0x0F, 0x00, 0x00, 0x00, 0x8D, 0xE4};
Serial.write (conf3,sizeof(conf3));
delay(300);
PROGMEM prog_uchar conf4[]={0xB5, 0x62, 0x06, 0x1A, 0x28, 0x00, 0x02, 0x00, 0x00, 0x00, 0x03, 0x04, 0x10, 0x02, 0x50, 0xC3, 0x00, 0x00, 0x18, 0x14, 0x05, 0x3C, 0x00, 0x03, 0x00, 0x00, 0xFA, 0x00, 0xFA, 0x00, 0x64, 0x00, 0x2C, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x6B, 0x6D};
Serial.write (conf4,sizeof(conf4));
delay(300);
PROGMEM prog_uchar conf5[]={0xB5, 0x62, 0x06, 0x24, 0x24, 0x00, 0xFF, 0xFF, 0x03, 0x03, 0x00, 0x00, 0x00, 0x00, 0x10, 0x27, 0x00, 0x00, 0x05, 0x00, 0xFA, 0x00, 0xFA, 0x00, 0x64, 0x00, 0x2C, 0x01, 0x00, 0x3C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x4F, 0x82};
Serial.write (conf5,sizeof(conf5)); //set GPS dynamic platform to "pedestrian" seems to be best for copter
delay(300);
PROGMEM prog_uchar conf6[]={0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x05, 0x00, 0xFF, 0x19};
Serial.write (conf6,sizeof(conf6));
delay(300);
PROGMEM prog_uchar conf8[]={0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x03, 0x00, 0xFD, 0x15};
Serial.write (conf8,sizeof(conf8));
delay(300);
PROGMEM prog_uchar conf9[]={0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x01, 0x00, 0xFB, 0x11};
Serial.write (conf9,sizeof(conf9));
delay(300);
PROGMEM prog_uchar conf10[]={0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x00, 0x00, 0xFA, 0x0F};
Serial.write (conf10,sizeof(conf10));
delay(100);
PROGMEM prog_uchar conf13[]={0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x02, 0x00, 0xFC, 0x13};
Serial.write (conf13,sizeof(conf13));
delay(100);
PROGMEM prog_uchar conf14[]={0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x04, 0x00, 0xFE, 0x17}; //disable all default NMEA messages, shorter code that disable all
Serial.write (conf14,sizeof(conf14));
delay(100);
PROGMEM prog_uchar conf15[]={0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0x01, 0x02, 0x01, 0x0E, 0x47};
Serial.write (conf15,sizeof(conf15));
delay(100);
PROGMEM prog_uchar conf17[]={0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0x01, 0x03, 0x01, 0x0F, 0x49};
Serial.write (conf17,sizeof(conf17));
delay(100);
PROGMEM prog_uchar conf18[]={0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0x01, 0x06, 0x01, 0x12, 0x4F};
Serial.write (conf18,sizeof(conf18));
delay(100);
PROGMEM prog_uchar conf19[]={0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0x01, 0x12, 0x01, 0x1E, 0x67}; //enable UBX messages POSLLH, SOL, STATUS and VELNED as is in EOSBandi's config file
Serial.write (conf19,sizeof(conf19));
delay(100);
PROGMEM prog_uchar conf7[23]={0xB5, 0x62, 0x06, 0x09, 0x0D, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFF, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x17, 0x31, 0xBF}; //write config to module
Serial.write (conf7,sizeof(conf7));
This code send all initialization commands to GPS, there is no more necessary to configure GPS board manualy in case of config data lost.
3. don't forget edit config.h of I2C_GPS_NAV and set #define UBLOX and #define GPS_SERIAL_SPEED 38400, upload it to I2C_GPS_NAV board.
That's all, I hope that my poor english is clear enough Any feedback will be appreciated.