Integrating Remzibi OSD & ArduPilot 2.5.04

I spent the better part of the night working on a way to send GPS data and flight control information over to the Remzibi OSD and have finally found a near complete working solution that doesn't involve enabling NMEA. Of course I could have taken the easy way out of enabling NMEA messages but I wanted to have something that would work with ANY GPS module as long as ArduPilot could set the correct variables in the current_loc struct.

The only pieces left to complete are numSV doesn't seem to be set right with the Ublox GPS adapter so I can't report on the number of satellites and I need to figure out a UTC clock source for the UTC time and DATE field. Might have to enable those messages on the Ublox.

I've only done bench testing with this as I'm still building my UAV, so if anyone wants to help out please add this to your print.pde file:

void print_remzibi(void)
{
int nMult=0;
int nMeters=0; //Change this to 1 for meters, 0 for feet
long current_lat;
long current_lng;
float lat=0;
float lng=0;
int lat_dd=0;
float lat_ff=0;
int lng_dd=0;
float lng_ff=0;

char *lat_hemi;
char *lng_hemi;
char *lat_zero;
char *lng_zero;

if (nMeters==1)
nMult=1;
else
nMult=3.2808399;

digitalWrite(13,HIGH);

Serial.print("$GPGGA,");
Serial.print("064951.000");//UTC time
Serial.print(",");

if(current_loc.lat < 0)
{
current_lat = current_loc.lat * -1;
lat_hemi = "S";
lat_zero = "0";
}
else
{
current_lat = current_loc.lat;
lat_hemi = "N";
lat_zero = "";
}


lat_dd = (int) (current_lat/10000000);
lat_ff = (float)((current_lat - (lat_dd * 10000000)));
lat_ff = 60 * lat_ff;
lat_ff = (float)(lat_ff / 10000000);
lat = (float)(lat_dd * 100) + lat_ff;
Serial.print(lat_zero);
Serial.print(lat);
Serial.print(",");
Serial.print(lat_hemi);
Serial.print(",");

if(current_loc.lng < 0)
{
current_lng = current_loc.lng * -1;
lng_hemi = "W";
lng_zero = "0";
}
else
{
current_lng = current_loc.lng;
lng_hemi = "E";
lng_zero = "";
}

lng_dd = (int) (current_lng/10000000);
lng_ff = (float)((current_lng - (lng_dd * 10000000)));
lng_ff = 60 * lng_ff;
lng_ff = (float)(lng_ff / 10000000);
lng = (float)(lng_dd * 100) + lat_ff;
Serial.print(lng_zero);
Serial.print(lng);
Serial.print(",");
Serial.print(lng_hemi);
Serial.print(",");

Serial.print("1,");
Serial.print((int)numSV);//number of sats
Serial.print(",,");
Serial.print(current_loc.alt/1000);
Serial.println(",,");
delay(50);


Serial.print("$GPRMC,");
Serial.print("064951.000");//time
Serial.print(",,,,,,");
Serial.print(ground_speed/100,DEC);//ground_speed
Serial.print(",");
Serial.print(ground_course/100,DEC);//ground_course
Serial.print(",");
Serial.print("020410");//date
Serial.println(",,");
delay(50);

//$M message bus system for remzibi OSD
Serial.print("$M");
Serial.print("82"); // Hex Column (01h - 1Eh) for small fonts add 80h (81h - 9Eh)
Serial.print("09"); // Hex Row (01h - 0Dh for NTSC, 01h - 10h for PAL)
Serial.print("BA"); // Hex address of First Character
Serial.print("00"); // Hex address of Last Character

switch (control_mode){
case MANUAL:
Serial.print("MANUAL");
Serial.println(" ");
break;
case STABILIZE:
Serial.print("STABILIZE");
Serial.println(" ");
break;
case FLY_BY_WIRE:
Serial.print("FLY BY WIRE");
Serial.println(" ");
break;
case AUTO:
if (wp_index == 0)
{
Serial.print("HOME:"); //Min length = 7
Serial.print((int)(wp_distance*nMult));
Serial.println(" ");
}
else
{
Serial.print("WP"); //Min length = 6
Serial.print((int)wp_index);
Serial.print(":");
Serial.print((int)(wp_distance*nMult));
Serial.println(" ");
}
break;
case RTL:
Serial.print("RTL");
Serial.println(" ");
break;
case LOITER:
Serial.print("LOITER");
Serial.println(" ");
break;
}

digitalWrite(13,LOW);

}


