AP_BoardConfig: 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:
Andrew Tridgell 2017-12-13 12:06:11 +11:00
parent ca91edbbeb
commit a4d2d79ce7
2 changed files with 6 additions and 15 deletions

View File

@ -9,9 +9,9 @@ extern "C" typedef int (*main_fn_t)(int argc, char **);
class AP_BoardConfig {
public:
static AP_BoardConfig create() { return AP_BoardConfig{}; }
constexpr AP_BoardConfig(AP_BoardConfig &&other) = default;
AP_BoardConfig() {
AP_Param::setup_object_defaults(this, var_info);
};
/* Do not allow copies */
AP_BoardConfig(const AP_BoardConfig &other) = delete;
@ -70,10 +70,6 @@ public:
#endif
private:
AP_BoardConfig() {
AP_Param::setup_object_defaults(this, var_info);
};
AP_Int16 vehicleSerialNumber;
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN

View File

@ -11,9 +11,9 @@
class AP_BoardConfig_CAN {
public:
static AP_BoardConfig_CAN create() { return AP_BoardConfig_CAN{}; }
constexpr AP_BoardConfig_CAN(AP_BoardConfig_CAN &&other) = default;
AP_BoardConfig_CAN() {
AP_Param::setup_object_defaults(this, var_info);
};
/* Do not allow copies */
AP_BoardConfig_CAN(const AP_BoardConfig_CAN &other) = delete;
@ -98,10 +98,5 @@ public:
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
void px4_setup_canbus(void);
#endif // HAL_BOARD_PX4 || HAL_BOARD_VRBRAIN
private:
AP_BoardConfig_CAN() {
AP_Param::setup_object_defaults(this, var_info);
};
};
#endif