From 154229006af3836da399fe7a2a5bbd9e8de2a958 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 9 Sep 2024 09:53:08 +1000 Subject: [PATCH] AP_MSP: avoid nullptr dereference on bad rcmap --- libraries/AP_MSP/AP_MSP_Telem_Backend.cpp | 19 ++++--------------- 1 file changed, 4 insertions(+), 15 deletions(-) diff --git a/libraries/AP_MSP/AP_MSP_Telem_Backend.cpp b/libraries/AP_MSP/AP_MSP_Telem_Backend.cpp index 4f22e6e42d..84cca6e136 100644 --- a/libraries/AP_MSP/AP_MSP_Telem_Backend.cpp +++ b/libraries/AP_MSP/AP_MSP_Telem_Backend.cpp @@ -25,7 +25,6 @@ #include #include #include -#include #include #include #include @@ -1068,17 +1067,10 @@ MSPCommandResult AP_MSP_Telem_Backend::msp_process_out_rtc(sbuf_t *dst) #if AP_RC_CHANNEL_ENABLED MSPCommandResult AP_MSP_Telem_Backend::msp_process_out_rc(sbuf_t *dst) { -#if AP_RCMAPPER_ENABLED - const RCMapper* rcmap = AP::rcmap(); - if (rcmap == nullptr) { - return MSP_RESULT_ERROR; - } - - // note: rcmap channels start at 1 - float roll = rc().rc_channel(rcmap->roll()-1)->norm_input_dz(); - float pitch = -rc().rc_channel(rcmap->pitch()-1)->norm_input_dz(); - float yaw = rc().rc_channel(rcmap->yaw()-1)->norm_input_dz(); - float throttle = rc().rc_channel(rcmap->throttle()-1)->norm_input_dz(); + float roll = rc().get_roll_channel().norm_input_dz(); + float pitch = -rc().get_pitch_channel().norm_input_dz(); + float yaw = rc().get_yaw_channel().norm_input_dz(); + float throttle = rc().get_throttle_channel().norm_input_dz(); const struct PACKED { uint16_t a; @@ -1095,9 +1087,6 @@ MSPCommandResult AP_MSP_Telem_Backend::msp_process_out_rc(sbuf_t *dst) sbuf_write_data(dst, &rc, sizeof(rc)); return MSP_RESULT_ACK; -#else - return MSP_RESULT_ERROR; -#endif } #endif // AP_RC_CHANNEL_ENABLED