Skip to content

Commit

Permalink
Fixed ground OSD mode for Betflight
Browse files Browse the repository at this point in the history
  • Loading branch information
tipoman9 committed Nov 10, 2024
1 parent 8e32165 commit fa68683
Show file tree
Hide file tree
Showing 9 changed files with 121 additions and 71 deletions.
49 changes: 48 additions & 1 deletion .vscode/launch.json
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,6 @@
"--baudrate",
"115200",
"--osd",

"-c",
"7",
"-c",
Expand Down Expand Up @@ -46,6 +45,54 @@
],
"preLaunchTask": "copy msposd"

},
{
//--on CAM read serial and forward via mavlink port
// msposd --channels 7 --master /dev/ttyS2 --baudrate 115200 --out 127.0.0.1:14550 --matrix 11 --ahi 3 -r 50

"name": "UART_FWD",
"type": "cppdbg",
"request": "launch",
"program": "${workspaceFolder}/msposd",
"args": [
"--master",
"/dev/ttyUSB0",
"--baudrate",
"115200",
"--out",
"127.0.0.1:14550",
"-c",
"7",
"-c",
"9",
"-r",
"50",
"--ahi",
"3",
"--matrix",
"11",
"-v",
"-f",
"/home/home/",
" "

],
"stopAtEntry": false,
"cwd": "${workspaceFolder}",
"environment": [],
"externalConsole": false,
"MIMode": "gdb",
"miDebuggerPath": "/usr/bin/gdb",

"setupCommands": [
{
"description": "MAVLINk gdb",
"text": "-enable-pretty-printing",
"ignoreFailures": true
}
],
"preLaunchTask": "copy msposd"

}
]
}
6 changes: 5 additions & 1 deletion develepment_notes.txt
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,11 @@ Will Line 1,2, 10,11, 19,20 will be Large font, the rest will be small, and alig
--ahi 3
Enhanced AHI ladder, home indicator on the main AHI line
--on PC read serial
msposd --channels 7 --master /dev/ttyUSB0 --baudrate 115200 --osd --matrix 11 --ahi 3 -r 30
msposd --channels 7 --master /dev/ttyUSB0 --baudrate 115200 --osd --matrix 11 --ahi 3 -r 30 -v

--on PC read serial and forward to test air no OSD mode
msposd --channels 7 --master /dev/ttyUSB0 --baudrate 115200 --out 127.0.0.1:14550 --matrix 11 --ahi 3 -r 50 -v


--on CAM read serial and forward via mavlink port
msposd --channels 7 --master /dev/ttyS2 --baudrate 115200 --out 127.0.0.1:14550 --matrix 11 --ahi 3 -r 30
Expand Down
18 changes: 9 additions & 9 deletions msposd.c
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ int AHI_Enabled=1;

const char *default_master = "/dev/ttyAMA0";
const int default_baudrate = 115200;
const char *defualt_out_addr = "127.0.0.1:14600";
const char *defualt_out_addr = "";
const char *default_in_addr = "127.0.0.1:0";
const int RC_CHANNELS = 65; //RC_CHANNELS ( #65 ) for regular MAVLINK RC Channels read (https://mavlink.io/en/messages/common.html#RC_CHANNELS)
const int RC_CHANNELS_RAW = 35; //RC_CHANNELS_RAW ( #35 ) for ExpressLRS,Crossfire and other RC procotols (https://mavlink.io/en/messages/common.html#RC_CHANNELS_RAW)
Expand All @@ -75,7 +75,7 @@ struct bufferevent *serial_bev;
struct sockaddr_in sin_out = {
.sin_family = AF_INET,
};
int out_sock;
int out_sock=0;


long aggregate=1;
Expand Down Expand Up @@ -1044,15 +1044,15 @@ static int handle_data(const char *port_name, int baudrate,
printf("Setup mspVTX ...\n");
msp_set_vtx_config(serial_fd);
}
out_sock = socket(AF_INET, SOCK_DGRAM, 0);

if (!parse_host_port(out_addr,
(struct in_addr *)&sin_out.sin_addr.s_addr,
&sin_out.sin_port))
goto err;
if (strlen(out_addr)>1){
out_sock = socket(AF_INET, SOCK_DGRAM, 0);



if (!parse_host_port(out_addr,
(struct in_addr *)&sin_out.sin_addr.s_addr,
&sin_out.sin_port))
goto err;
}

