Blake Krone's Posts (2)

Sort by

Remzibi OSD + APM Integration

I finally got my mods to a point where I'm comfortable with others testing. I've only been using it with XPlane seen as it is so dang cold and snowy outside. You need to define OSD_PORT and OSD_MODE_CHANNEL. OSD_MODE_CHANNEL will allow you to assign a toggle switch to turn on and off the OSD overlay while in the air.

 

Some of the features included:

  • Auto-home saving from init_home()
  • Distance and direction to home
  • Artificial horizon
  • GPS LAT & LONG
  • Control mode and next waypoint + distance (working on relaying takeoff, land, etc messages)
  • Overlay on/off via Tx switch

Here are the Remzibi Mods:
+----------------+
|  APM_Config.h  |
+----------------+
#define OSD_PROTOCOL        OSD_PROTOCOL_REMZIBI
#define OSD_PORT            3
#define OSD_MODE_CHANNEL    7

+---------------------+
|  ArduPilotMega.pde  |
+---------------------+
Medium loop, case 3:
#if OSD_PROTOCOL != OSD_PROTOCOL_NONE
        print_osd_ahrs();
#endif

Slow loop, case 1:
// Output OSD Data slow loop
#if OSD_PROTOCOL != OSD_PROTOCOL_NONE
        print_osd_data();                       
#endif

// Read OSD Mode Switch
#if OSD_PROTOCOL == OSD_PROTOCOL_REMZIBI
        read_osd_switch();
#endif

+---------------+
|   defines.h   |
+---------------+
After GPS type defines:
// OSD type codes
#define OSD_PROTOCOL_NONE       -1
#define OSD_PROTOCOL_REMZIBI     0

+----------------+
|  commands.pde  |
+----------------+
After line 251, bottom of init_home():
// Save Home to OSD
// ----------------
#if OSD_PROTOCOL == OSD_PROTOCOL_REMZIBI       
        osd_init_home();
#endif

 

And finally add the following file into your APM folder:

OSD_Remzibi.pde <-Version 1

OSD_Remzibi.pde <-Version 2

 

And for my Remzibi layout:

APM.bin

Read more…

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
Read more…