Then in your main Ardupilot_25_04 file add the following below the if print_telemtry section:
if(REMZIBI)
{
print_remzibi();
}

Also you'll want to then set REMZIBI to 1 in your define.pde
E-mail me when people leave their comments –

You need to be a member of diydrones to add comments!

Join diydrones

Comments

  • Developer
    Any more updates, New MSG format in 2.7 b52 may help with speed.
  • When I last time wrote some code for the remzibi display, the Arduino environment had no serial output buffer. Not sure if it's still missing. Without buffer these serial prints eat most of the valuable processor time.
  • Yea I agree on the bogging it down. Still getting familiar with ardupilot! I will look at it this week.
  • Developer
    @Blake - great stuff! I plan to redo the output sections of ArduPilot 2.6 so that users can select an output type (e.g. ArduStation, Remzibi, other GCS, etc.) much like they select a gps type now. However I probably won't work on this till after 4/19.

    Could you take a look at the execution time of print_remzibi(). Possibly there is a need to break it into pieces so that their execution can be staggered over several main loop iterations so we don't bog the main loop down.
  • Change the time difference for local time to be the following, for some reason I copied pasted a version that didn't have the else statement:

    if(gps_time_hour < 5)
    {
    gps_time_day = gps_time_day - 1;
    int difference = 5 - gps_time_hour;
    gps_time_hour = 24 - difference;
    }
    else
    {
    gps_time_hour = gps_time_hour - 5;
    }
  • Ok, here is how I managed to get the date to show up. Need to modify a couple of files. First the GPS_UBLOX add this to the switch statement for join_data:

    case 0x21: // ID NAV-TIMEUTC
    gps_time_month = join_1_bytes(&UBX_buffer[14]);
    gps_time_day = join_1_bytes(&UBX_buffer[15]);
    gps_time_year = join_2_bytes(&UBX_buffer[12]);
    gps_time_hour = join_1_bytes(&UBX_buffer[16]);
    gps_time_minute = join_1_bytes(&UBX_buffer[17]);
    gps_time_second = join_1_bytes(&UBX_buffer[18]);

    //timezone stuff to make it local time
    //CDT is -5 from UTC
    //CST is -6 from UTC
    if(gps_time_hour < 5)
    {
    gps_time_day = gps_time_day - 1;
    int difference = 5 - gps_time_hour;
    gps_time_hour = 24 - difference;
    }

    break;

    Next add the following as well to the GPS_UBLOX:
    // Join 2 bytes into a long
    int32_t join_2_bytes(byte Buffer[])
    {
    longUnion.byte[0] = *Buffer;
    longUnion.byte[1] = *(Buffer+1);
    return(longUnion.dword);
    }

    // Join 1 byte into an int
    int32_t join_1_bytes(byte Buffer[])
    {
    intUnion.byte[0] = *Buffer;
    return(intUnion.word);
    }

    Here is the new print_remzibi:

    void print_remzibi(void)
    {
    int nMult=0;
    int nMeters=0; //Change this to 1 for meters, 0 for feet
    long current_lat;
    long current_lng;
    float lat=0;
    float lng=0;
    int lat_dd=0;
    float lat_ff=0;
    int lng_dd=0;
    float lng_ff=0;

    char *lat_hemi;
    char *lng_hemi;
    char *lat_zero;
    char *lng_zero;

    if (nMeters==1)
    nMult=1;
    else
    nMult=3.2808399;

    digitalWrite(13,HIGH);
    //$GPGGA,,,,,,,,,,,,,,
    Serial.print("$GPGGA,");
    if(gps_time_hour < 10)
    {
    Serial.print("0");
    }
    Serial.print(gps_time_hour);
    if(gps_time_minute < 10)
    {
    Serial.print("0");
    }
    Serial.print(gps_time_minute);
    if(gps_time_second < 10)
    {
    Serial.print("0");
    }
    Serial.print(gps_time_second);
    Serial.print(".000");
    Serial.print(",");

    if(current_loc.lat < 0)
    {
    current_lat = current_loc.lat * -1;
    lat_hemi = "S";
    lat_zero = "0";
    }
    else
    {
    current_lat = current_loc.lat;
    lat_hemi = "N";
    lat_zero = "";
    }


    lat_dd = (int) (current_lat/10000000);
    lat_ff = (float)((current_lat - (lat_dd * 10000000)));
    lat_ff = 60 * lat_ff;
    lat_ff = (float)(lat_ff / 10000000);
    lat = (float)(lat_dd * 100) + lat_ff;
    Serial.print(lat_zero);
    Serial.print(lat);
    Serial.print(",");
    Serial.print(lat_hemi);
    Serial.print(",");

    if(current_loc.lng < 0)
    {
    current_lng = current_loc.lng * -1;
    lng_hemi = "W";
    lng_zero = "0";
    }
    else
    {
    current_lng = current_loc.lng;
    lng_hemi = "E";
    lng_zero = "";
    }

    lng_dd = (int) (current_lng/10000000);
    lng_ff = (float)((current_lng - (lng_dd * 10000000)));
    lng_ff = 60 * lng_ff;
    lng_ff = (float)(lng_ff / 10000000);
    lng = (float)(lng_dd * 100) + lat_ff;
    Serial.print(lng_zero);
    Serial.print(lng);
    Serial.print(",");
    Serial.print(lng_hemi);
    Serial.print(",");

    Serial.print("1,");
    Serial.print(numSV,BYTE);//number of sats
    Serial.print(",,");
    Serial.print(current_loc.alt/1000);
    Serial.println(",,");
    delay(50);

    //$GPRMC,,,,,,,,,
    Serial.print("$GPRMC,");
    if(gps_time_hour < 10)
    {
    Serial.print("0");
    }
    Serial.print(gps_time_hour);
    if(gps_time_minute < 10)
    {
    Serial.print("0");
    }
    Serial.print(gps_time_minute);
    if(gps_time_second < 10)
    {
    Serial.print("0");
    }
    Serial.print(gps_time_second);
    Serial.print(".000");
    Serial.print(",,,,,,");
    Serial.print(ground_speed/100,DEC);//ground_speed
    Serial.print(",");
    Serial.print(ground_course/100,DEC);//ground_course
    Serial.print(",");
    if(gps_time_day < 10)
    {
    Serial.print("0");
    }
    Serial.print(gps_time_day);
    if(gps_time_month < 10)
    {
    Serial.print("0");
    }
    Serial.print(gps_time_month);

    Serial.print(gps_time_year - 2000);
    // Serial.print("020410");//date
    Serial.println(",,");
    delay(50);

    //$M message bus system for remzibi OSD
    Serial.print("$M");
    Serial.print("82"); // Hex Column (01h - 1Eh) for small fonts add 80h (81h - 9Eh)
    Serial.print("09"); // Hex Row (01h - 0Dh for NTSC, 01h - 10h for PAL)
    Serial.print("BA"); // Hex address of First Character
    Serial.print("00"); // Hex address of Last Character

    switch (control_mode){
    case MANUAL:
    Serial.print("MANUAL");
    Serial.println(" ");
    break;
    case STABILIZE:
    Serial.print("STABILIZE");
    Serial.println(" ");
    break;
    case FLY_BY_WIRE:
    Serial.print("FLY BY WIRE");
    Serial.println(" ");
    break;
    case AUTO:
    if (wp_index == 0)
    {
    Serial.print("HOME:"); //Min length = 7
    Serial.print((int)(wp_distance*nMult));
    Serial.println(" ");
    }
    else
    {
    Serial.print("WP"); //Min length = 6
    Serial.print((int)wp_index);
    Serial.print(":");
    Serial.print((int)(wp_distance*nMult));
    Serial.println(" ");
    }
    break;
    case RTL:
    Serial.print("RTL");
    Serial.println(" ");
    break;
    case LOITER:
    Serial.print("LOITER");
    Serial.println(" ");
    break;
    }

    digitalWrite(13,LOW);

    }

    Finally, enable TIMEUTC on your uBlox module. I still can't seem to get numSV to display anything with SOL enabled.
  • Developer
    Hi Blake,
    The uBox needs to output NAV-SOL instead of NAV-STATUS to get the number of satellites. uBlox are shippong from Jordi now with Nav-SOL enabled over Nav-STATUS. You can change that with uCenter, I think.
    Nice work.
    Jason
  • Developer
    Thanks for sharing your code, I will give it a try
  • well done Blake, thanks for sharing your hard work.
  • Admin
    well done Blake, thanks for sharing your hard work.
This reply was deleted.