Skip to content

Commit b5541fe

Browse files
DzikuVxJulianTiller
authored andcommitted
Revert "Merge pull request iNavFlight#9865 from iNavFlight/dzikuvx-drop-msp-osd-config"
This reverts commit a8de611, reversing changes made to 05e7a31.
1 parent c21c2b3 commit b5541fe

File tree

2 files changed

+53
-0
lines changed

2 files changed

+53
-0
lines changed

src/main/fc/fc_msp.c

Lines changed: 50 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1156,6 +1156,26 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
11561156
break;
11571157
#endif
11581158

1159+
case MSP_OSD_CONFIG:
1160+
#ifdef USE_OSD
1161+
sbufWriteU8(dst, OSD_DRIVER_MAX7456); // OSD supported
1162+
// send video system (AUTO/PAL/NTSC)
1163+
sbufWriteU8(dst, osdConfig()->video_system);
1164+
sbufWriteU8(dst, osdConfig()->units);
1165+
sbufWriteU8(dst, osdConfig()->rssi_alarm);
1166+
sbufWriteU16(dst, currentBatteryProfile->capacity.warning);
1167+
sbufWriteU16(dst, osdConfig()->time_alarm);
1168+
sbufWriteU16(dst, osdConfig()->alt_alarm);
1169+
sbufWriteU16(dst, osdConfig()->dist_alarm);
1170+
sbufWriteU16(dst, osdConfig()->neg_alt_alarm);
1171+
for (int i = 0; i < OSD_ITEM_COUNT; i++) {
1172+
sbufWriteU16(dst, osdLayoutsConfig()->item_pos[0][i]);
1173+
}
1174+
#else
1175+
sbufWriteU8(dst, OSD_DRIVER_NONE); // OSD not supported
1176+
#endif
1177+
break;
1178+
11591179
case MSP_3D:
11601180
sbufWriteU16(dst, reversibleMotorsConfig()->deadband_low);
11611181
sbufWriteU16(dst, reversibleMotorsConfig()->deadband_high);
@@ -2383,6 +2403,36 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
23832403
#endif
23842404

23852405
#ifdef USE_OSD
2406+
case MSP_SET_OSD_CONFIG:
2407+
sbufReadU8Safe(&tmp_u8, src);
2408+
// set all the other settings
2409+
if ((int8_t)tmp_u8 == -1) {
2410+
if (dataSize >= 10) {
2411+
osdConfigMutable()->video_system = sbufReadU8(src);
2412+
osdConfigMutable()->units = sbufReadU8(src);
2413+
osdConfigMutable()->rssi_alarm = sbufReadU8(src);
2414+
currentBatteryProfileMutable->capacity.warning = sbufReadU16(src);
2415+
osdConfigMutable()->time_alarm = sbufReadU16(src);
2416+
osdConfigMutable()->alt_alarm = sbufReadU16(src);
2417+
// Won't be read if they weren't provided
2418+
sbufReadU16Safe(&osdConfigMutable()->dist_alarm, src);
2419+
sbufReadU16Safe(&osdConfigMutable()->neg_alt_alarm, src);
2420+
} else
2421+
return MSP_RESULT_ERROR;
2422+
} else {
2423+
// set a position setting
2424+
if ((dataSize >= 3) && (tmp_u8 < OSD_ITEM_COUNT)) // tmp_u8 == addr
2425+
osdLayoutsConfigMutable()->item_pos[0][tmp_u8] = sbufReadU16(src);
2426+
else
2427+
return MSP_RESULT_ERROR;
2428+
}
2429+
// Either a element position change or a units change needs
2430+
// a full redraw, since an element can change size significantly
2431+
// and the old position or the now unused space due to the
2432+
// size change need to be erased.
2433+
osdStartFullRedraw();
2434+
break;
2435+
23862436
case MSP_OSD_CHAR_WRITE:
23872437
if (dataSize >= 55) {
23882438
osdCharacter_t chr;

src/main/msp/msp_protocol.h

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -186,6 +186,9 @@
186186
#define MSP_TRANSPONDER_CONFIG 82 //out message Get transponder settings
187187
#define MSP_SET_TRANSPONDER_CONFIG 83 //in message Set transponder settings
188188

189+
#define MSP_OSD_CONFIG 84 //out message Get osd settings - betaflight
190+
#define MSP_SET_OSD_CONFIG 85 //in message Set osd settings - betaflight
191+
189192
#define MSP_OSD_CHAR_READ 86 //out message Get osd settings - betaflight
190193
#define MSP_OSD_CHAR_WRITE 87 //in message Set osd settings - betaflight
191194

0 commit comments

Comments
 (0)