Sub: 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:15 +11:00
parent 30e224e705
commit 4c9f48244e
3 changed files with 35 additions and 41 deletions

View File

@ -4,12 +4,12 @@
class AP_Arming_Sub : public AP_Arming {
public:
static AP_Arming_Sub create(const AP_AHRS &ahrs_ref, const AP_Baro &baro, Compass &compass, const AP_BattMonitor &battery) {
return AP_Arming_Sub{ahrs_ref, baro, compass, battery};
AP_Arming_Sub(const AP_AHRS &ahrs_ref, const AP_Baro &baro, Compass &compass,
const AP_BattMonitor &battery)
: AP_Arming(ahrs_ref, baro, compass, battery)
{
}
constexpr AP_Arming_Sub(AP_Arming_Sub &&other) = default;
/* Do not allow copies */
AP_Arming_Sub(const AP_Arming_Sub &other) = delete;
AP_Arming_Sub &operator=(const AP_Baro&) = delete;
@ -18,12 +18,6 @@ public:
bool pre_arm_checks(bool report) override;
protected:
AP_Arming_Sub(const AP_AHRS &ahrs_ref, const AP_Baro &baro, Compass &compass,
const AP_BattMonitor &battery)
: AP_Arming(ahrs_ref, baro, compass, battery)
{
}
bool ins_checks(bool report) override;
enum HomeState home_status() const override;
};

View File

@ -24,7 +24,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
constructor for main Sub class
*/
Sub::Sub(void)
: DataFlash(DataFlash_Class::create(fwver.fw_string, g.log_bitmask)),
: DataFlash(fwver.fw_string, g.log_bitmask),
control_mode(MANUAL),
motors(MAIN_LOOP_RATE),
scaleLongDown(1),

View File

@ -146,10 +146,10 @@ private:
ParametersG2 g2;
// main loop scheduler
AP_Scheduler scheduler = AP_Scheduler::create();
AP_Scheduler scheduler;
// AP_Notify instance
AP_Notify notify = AP_Notify::create();
AP_Notify notify;
// primary input control channels
RC_Channel *channel_roll;
@ -162,16 +162,16 @@ private:
// Dataflash
DataFlash_Class DataFlash;
AP_GPS gps = AP_GPS::create();
AP_GPS gps;
AP_LeakDetector leak_detector = AP_LeakDetector::create();
AP_LeakDetector leak_detector;
TSYS01 celsius;
AP_Baro barometer = AP_Baro::create();
Compass compass = Compass::create();
AP_InertialSensor ins = AP_InertialSensor::create();
AP_Baro barometer;
Compass compass;
AP_InertialSensor ins;
RangeFinder rangefinder = RangeFinder::create(serial_manager, ROTATION_PITCH_270);
RangeFinder rangefinder{serial_manager, ROTATION_PITCH_270};
struct {
bool enabled:1;
bool alt_healthy:1; // true if we can trust the altitude from the rangefinder
@ -181,27 +181,27 @@ private:
} rangefinder_state = { false, false, 0, 0 };
#if RPM_ENABLED == ENABLED
AP_RPM rpm_sensor = AP_RPM::create();
AP_RPM rpm_sensor;
#endif
// Inertial Navigation EKF
NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, rangefinder);
NavEKF3 EKF3 = NavEKF3::create(&ahrs, barometer, rangefinder);
AP_AHRS_NavEKF ahrs = AP_AHRS_NavEKF::create(ins, barometer, gps, EKF2, EKF3, AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF);
NavEKF2 EKF2{&ahrs, barometer, rangefinder};
NavEKF3 EKF3{&ahrs, barometer, rangefinder};
AP_AHRS_NavEKF ahrs{ins, barometer, gps, EKF2, EKF3, AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF};
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
SITL::SITL sitl;
#endif
// Mission library
AP_Mission mission = AP_Mission::create(ahrs,
AP_Mission mission{ahrs,
FUNCTOR_BIND_MEMBER(&Sub::start_command, bool, const AP_Mission::Mission_Command &),
FUNCTOR_BIND_MEMBER(&Sub::verify_command_callback, bool, const AP_Mission::Mission_Command &),
FUNCTOR_BIND_MEMBER(&Sub::exit_mission, void));
FUNCTOR_BIND_MEMBER(&Sub::exit_mission, void)};
// Optical flow sensor
#if OPTFLOW == ENABLED
OpticalFlow optflow = OpticalFlow::create(ahrs);
OpticalFlow optflow{ahrs};
#endif
// gnd speed limit required to observe optical flow sensor limits
@ -213,7 +213,7 @@ private:
// system time in milliseconds of last recorded yaw reset from ekf
uint32_t ekfYawReset_ms = 0;
AP_SerialManager serial_manager = AP_SerialManager::create();
AP_SerialManager serial_manager;
// GCS selection
GCS_Sub _gcs; // avoid using this; use gcs()
@ -252,15 +252,15 @@ private:
mode_reason_t prev_control_mode_reason = MODE_REASON_UNKNOWN;
#if RCMAP_ENABLED == ENABLED
RCMapper rcmap = RCMapper::create();
RCMapper rcmap;
#endif
// board specific config
AP_BoardConfig BoardConfig = AP_BoardConfig::create();
AP_BoardConfig BoardConfig;
#if HAL_WITH_UAVCAN
// board specific config for CAN bus
AP_BoardConfig_CAN BoardConfig_CAN = AP_BoardConfig_CAN::create();
AP_BoardConfig_CAN BoardConfig_CAN;
#endif
// Failsafe
@ -327,9 +327,9 @@ private:
uint32_t nav_delay_time_start;
// Battery Sensors
AP_BattMonitor battery = AP_BattMonitor::create();
AP_BattMonitor battery;
AP_Arming_Sub arming = AP_Arming_Sub::create(ahrs, barometer, compass, battery);
AP_Arming_Sub arming{ahrs, barometer, compass, battery};
// Altitude
// The cm/s we are moving up or down based on filtered data - Positive = UP
@ -347,7 +347,7 @@ private:
bool input_hold_engaged;
// loop performance monitoring:
AP::PerfInfo perf_info = AP::PerfInfo::create();
AP::PerfInfo perf_info;
// 3D Location vectors
// Current location of the Sub (altitude is relative to home)
@ -408,39 +408,39 @@ private:
uint16_t mainLoop_count;
// Reference to the relay object
AP_Relay relay = AP_Relay::create();
AP_Relay relay;
// handle repeated servo and relay events
AP_ServoRelayEvents ServoRelayEvents = AP_ServoRelayEvents::create(relay);
AP_ServoRelayEvents ServoRelayEvents{relay};
// Camera
#if CAMERA == ENABLED
AP_Camera camera = AP_Camera::create(&relay, MASK_LOG_CAMERA, current_loc, ahrs);
AP_Camera camera{&relay, MASK_LOG_CAMERA, current_loc, ahrs};
#endif
// Camera/Antenna mount tracking and stabilisation stuff
#if MOUNT == ENABLED
// current_loc uses the baro/gps soloution for altitude rather than gps only.
AP_Mount camera_mount = AP_Mount::create(ahrs, current_loc);
AP_Mount camera_mount{ahrs, current_loc};
#endif
// AC_Fence library to reduce fly-aways
#if AC_FENCE == ENABLED
AC_Fence fence = AC_Fence::create(ahrs);
AC_Fence fence{ahrs};
#endif
#if AVOIDANCE_ENABLED == ENABLED
AC_Avoid avoid = AC_Avoid::create(ahrs, inertial_nav, fence, g2.proximity, &g2.beacon);
AC_Avoid avoid{ahrs, inertial_nav, fence, g2.proximity, &g2.beacon};
#endif
// Rally library
#if AC_RALLY == ENABLED
AP_Rally rally = AP_Rally::create(ahrs);
AP_Rally rally{ahrs};
#endif
// terrain handling
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
AP_Terrain terrain = AP_Terrain::create(ahrs, mission, rally);
AP_Terrain terrain{ahrs, mission, rally};
#endif
// use this to prevent recursion during sensor init