Rover: 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 a8a715d673
commit 482ae876fb
3 changed files with 32 additions and 38 deletions

View File

@ -8,12 +8,12 @@
class AP_Arming_Rover : public AP_Arming
{
public:
static AP_Arming_Rover create(const AP_AHRS &ahrs_ref, const AP_Baro &baro, Compass &compass, const AP_BattMonitor &battery) {
return AP_Arming_Rover{ahrs_ref, baro, compass, battery};
AP_Arming_Rover(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_Rover(AP_Arming_Rover &&other) = default;
/* Do not allow copies */
AP_Arming_Rover(const AP_Arming_Rover &other) = delete;
AP_Arming_Rover &operator=(const AP_Baro&) = delete;
@ -23,11 +23,5 @@ public:
bool gps_checks(bool display_failure) override;
protected:
AP_Arming_Rover(const AP_AHRS &ahrs_ref, const AP_Baro &baro, Compass &compass,
const AP_BattMonitor &battery)
: AP_Arming(ahrs_ref, baro, compass, battery)
{
}
enum HomeState home_status() const override;
};

View File

@ -27,7 +27,7 @@ Rover::Rover(void) :
channel_steer(nullptr),
channel_throttle(nullptr),
channel_aux(nullptr),
DataFlash(DataFlash_Class::create(fwver.fw_string, g.log_bitmask)),
DataFlash{fwver.fw_string, g.log_bitmask},
modes(&g.mode1),
nav_controller(&L1_controller),
control_mode(&mode_initializing),

View File

@ -133,17 +133,17 @@ private:
ParametersG2 g2;
// main loop scheduler
AP_Scheduler scheduler = AP_Scheduler::create();
AP_Scheduler scheduler;
// mapping between input channels
RCMapper rcmap = RCMapper::create();
RCMapper rcmap;
// 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
// primary control channels
@ -154,11 +154,11 @@ private:
DataFlash_Class DataFlash;
// sensor drivers
AP_GPS gps = AP_GPS::create();
AP_Baro barometer = AP_Baro::create();
Compass compass = Compass::create();
AP_InertialSensor ins = AP_InertialSensor::create();
RangeFinder rangefinder = RangeFinder::create(serial_manager, ROTATION_NONE);
AP_GPS gps;
AP_Baro barometer;
Compass compass;
AP_InertialSensor ins;
RangeFinder rangefinder{serial_manager, ROTATION_NONE};
AP_Button button;
// flight modes convenience array
@ -166,61 +166,61 @@ private:
// Inertial Navigation EKF
#if AP_AHRS_NAVEKF_AVAILABLE
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);
NavEKF2 EKF2{&ahrs, barometer, rangefinder};
NavEKF3 EKF3{&ahrs, barometer, rangefinder};
AP_AHRS_NavEKF ahrs{ins, barometer, gps, EKF2, EKF3};
#else
AP_AHRS_DCM ahrs = AP_AHRS_DCM::create(ins, barometer, gps);
AP_AHRS_DCM ahrs{ins, barometer, gps};
#endif
// Arming/Disarming management class
AP_Arming_Rover arming = AP_Arming_Rover::create(ahrs, barometer, compass, battery);
AP_Arming_Rover arming{ahrs, barometer, compass, battery};
AP_L1_Control L1_controller = AP_L1_Control::create(ahrs, nullptr);
AP_L1_Control L1_controller{ahrs, nullptr};
// selected navigation controller
AP_Navigation *nav_controller;
// Mission library
AP_Mission mission = AP_Mission::create(ahrs,
AP_Mission mission{ahrs,
FUNCTOR_BIND_MEMBER(&Rover::start_command, bool, const AP_Mission::Mission_Command&),
FUNCTOR_BIND_MEMBER(&Rover::verify_command_callback, bool, const AP_Mission::Mission_Command&),
FUNCTOR_BIND_MEMBER(&Rover::exit_mission, void));
FUNCTOR_BIND_MEMBER(&Rover::exit_mission, void)};
#if AP_AHRS_NAVEKF_AVAILABLE
OpticalFlow optflow = OpticalFlow::create(ahrs);
OpticalFlow optflow{ahrs};
#endif
// RSSI
AP_RSSI rssi = AP_RSSI::create();
AP_RSSI rssi;
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
SITL::SITL sitl;
#endif
AP_SerialManager serial_manager = AP_SerialManager::create();
AP_SerialManager serial_manager;
// GCS handling
GCS_Rover _gcs; // avoid using this; use gcs()
GCS_Rover &gcs() { return _gcs; }
// relay support
AP_Relay relay = AP_Relay::create();
AP_Relay relay;
AP_ServoRelayEvents ServoRelayEvents = AP_ServoRelayEvents::create(relay);
AP_ServoRelayEvents ServoRelayEvents{relay};
// The rover's current location
struct Location current_loc;
// 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 solution for altitude rather than gps only.
AP_Mount camera_mount = AP_Mount::create(ahrs, current_loc);
AP_Mount camera_mount{ahrs, current_loc};
#endif
// true if initialisation has completed
@ -258,7 +258,7 @@ private:
} failsafe;
// notification object for LEDs, buzzers etc (parameter set to false disables external leds)
AP_Notify notify = AP_Notify::create();
AP_Notify notify;
// true if we have a position estimate from AHRS
bool have_position;
@ -289,11 +289,11 @@ private:
aux_switch_pos aux_ch7;
// Battery Sensors
AP_BattMonitor battery = AP_BattMonitor::create();
AP_BattMonitor battery;
#if FRSKY_TELEM_ENABLED == ENABLED
// FrSky telemetry support
AP_Frsky_Telem frsky_telemetry = AP_Frsky_Telem::create(ahrs, battery, rangefinder);
AP_Frsky_Telem frsky_telemetry{ahrs, battery, rangefinder};
#endif
uint32_t control_sensors_present;