Skip to content

Commit c865a5a

Browse files
committed
Removed redundant code for mode switch OSD switching.
Cleaned up all C warnings, removed unused variables.
1 parent 920b8c0 commit c865a5a

File tree

5 files changed

+150
-150
lines changed

5 files changed

+150
-150
lines changed

MinimOSD_Extra_Plane_Pre_release_Beta/MAVLink.ino

Lines changed: 4 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -129,14 +129,10 @@ void read_mavlink(){
129129
break;
130130
case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
131131
{
132-
// chan1_raw = mavlink_msg_rc_channels_raw_get_chan1_raw(&msg);
133-
// chan2_raw = mavlink_msg_rc_channels_raw_get_chan2_raw(&msg);
134-
// chan3_raw = mavlink_msg_rc_channels_raw_get_chan3_raw(&msg);
135-
// chan4_raw = mavlink_msg_rc_channels_raw_get_chan4_raw(&msg);
136-
chan5_raw = mavlink_msg_rc_channels_raw_get_chan5_raw(&msg);
137-
chan6_raw = mavlink_msg_rc_channels_raw_get_chan6_raw(&msg);
138-
chan7_raw = mavlink_msg_rc_channels_raw_get_chan7_raw(&msg);
139-
chan8_raw = mavlink_msg_rc_channels_raw_get_chan8_raw(&msg);
132+
chan_raw[5] = mavlink_msg_rc_channels_raw_get_chan5_raw(&msg);
133+
chan_raw[6] = mavlink_msg_rc_channels_raw_get_chan6_raw(&msg);
134+
chan_raw[7] = mavlink_msg_rc_channels_raw_get_chan7_raw(&msg);
135+
chan_raw[8] = mavlink_msg_rc_channels_raw_get_chan8_raw(&msg);
140136
osd_rssi = mavlink_msg_rc_channels_raw_get_rssi(&msg);
141137
}
142138
break;

MinimOSD_Extra_Plane_Pre_release_Beta/MinimOSD_Extra_Plane_Pre_release_Beta.ino

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -182,7 +182,7 @@ void loop()
182182
//osd.printf_P(PSTR("Requesting DataStreams..."));
183183
//osd.closePanel();
184184
//for(int n = 0; n < 3; n++){
185-
// request_mavlink_rates();//Three times to certify it will be readed
185+
// request_mavlink_rates();//Three times to certify it will be read
186186
// delay(50);
187187
//}
188188
enable_mav_request = 0;

MinimOSD_Extra_Plane_Pre_release_Beta/OSD_Panels.ino

Lines changed: 104 additions & 109 deletions
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,7 @@ void startPanels(){
1010
void panLogo(){
1111
osd.setPanel(5, 5);
1212
osd.openPanel();
13-
osd.printf_P(PSTR("MinimOSD-Extra 2.4|Plane r807"));
13+
osd.printf_P(PSTR("MinimOSD-Extra 2.4|Plane r808"));
1414
osd.closePanel();
1515
}
1616

@@ -166,9 +166,9 @@ void panDistance(int first_col, int first_line){
166166
osd.openPanel();
167167
//do_converts();
168168
if ((tdistance * converth) > 9999.0) {
169-
osd.printf("%c%5.2f%c", 0x8f, ((tdistance * converth) / distconv), distchar);
169+
osd.printf("%c%5.2f%c", 0x8f, (double)((tdistance * converth) / distconv), distchar);
170170
}else{
171-
osd.printf("%c%5.0f%c", 0x8f, (tdistance * converth), high);
171+
osd.printf("%c%5.0f%c", 0x8f, (double)(tdistance * converth), high);
172172
}
173173
osd.closePanel();
174174
}
@@ -183,7 +183,7 @@ void panFdata(){
183183
osd.setPanel(11, 3);
184184
osd.openPanel();
185185
// osd.printf("%c%3i%c%02i|%c%5.0f%c|%c%5.0f%c|%c%5.0f%c|%c%5.0f%c|%c%5.0f%c|%c%5.0f%c", 0x08,((int)start_Time/60)%60,0x3A,(int)start_Time%60, 0x0b, ((max_home_distance) * converth), high, 0x1b, ((tdistance) * converth), high, 0x13,(max_osd_airspeed * converts), spe,0x14,(max_osd_groundspeed * converts),spe,0x12, (max_osd_home_alt * converth), high,0x1d,(max_osd_windspeed * converts),spe);
186-
osd.printf("%c%3i%c%02i|%c%5.0f%c|%c%5.0f%c|%c%5i%c|%c%5i%c|%c%5i%c|%c%5i%c|%c%5.0f%c|%c%11.6f|%c%11.6f", 0x08,((int)(start_Time/60)),0x3A,(int)start_Time%60, 0x0b, ((max_home_distance) * converth), high, 0x8f, (tdistance * converth), high, 0x13,(int)(max_osd_airspeed * converts), spe,0x14,(int)(max_osd_groundspeed * converts),spe,0x12, (int)(max_osd_home_alt * converth), high,0x1d,(int)(max_osd_windspeed * converts),spe, 0x17, mah_used, 0x01, 0x03, (double)osd_lat, 0x04, (double)osd_lon);
186+
osd.printf("%c%3i%c%02i|%c%5.0f%c|%c%5.0f%c|%c%5i%c|%c%5i%c|%c%5i%c|%c%5i%c|%c%5.0f%c|%c%11.6f|%c%11.6f", 0x08,((int)(start_Time/60)),0x3A,(int)start_Time%60, 0x0b, (double)((max_home_distance) * converth), high, 0x8f, (double)(tdistance * converth), high, 0x13,(int)(max_osd_airspeed * converts), spe,0x14,(int)(max_osd_groundspeed * converts),spe,0x12, (int)(max_osd_home_alt * converth), high,0x1d,(int)(max_osd_windspeed * converts),spe, 0x17, (double)mah_used, 0x01, 0x03, (double)osd_lat, 0x04, (double)osd_lon);
187187
osd.closePanel();
188188
}
189189

@@ -198,7 +198,7 @@ void panTemp(int first_col, int first_line){
198198
osd.setPanel(first_col, first_line);
199199
osd.openPanel();
200200
// osd.printf("%c%5.1f%c", 0x0a, (float(temperature * tempconv + tempconvAdd) / 100), temps);
201-
osd.printf("%5.1f%c", (float(temperature * tempconv + tempconvAdd) / 1000), temps);
201+
osd.printf("%5.1f%c", (double)(float(temperature * tempconv + tempconvAdd) / 1000), temps);
202202
osd.closePanel();
203203
}
204204

@@ -219,7 +219,7 @@ void panEff(int first_col, int first_line){
219219
if (osd_groundspeed != 0) eff = (float(osd_curr_A * 10.0) / (osd_groundspeed * converts))* 0.1 + eff * 0.9;
220220
// eff = eff * 0.2 + eff * 0.8;
221221
if (eff > 0 && eff <= 9999) {
222-
osd.printf("%c%4.0f%c", 0x16, eff, 0x01);
222+
osd.printf("%c%4.0f%c", 0x16, (double)eff, 0x01);
223223
}else{
224224
osd.printf_P(PSTR("\x16\x20\x20\x20\x20\x20"));
225225
}
@@ -238,8 +238,8 @@ void panEff(int first_col, int first_line){
238238
// glide = ((osd_alt_to_home / (palt - osd_alt_to_home)) * ((millis() - descendt) / 1000)) * osd_groundspeed;
239239
glide = ((osd_alt_to_home / (palt - osd_alt_to_home)) * (tdistance - ddistance)) * converth;
240240
if (glide > 9999) glide = 9999;
241-
if (glide != 'inf' && glide > -0){
242-
osd.printf("%c%4.0f%c", 0x18, glide, high);
241+
if (glide != INFINITY && glide > -0){
242+
osd.printf("%c%4.0f%c", 0x18, (double)glide, high);
243243
}
244244
}
245245
else if (osd_climb >= -0.05 && osd_pitch < 0) {
@@ -285,10 +285,11 @@ void panRSSI(int first_col, int first_line){
285285
if(osd_rssi < rssipersent) osd_rssi = rssipersent;
286286
if(osd_rssi > rssical) osd_rssi = rssical;
287287
if(rssiraw_on == 0) rssi = (int16_t)((float)((int16_t)osd_rssi - rssipersent)/(float)(rssical-rssipersent)*100.0f);
288-
if(rssiraw_on == 8) rssi = (int16_t)((float)(chan8_raw / 10 - rssipersent)/(float)(rssical-rssipersent)*100.0f);
288+
if(rssiraw_on == 8) rssi = (int16_t)((float)(chan_raw[8] / 10 - rssipersent)/(float)(rssical-rssipersent)*100.0f);
289289
}
290290
if(rssiraw_on == 1) rssi = (int16_t)osd_rssi;
291-
if(rssiraw_on == 9) rssi = chan8_raw;
291+
// FIXME: why is this here? Delete?
292+
if(rssiraw_on == 9) rssi = chan_raw[8];
292293

293294
if(rssi > 100.0) rssi = 100;
294295

@@ -434,83 +435,62 @@ void panWindSpeed(int first_col, int first_line){
434435
void panOff(){
435436
bool rotatePanel = 0;
436437

437-
if(ch_toggle == 5) ch_raw = chan5_raw;
438-
else if(ch_toggle == 6) ch_raw = chan6_raw;
439-
else if(ch_toggle == 7) ch_raw = chan7_raw;
440-
else if(ch_toggle == 8) ch_raw = chan8_raw;
438+
ch_raw = chan_raw[ch_toggle];
441439

442440
//If there is a warning force switch to panel 0
443441
if(canswitch == 0){
444442
if(panel != panel_auto_switch){
445-
//osd.clear();
446443
osd_clear = 1;
447444
}
448445
panel = panel_auto_switch;
449446
}
450447
else{
451-
//Flight mode switching
452-
if (ch_toggle == 4){
453-
if ((osd_mode != 6) && (osd_mode != 7)){
454-
if (osd_off_switch != osd_mode){
455-
osd_off_switch = osd_mode;
456-
osd_switch_time = millis();
457-
if (osd_off_switch == osd_switch_last){
458-
rotatePanel = 1;
459-
}
460-
}
461-
if ((millis() - osd_switch_time) > 2000){
462-
osd_switch_last = osd_mode;
463-
}
448+
//Switch mode by value
449+
if (switch_mode == 0){
450+
//First panel
451+
if (ch_raw < 1233) {
452+
if (panel != 0) {
453+
osd_clear = 1;
454+
panel = 0;
455+
}
456+
}
457+
//Second panel
458+
else if (ch_raw <= 1467) {
459+
if (panel != 1) {
460+
osd_clear = 1;
461+
panel = 1;
462+
}
463+
}
464+
//Panel off
465+
else if (panel != npanels) {
466+
osd_clear = 1;
467+
panel = npanels; //off panel
464468
}
465469
}
470+
// Rotation switch
466471
else {
467-
468-
//Switch mode by value
469-
if (switch_mode == 0){
470-
//First panel
471-
if (ch_raw < 1233 && panel != 0) {
472-
osd_clear = 1;
473-
//osd.clear();
474-
panel = 0;
475-
}
476-
//Second panel
477-
else if (ch_raw >= 1233 && ch_raw <= 1467 && panel != 1) { //second panel
478-
osd_clear = 1;
479-
//osd.clear();
480-
panel = 1;
481-
}
482-
//Panel off
483-
else if (ch_raw > 1467 && panel != npanels) {
484-
osd_clear = 1;
485-
//osd.clear();
486-
panel = npanels; //off panel
487-
}
488-
}
489-
// Rotation switch
490-
else {
491-
// Switch changed from its last position
492-
if (abs (ch_raw - ch_raw_prev1) > 100) {
493-
// but is the same than 2 positions ago
494-
if (abs (ch_raw - ch_raw_prev2) < 100) {
495-
osd.closePanel();
496-
// and it's been less than 1 sec since the position switch and back
497-
if (osd_switch_time + 1000 > millis()) {
498-
// then rotate
499-
rotatePanel = 1;
500-
}
501-
// stop continuous rotation, forcing a switch flip to restart the process
502-
// or if the flip didn't happen because it happened too slowly, reset too.
503-
ch_raw_prev2 = 0;
504-
} else {
505-
osd_switch_time = millis();
506-
// If position changed and is different from what it was 2 positions ago
507-
// record the new state
508-
ch_raw_prev2 = ch_raw_prev1;
509-
ch_raw_prev1 = ch_raw;
472+
// Switch changed from its last position
473+
if (abs (ch_raw - ch_raw_prev1) > 100) {
474+
// but is the same than 2 positions ago
475+
if (abs (ch_raw - ch_raw_prev2) < 100) {
476+
osd.closePanel();
477+
// and it's been less than 1 sec since the position switch and back
478+
if (osd_switch_time + 1000 > millis()) {
479+
// then rotate
480+
rotatePanel = 1;
510481
}
482+
// stop continuous rotation, forcing a switch flip to restart the process
483+
// or if the flip didn't happen because it happened too slowly, reset too.
484+
ch_raw_prev2 = 0;
485+
} else {
486+
osd_switch_time = millis();
487+
// If position changed and is different from what it was 2 positions ago
488+
// record the new state
489+
ch_raw_prev2 = ch_raw_prev1;
490+
ch_raw_prev1 = ch_raw;
511491
}
512-
}
513-
}
492+
}
493+
}
514494
if(rotatePanel == 1){
515495
osd_clear = 1;
516496
//osd.clear();
@@ -531,7 +511,7 @@ void panOff(){
531511
osd.setPanel(first_col, first_line);
532512
osd.openPanel();
533513

534-
osd.printf("%c%3.0f%c%c|%c%3.0f%c%c", 0xb0, (alt_error * converth * -1), high, 0x20, 0xb1, ((aspd_error / 100.0) * converts), spe, 0x20);
514+
osd.printf("%c%3.0f%c%c|%c%3.0f%c%c", 0xb0, (double)(alt_error * converth * -1), high, 0x20, 0xb1, ((aspd_error / 100.0) * converts), spe, 0x20);
535515

536516
osd.closePanel();
537517
}
@@ -679,51 +659,66 @@ void panWarn(int first_col, int first_line){
679659

680660

681661
// Prepare for printf in rotation
682-
if (rotation == 0) if (warning[0] == 0 || warning[0] + warning[1] + warning[2] + warning[3] + warning[4] + warning[5] == 2) {
683-
warning_string = "\x20\x20\x20\x20\x20\x20\x20\x20\x20\x20\x20\x20";
662+
if (rotation == 0) {
663+
if (warning[0] == 0 || warning[0] + warning[1] + warning[2] + warning[3] + warning[4] + warning[5] == 2) {
664+
warning_string = (char *)"\x20\x20\x20\x20\x20\x20\x20\x20\x20\x20\x20\x20";
684665
}else{
685666
rotation = 1;
686-
}
667+
}
668+
}
687669

688-
if (rotation == 1) if (warning[1] == 1) {
689-
warning_string = "\x20\x4E\x6F\x20\x47\x50\x53\x20\x66\x69\x78\x21";
670+
if (rotation == 1) {
671+
if (warning[1] == 1) {
672+
warning_string = (char *)"\x20\x4E\x6F\x20\x47\x50\x53\x20\x66\x69\x78\x21";
690673
}else{
691674
rotation = 2;
692675
}
676+
}
693677

694-
if (rotation == 2) if (warning[2] == 1) {
695-
warning_string = "\x20\x20\x20\x53\x74\x61\x6c\x6c\x21\x20\x20\x20";
678+
if (rotation == 2) {
679+
if (warning[2] == 1) {
680+
warning_string = (char *)"\x20\x20\x20\x53\x74\x61\x6c\x6c\x21\x20\x20\x20";
696681
}else{
697682
rotation = 3;
698683
}
684+
}
699685

700-
if (rotation == 3) if (warning[3] == 1) {
701-
warning_string = "\x20\x4f\x76\x65\x72\x53\x70\x65\x65\x64\x21\x20";
686+
if (rotation == 3) {
687+
if (warning[3] == 1) {
688+
warning_string = (char *)"\x20\x4f\x76\x65\x72\x53\x70\x65\x65\x64\x21\x20";
702689
}else{
703690
rotation = 4;
704691
}
692+
}
705693

706-
if (rotation == 4) if (warning[4] == 1) {
707-
warning_string = "\x42\x61\x74\x74\x65\x72\x79\x20\x4c\x6f\x77\x21";
694+
if (rotation == 4) {
695+
if (warning[4] == 1) {
696+
warning_string = (char *)"\x42\x61\x74\x74\x65\x72\x79\x20\x4c\x6f\x77\x21";
708697
}else{
709698
rotation = 5;
710699
}
700+
}
711701

712-
if (rotation == 5) if (warning[5] == 1) {
713-
warning_string = "\x20\x20\x4c\x6f\x77\x20\x52\x73\x73\x69\x20\x20";
702+
if (rotation == 5) {
703+
if (warning[5] == 1) {
704+
warning_string = (char *)"\x20\x20\x4c\x6f\x77\x20\x52\x73\x73\x69\x20\x20";
705+
// rotation++ below makes this happen
714706
// rotation = 6;
715707
}
708+
}
716709

717-
// if (rotation == 6) if (warning[6] == 1) {
718-
// warning_string = "\x20\x20\x4c\x6f\x77\x20\x48\x44\x4f\x50\x20\x20";
719-
// }
710+
// if (rotation == 6) {
711+
// if (warning[6] == 1) {
712+
// warning_string = (char *)"\x20\x20\x4c\x6f\x77\x20\x48\x44\x4f\x50\x20\x20";
713+
// }
714+
// }
720715
rotation++;
721716

722717
// Auto switch decision
723718
if (warning[0] == 1 && panel_auto_switch < 3){
724-
canswitch = 0;
719+
canswitch = 0;
725720
}else if (ch_raw < 1200) {
726-
canswitch = 1;
721+
canswitch = 1;
727722
}
728723
if (rotation > 5) rotation = 0;
729724

@@ -761,7 +756,7 @@ void panBatteryPercent(int first_col, int first_line){
761756
if (EEPROM.read(OSD_BATT_SHOW_PERCENT_ADDR) == 1){
762757
osd.printf("%c%3.0i%c", 0x17, osd_battery_remaining_A, 0x25);
763758
}else{
764-
osd.printf("%c%4.0f%c", 0x17, mah_used, 0x01);
759+
osd.printf("%c%4.0f%c", 0x17, (double)mah_used, 0x01);
765760
}
766761
osd.closePanel();
767762
}
@@ -804,9 +799,9 @@ void panHomeDis(int first_col, int first_line){
804799

805800

806801
if ((osd_home_distance * converth) > 9999.0) {
807-
osd.printf("%c%5.2f%c", 0x0b, ((osd_home_distance * converth) / distconv), distchar);
802+
osd.printf("%c%5.2f%c", 0x0b, (double)((osd_home_distance * converth) / distconv), distchar);
808803
}else{
809-
osd.printf("%c%5.0f%c", 0x0b, (osd_home_distance * converth), high);
804+
osd.printf("%c%5.0f%c", 0x0b, (double)(osd_home_distance * converth), high);
810805
}
811806

812807
osd.closePanel();
@@ -1077,7 +1072,7 @@ void panWPDis(int first_col, int first_line){
10771072
showArrow((uint8_t)wp_target_bearing_rotate_int,0);
10781073

10791074
if (osd_mode == 10 || osd_mode == 15 || osd_mode == 7){
1080-
osd.printf("%c%c%c%4.0f%c", 0x20, 0x58, 0x65, (xtrack_error* converth), high);
1075+
osd.printf("%c%c%c%4.0f%c", 0x20, 0x58, 0x65, (double)(xtrack_error* converth), high);
10811076
}else{
10821077
osd.printf_P(PSTR("\x20\x20\x20\x20\x20\x20\x20\x20"));
10831078
}
@@ -1109,19 +1104,19 @@ void panFlightMode(int first_col, int first_line){
11091104
osd.setPanel(first_col, first_line);
11101105
osd.openPanel();
11111106
//char c1 = 0x7f ;//"; char c2; char c3; char c4; char c5;
1112-
char* mode_str="";
1113-
if (osd_mode == 0) mode_str = "manu"; //Manual
1114-
if (osd_mode == 1) mode_str = "circ"; //CIRCLE
1115-
if (osd_mode == 2) mode_str = "stab"; //Stabilize
1116-
if (osd_mode == 3) mode_str = "trai"; //Training
1117-
if (osd_mode == 4) mode_str = "acro"; //ACRO
1118-
if (osd_mode == 5) mode_str = "fbwa"; //FLY_BY_WIRE_A
1119-
if (osd_mode == 6) mode_str = "fbwb"; //FLY_BY_WIRE_B
1120-
if (osd_mode == 7) mode_str = "cruz"; //Cruise
1121-
if (osd_mode == 10) mode_str = "auto"; //AUTO
1122-
if (osd_mode == 11) mode_str = "retl"; //Return to Launch
1123-
if (osd_mode == 12) mode_str = "loit"; //Loiter
1124-
if (osd_mode == 15) mode_str = "guid"; //GUIDED
1107+
char* mode_str=(char *)"";
1108+
if (osd_mode == 0) mode_str = (char *)"manu"; //Manual
1109+
if (osd_mode == 1) mode_str = (char *)"circ"; //CIRCLE
1110+
if (osd_mode == 2) mode_str = (char *)"stab"; //Stabilize
1111+
if (osd_mode == 3) mode_str = (char *)"trai"; //Training
1112+
if (osd_mode == 4) mode_str = (char *)"acro"; //ACRO
1113+
if (osd_mode == 5) mode_str = (char *)"fbwa"; //FLY_BY_WIRE_A
1114+
if (osd_mode == 6) mode_str = (char *)"fbwb"; //FLY_BY_WIRE_B
1115+
if (osd_mode == 7) mode_str = (char *)"cruz"; //Cruise
1116+
if (osd_mode == 10) mode_str = (char *)"auto"; //AUTO
1117+
if (osd_mode == 11) mode_str = (char *)"retl"; //Return to Launch
1118+
if (osd_mode == 12) mode_str = (char *)"loit"; //Loiter
1119+
if (osd_mode == 15) mode_str = (char *)"guid"; //GUIDED
11251120

11261121

11271122
// osd.printf("%c%s", 0x7f, mode_str);

0 commit comments

Comments
 (0)