struct sockaddr_in sin_in = {
.sin_family = AF_INET,
Expand Down
109 changes: 58 additions & 51 deletions osd.c
Original file line number Diff line number Diff line change
Expand Up @@ -420,18 +420,22 @@ static void rx_msp_callback(msp_msg_t *msp_message)
stat_msp_msgs++;

//We will forward ALL MSP traffic, not only DisplayPort
if(fb_cursor > sizeof(frame_buffer)) {
printf("Exhausted frame buffer! Resetting...\n");
sendto(out_sock, frame_buffer, fb_cursor, 0, (struct sockaddr *)&sin_out, sizeof(sin_out));
if(fb_cursor > sizeof(frame_buffer)) {
if (out_sock>0){
printf("Exhausted frame buffer! Flushing...\n");
sendto(out_sock, frame_buffer, fb_cursor, 0, (struct sockaddr *)&sin_out, sizeof(sin_out));
}
fb_cursor = 0;
return;
//return;
}
//Here it will replace custom text messages for configurator screen
if (msp_message->cmd==MSP_CMD_DISPLAYPORT && msp_message->direction == MSP_INBOUND && msp_message->cmd == MSP_CMD_DISPLAYPORT && msp_message->payload[0] == MSP_DISPLAYPORT_DRAW_STRING)
InjectChars(&msp_message->payload[0]);

uint16_t size = msp_data_from_msg(message_buffer, msp_message);
copy_to_msp_frame_buffer(message_buffer, size);
//if (out_sock>0){//No need to cache MSP if we won't send it later
uint16_t size = msp_data_from_msg(message_buffer, msp_message);
copy_to_msp_frame_buffer(message_buffer, size);
//}

switch(msp_message->cmd) {

Expand Down Expand Up @@ -495,9 +499,10 @@ GPS_update UINT 8 a flag to indicate when a new GPS frame is received (the GPS f
if (!DrawOSD){//if we only resend to ground station and menu is active, stop regular OSD
LastPcktSent= get_time_ms();//clear buffer and prevent from sending MSP to ground
fb_cursor = 0;
printf("D");
}

if (out_sock>0){
if (out_sock>0 && fb_cursor>0){//if there is data to send
if(msp_message->payload[0] == MSP_DISPLAYPORT_DRAW_SCREEN) {
//Try to aggregate several MSP packets into one UDP packets
if ( (!DrawOSD) && MinTimeBetweenScreenRefresh>20 && (get_time_ms() - LastPcktSent ) < MinTimeBetweenScreenRefresh)
Expand Down Expand Up @@ -1319,16 +1324,17 @@ bool DrawTextOnOSDBitmap(){
// so we simply send it to the ground

if (!DrawOSD && out_sock>0){//send the line to the ground
static uint8_t message_buffer[256];
static uint8_t msg_buffer[256];
static uint8_t payload_buffer[256];
out[79]=0;//just in case
int msglen = strlen(&out[0]);

payload_buffer[0]=MSP_DISPLAYPORT_INFO_MSG;
memcpy(&payload_buffer[1],&out[0], msglen+1); //include the 0 for string ending
construct_msp_command(message_buffer, MSP_CMD_DISPLAYPORT, &payload_buffer[0], 80, MSP_INBOUND);
sendto(out_sock, message_buffer,100 , 0, (struct sockaddr *)&sin_out, sizeof(sin_out));
printf("Sent text msg : %s\r\n",out);
construct_msp_command(msg_buffer, MSP_CMD_DISPLAYPORT, &payload_buffer[0], 80, MSP_INBOUND);
sendto(out_sock, msg_buffer,100 , 0, (struct sockaddr *)&sin_out, sizeof(sin_out));

//printf("Sent text msg : %s\r\n",out);
return false;
}

Expand Down Expand Up @@ -1526,18 +1532,19 @@ static void draw_screenBMP(){
if (cntr++<0 )//skip in the beginning to show to font preview
return ;

if ( !DrawOSD && (get_time_ms() - LastDrawn ) < 200)//No need to redraw text on screen so often, lets keep low
if ( !DrawOSD && (get_time_ms() - LastDrawn ) < 200)//No need to redraw text on screen so often, lets keep low CPU load
return ;

if ( (get_time_ms() - LastDrawn ) < MinTimeBetweenScreenRefresh){//Set some delay to keep CPU load low
stat_skipped_frames++;
return ;
}

if ( (get_time_ms() - LastCleared ) < 2){//at least 2ms to reload some data after clearscreen, otherwise the screen will blink?
//but if there is too few chars to show we may never render it
if ( (get_time_ms() - LastCleared ) < 2){
//at least 2ms to reload some data after clearscreen, otherwise the screen will blink?
//but if there is too few chars to show we may never render it
//printf("%lu DrawSkipped after clear LastDrawn:%lu | %lu%\r\n",(uint32_t)get_time_ms()%10000, (uint32_t)LastDrawn%10000 , (uint32_t) LastCleared%10000);
return ;
//return ;
}

LastDrawn= get_time_ms();
Expand Down Expand Up @@ -1665,41 +1672,40 @@ static void draw_screenBMP(){
//memcpy(bmp_x86,bmpBuff.pData, bmpBuff.u32Width * bmpBuff.u32Height * 4);//Do not need to copy...
bmp_x86=bmpBuff.pData;

//ClearScreen_x86();
Render_x86(bmp_x86,bmpBuff.u32Width, bmpBuff.u32Height);

if (AHI_Enabled==2)
draw_AHI();
if (AHI_Enabled==1 || AHI_Enabled>2)
draw_Ladder();
if (RCWidgetX>0)
drawRC_Channels(RCWidgetX, RCWidgetY, channels[0], channels[1], channels[2], channels[3]);

//strcpy(air_unit_info_msg,"30fps/MCS1 7Mb reset test message that can be 80 characters long that are enough");
if (strlen(air_unit_info_msg)>1){
int osd_font_size=osds[FULL_OVERLAY_ID].size - 6; //Some offset needed to keep the same with air rendering
uint64_t timems=get_time_ms();
int width=getTextWidth_x86(air_unit_info_msg,osd_font_size);

if (DrawOSD){
//ClearScreen_x86();
Render_x86(bmp_x86,bmpBuff.u32Width, bmpBuff.u32Height);

if (AHI_Enabled==2)
draw_AHI();
if (AHI_Enabled==1 || AHI_Enabled>2)
draw_Ladder();
if (RCWidgetX>0)
drawRC_Channels(RCWidgetX, RCWidgetY, channels[0], channels[1], channels[2], channels[3]);

//strcpy(air_unit_info_msg,"30fps/MCS1 7Mb reset test message that can be 80 characters long that are enough");
if (strlen(air_unit_info_msg)>1){
int osd_font_size=osds[FULL_OVERLAY_ID].size - 6; //Some offset needed to keep the same with air rendering
uint64_t timems=get_time_ms();
int width=getTextWidth_x86(air_unit_info_msg,osd_font_size);

int posX=0,posY=0;
if (msg_layout%4==0)// left
posX=4;
if (msg_layout%4==1)// center
posX=(bmpBuff.u32Width - width) /2;
if (msg_layout%4==2)// right
posX=(bmpBuff.u32Width - width) - 42;
if (msg_layout%4==3)//moving
posX=20 + ((timems/16)%(bmpBuff.u32Width - width - 40))& ~1;
posY=(msg_layout/4)== 0 ? osd_font_size : (bmpBuff.u32Height ) - 6;//Uppper or lower line

drawText_x86(air_unit_info_msg, posX , posY, getcolor(msg_colour), /*font_size*/ osd_font_size, false,0);
}

int posX=0,posY=0;
if (msg_layout%4==0)// left
posX=4;
if (msg_layout%4==1)// center
posX=(bmpBuff.u32Width - width) /2;
if (msg_layout%4==2)// right
posX=(bmpBuff.u32Width - width) - 42;
if (msg_layout%4==3)//moving
posX=20 + ((timems/16)%(bmpBuff.u32Width - width - 40))& ~1;
posY=(msg_layout/4)== 0 ? osd_font_size : (bmpBuff.u32Height ) - 6;//Uppper or lower line

drawText_x86(air_unit_info_msg, posX , posY, getcolor(msg_colour), /*font_size*/ osd_font_size, false,0);
FlushDrawing_x86();
}

//Render_x86_rect(bmp_x86,bmpBuff.u32Width, bmpBuff.u32Height,10,10,10,10,24,36);
FlushDrawing_x86();

//free(bmp_x86);


#elif __GOKE__
if (DrawOSD)
Expand Down Expand Up @@ -1960,7 +1966,8 @@ static void InitMSPHook(){
int height = GetMajesticVideoConfig(&majestic_width);

#ifdef _x86
Init_x86(&OVERLAY_WIDTH, &OVERLAY_HEIGHT);
if (DrawOSD)
Init_x86(&OVERLAY_WIDTH, &OVERLAY_HEIGHT);
height=OVERLAY_HEIGHT;
#endif

Expand Down Expand Up @@ -2085,9 +2092,9 @@ On sigmastar the BMP row stride is aligned to 8 bytes, that is 16 pixels in PIXE

if (DrawOSD){ //Show Font Preview
#ifdef _x86
cntr= - 30; //skip first 40 draw requests from the FC to show the preview, about 3 seconds
cntr= - 20; //skip first 40 draw requests from the FC to show the preview, about 1 seconds
#else
cntr= - 130; //skip first 40 draw requests from the FC to show the preview, about 3 seconds
cntr= - 80; //skip first 80 draw requests from the FC to show the preview, about 2 seconds
#endif
BITMAP bitmap;
int prepared=0;
Expand Down
10 changes: 1 addition & 9 deletions osd/util/Render_x86.c
Original file line number Diff line number Diff line change
Expand Up @@ -166,15 +166,7 @@ void ClearScreen_x86(){

void Render_x86( unsigned char* rgbaData, int u32Width, int u32Height){

//no need to change every frame, just change the font bitmap once
// premultiplyAlpha((uint32_t*)rgbaData, u32Width, u32Height);

// Clear the main surface to avoid lingering frames
//cairo_set_operator(cr_x11, CAIRO_OPERATOR_SOURCE);
//cairo_set_source_rgba(cr_x11, 0, 0, 0, 0); // Transparent background for main surface
//cairo_paint(cr_x11);

// Clear the buffer surface

cairo_set_source_rgba(cr, 0, 0, 0, 0); // Transparent background for buffer
cairo_set_operator(cr, CAIRO_OPERATOR_SOURCE); // Clear everything on the buffer
cairo_paint(cr);
Expand Down
Binary file modified release/goke/msposd
Binary file not shown.
Binary file modified release/hisi/msposd
Binary file not shown.
Binary file modified release/star6e/msposd
Binary file not shown.
Binary file modified release/x86/msposd
Binary file not shown.

0 comments on commit fa68683

Please sign in to comment.