mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AC_InputManager: removed create() method for objects
See discussion here: https://github.com/ArduPilot/ardupilot/issues/7331 we were getting some uninitialised variables. While it only showed up in AP_SbusOut, it means we can't be sure it won't happen on other objects, so safest to remove the approach Thanks to assistance from Lucas, Peter and Francisco
This commit is contained in:
parent
25b9a7e711
commit
25c409d4a2
@ -11,9 +11,10 @@
|
|||||||
/// @brief Class managing the pilot's control inputs
|
/// @brief Class managing the pilot's control inputs
|
||||||
class AC_InputManager{
|
class AC_InputManager{
|
||||||
public:
|
public:
|
||||||
static AC_InputManager create() { return AC_InputManager{}; }
|
AC_InputManager() {
|
||||||
|
// setup parameter defaults
|
||||||
constexpr AC_InputManager(AC_InputManager &&other) = default;
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
|
}
|
||||||
|
|
||||||
/* Do not allow copies */
|
/* Do not allow copies */
|
||||||
AC_InputManager(const AC_InputManager &other) = delete;
|
AC_InputManager(const AC_InputManager &other) = delete;
|
||||||
@ -23,11 +24,6 @@ public:
|
|||||||
void set_loop_rate(uint16_t loop_rate) { _loop_rate = loop_rate; }
|
void set_loop_rate(uint16_t loop_rate) { _loop_rate = loop_rate; }
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
AC_InputManager() {
|
|
||||||
// setup parameter defaults
|
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
|
||||||
}
|
|
||||||
|
|
||||||
// internal variables
|
// internal variables
|
||||||
uint16_t _loop_rate; // rate at which output() function is called (normally 400hz)
|
uint16_t _loop_rate; // rate at which output() function is called (normally 400hz)
|
||||||
|
|
||||||
|
@ -16,9 +16,13 @@
|
|||||||
/// @brief Class managing the pilot's control inputs for Conventional Helicopter
|
/// @brief Class managing the pilot's control inputs for Conventional Helicopter
|
||||||
class AC_InputManager_Heli : public AC_InputManager {
|
class AC_InputManager_Heli : public AC_InputManager {
|
||||||
public:
|
public:
|
||||||
static AC_InputManager_Heli create() { return AC_InputManager_Heli{}; }
|
// Constructor
|
||||||
|
AC_InputManager_Heli()
|
||||||
constexpr AC_InputManager_Heli(AC_InputManager_Heli &&other) = default;
|
: AC_InputManager()
|
||||||
|
{
|
||||||
|
// setup parameter defaults
|
||||||
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
|
}
|
||||||
|
|
||||||
/* Do not allow copies */
|
/* Do not allow copies */
|
||||||
AC_InputManager_Heli(const AC_InputManager_Heli &other) = delete;
|
AC_InputManager_Heli(const AC_InputManager_Heli &other) = delete;
|
||||||
@ -35,15 +39,6 @@ public:
|
|||||||
|
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
protected:
|
|
||||||
// Constructor
|
|
||||||
AC_InputManager_Heli()
|
|
||||||
: AC_InputManager()
|
|
||||||
{
|
|
||||||
// setup parameter defaults
|
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
|
||||||
}
|
|
||||||
|
|
||||||
private:
|
private:
|
||||||
struct InputManagerHeliFlags {
|
struct InputManagerHeliFlags {
|
||||||
uint8_t use_stab_col : 1; // 1 if we should use Stabilise mode collective range, 0 for Acro range
|
uint8_t use_stab_col : 1; // 1 if we should use Stabilise mode collective range, 0 for Acro range
|
||||||
|
Loading…
Reference in New Issue
Block a user