INS Support for MTK3339 Chipset

Hi All,

Just wondering if there is support for the MTK3339 chipset (used in the inexpensive Adafruit GPS module) for the INS app? Ideally I'd like to use the pre-built app to produce LatLon INS-aided data.

Thanks in advance

I think you have to write your own GPS receiver driver in our open-source framework. But if you choose NMEA as the receiver output, which is not recommended since NMEA lacks some required info, you can use the INS app.

I currently have the receiver outputting GGA, GSA, RMC and VTG NMEA messages, and on the websocket live viewer, the latitude and longitude are still reporting as 0. Is there any way I can confirm that the INS app is accepting or rejecting the NMEA messages?

Thanks

Do you directly download the firmware bin or source code? If the source code, you can change the GPS protocal in UserConfiguration.c. The following picture shows the one I am using for development.

const UserConfigurationStruct gDefaultUserConfig = {
    .dataCRC             =  0,
    .dataSize            =  sizeof(UserConfigurationStruct),
    .userUartBaudRate    =  230400,
    .userPacketType      =  "e2",
    .userPacketRate      =  100,
    .lpfAccelFilterFreq  =  25,
    .lpfRateFilterFreq   =  25,
    .orientation         =  "-Y+X+Z",   // the EVB connector pointing forward
    .gpsBaudRate         =  115200,
    .gpsProtocol         =  UBLOX_BINARY,
    // add default parameter values here, if desired
    .hardIron_X          = 0.0,
    .hardIron_Y          = 0.0,
    .softIron_Ratio      = 1.0,
    .softIron_Angle      = 0.0
};

If the bin file, I need to ask for firmware engineers' help to see if there is commands to change the settings online.

I used the bin file through the web interface. If you can send me a link to the source code please that would be great, as I can't seem to find it. I can then read through the source and work out what commands I need to send.

Thanks for your help

Apologies, I have the source code now for the INS app (through installation of the Aceinna Studio).

I have set the device to be NMEA_TEXT at 9600 baud. The GPS has a fix and is outputting the data, yet upon use of the Navigation Studio python driver with websocket, there is no latitude or longitude being reported (they stay as 0, 0). The INS page of the website also doesn't show any data.

Have I missed something?
Thanks

  1. Please first confirm the GPS receiver is correctly connected to the EVK.
    GPS receiver connection.jpg .

  2. In TaskGps() in TaskGps.c, please track if it can run into GPSHandler()-->_handleGpsMessages(), and the data is decoded as desired, which is NMEA in you case.

switch(GPSData->GPSProtocol){
            case NMEA_TEXT: 
                parseNMEAMessage(tmp, gpsMsg, GPSData);
                break; 
            case NOVATEL_BINARY:
                parseNovotelBinaryMessage(tmp, gpsMsg, GPSData);
                break;
            case UBLOX_BINARY:
                parseUbloBinaryMessage(tmp, gpsMsg, GPSData);
                break;
            default:
                break;
                }
        }
  1. Please notice, NMEA is not recommended because it lacks some required info.

Thank you for the help. Your wiring suggestions fixed the issue. I had connected the GPS receiver according to the data on the "readthedocs" documentation which suggests connection to the expansion port P4. Upon connecting to P2, the system works and is reporting latlon data.

Thanks for your help.

You are welcome.

Dear Xiaoguang,

I connected U-Blox F9P module to OpenIMS300 (INS App) by following the wiring instruction in the document and above dated 5/15/2019. But the latitude and longitude are "0" (Note: I connected the F9P module to PC and used the U-center software provided by U-Blox, the latitude and longitude are not 0). What's is wrong?

Thank you for your help.

what kind of message does F9P output?For ublox receivers, we support NMEA and binary nav-pvt. For the same time, you can only choose one of the two. For me, I use nav-pvt most of the time.

Here is a quick start of the INS app on our online doc;
https://openimu.readthedocs.io/en/latest/apps/ins.html

@Dong-xiaoguang

I used the most recent INS app (1.1.1) with Firmware version 1.1.2 and follow the online doc, for example, (1) wiring; (2) Remove jumper between pins 5 and 6 in the header P1. But the latitude/longitude values are still "0". See the screenshot posted in the following link:

https://sites.google.com/site/johnrhxie2018/itrain2019/rd2/x19121301.png?attredirects=0&d=1

Any suggestion?

Thank you.

First, please check your receiver output baud rate and protocol. The protocol should match that in UserConfiguration.c.
Further, you may print log in EKF_SetInputStruct() in EKF_Algorithm.c to see if GPS measurement is fed into the algorithm. If not, you need check the GPS driver in taskGPS.c.

@Dong-xiaoguang
Dear Xiaoguang,

Baud rate us 115200 and protocol is UBLOX_BINARY, which match those defined in UserConfiguration.c. I will follow your suggestions to print the log in EKF_SetinpuStruct().

Thank you.

@John-Xie , please notice UBLOX_BINARY indeed means uBlox binary nav-pvt.

Log in to reply