RC_Channel: avoid nullptr dereference on bad rcmap value entry

This commit is contained in:
Peter Barker 2024-09-08 00:05:57 +10:00 committed by Peter Barker
parent d6386cc1fd
commit 9cbb494092
2 changed files with 43 additions and 0 deletions

View File

@ -612,6 +612,12 @@ public:
// get failsafe timeout in milliseconds // get failsafe timeout in milliseconds
uint32_t get_fs_timeout_ms() const { return MAX(_fs_timeout * 1000, 100); } uint32_t get_fs_timeout_ms() const { return MAX(_fs_timeout * 1000, 100); }
// methods which return RC input channels used for various axes.
RC_Channel &get_roll_channel();
RC_Channel &get_pitch_channel();
RC_Channel &get_yaw_channel();
RC_Channel &get_throttle_channel();
protected: protected:
void new_override_received() { void new_override_received() {
@ -653,6 +659,9 @@ private:
void set_aux_cached(RC_Channel::AUX_FUNC aux_fn, RC_Channel::AuxSwitchPos pos); void set_aux_cached(RC_Channel::AUX_FUNC aux_fn, RC_Channel::AuxSwitchPos pos);
#endif #endif
RC_Channel &get_rcmap_channel_nonnull(uint8_t rcmap_number);
RC_Channel dummy_rcchannel;
}; };
RC_Channels &rc(); RC_Channels &rc();

View File

@ -30,6 +30,7 @@ extern const AP_HAL::HAL& hal;
#include <AP_Math/AP_Math.h> #include <AP_Math/AP_Math.h>
#include <AP_Logger/AP_Logger.h> #include <AP_Logger/AP_Logger.h>
#include <AP_RCMapper/AP_RCMapper.h>
#include "RC_Channel.h" #include "RC_Channel.h"
@ -307,6 +308,39 @@ void RC_Channels::set_aux_cached(RC_Channel::AUX_FUNC aux_fn, RC_Channel::AuxSwi
} }
#endif // AP_SCRIPTING_ENABLED #endif // AP_SCRIPTING_ENABLED
#if AP_RCMAPPER_ENABLED
// these methods return an RC_Channel pointers based on values from
// AP_::rcmap(). The return value is guaranteed to be not-null to
// allow use of the pointer without checking it for null-ness. If an
// invalid option has been chosen somehow then the returned channel
// will be a dummy channel.
RC_Channel &RC_Channels::get_rcmap_channel_nonnull(uint8_t rcmap_number)
{
RC_Channel *ret = RC_Channels::rc_channel(rcmap_number-1);
if (ret != nullptr) {
return *ret;
}
return dummy_rcchannel;
}
RC_Channel &RC_Channels::get_roll_channel()
{
return get_rcmap_channel_nonnull(AP::rcmap()->roll());
};
RC_Channel &RC_Channels::get_pitch_channel()
{
return get_rcmap_channel_nonnull(AP::rcmap()->pitch());
};
RC_Channel &RC_Channels::get_throttle_channel()
{
return get_rcmap_channel_nonnull(AP::rcmap()->throttle());
};
RC_Channel &RC_Channels::get_yaw_channel()
{
return get_rcmap_channel_nonnull(AP::rcmap()->yaw());
};
#endif // AP_RCMAPPER_ENABLED
// singleton instance // singleton instance
RC_Channels *RC_Channels::_singleton; RC_Channels *RC_Channels::_singleton;