Plane: 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 8ab0ac8a16
commit 30e224e705
4 changed files with 56 additions and 68 deletions

View File

@ -8,18 +8,19 @@
class AP_Arming_Plane : public AP_Arming
{
public:
AP_Arming_Plane(const AP_AHRS &ahrs_ref, const AP_Baro &baro, Compass &compass,
const AP_BattMonitor &battery)
: AP_Arming(ahrs_ref, baro, compass, battery)
{
AP_Param::setup_object_defaults(this, var_info);
}
enum ArmingRudder {
ARMING_RUDDER_DISABLED = 0,
ARMING_RUDDER_ARMONLY = 1,
ARMING_RUDDER_ARMDISARM = 2
};
static AP_Arming_Plane create(const AP_AHRS &ahrs_ref, const AP_Baro &baro, Compass &compass, const AP_BattMonitor &battery) {
return AP_Arming_Plane{ahrs_ref, baro, compass, battery};
}
constexpr AP_Arming_Plane(AP_Arming_Plane &&other) = default;
/* Do not allow copies */
AP_Arming_Plane(const AP_Arming_Plane &other) = delete;
AP_Arming_Plane &operator=(const AP_Baro&) = delete;
@ -32,13 +33,6 @@ public:
static const struct AP_Param::GroupInfo var_info[];
protected:
AP_Arming_Plane(const AP_AHRS &ahrs_ref, const AP_Baro &baro, Compass &compass,
const AP_BattMonitor &battery)
: AP_Arming(ahrs_ref, baro, compass, battery)
{
AP_Param::setup_object_defaults(this, var_info);
}
bool ins_checks(bool report);
enum HomeState home_status() const override;

View File

@ -24,7 +24,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
constructor for main Plane class
*/
Plane::Plane(void)
: DataFlash(DataFlash_Class::create(fwver.fw_string, g.log_bitmask))
: DataFlash(fwver.fw_string, g.log_bitmask)
{
// C++11 doesn't allow in-class initialisation of bitfields
auto_state.takeoff_complete = true;

View File

@ -166,17 +166,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;
// board specific config for CAN bus
#if HAL_WITH_UAVCAN
AP_BoardConfig_CAN BoardConfig_CAN = AP_BoardConfig_CAN::create();
AP_BoardConfig_CAN BoardConfig_CAN;
#endif
// primary input channels
@ -186,7 +186,7 @@ private:
RC_Channel *channel_rudder;
// notification object for LEDs, buzzers etc (parameter set to false disables external leds)
AP_Notify notify = AP_Notify::create();
AP_Notify notify;
DataFlash_Class DataFlash;
@ -195,39 +195,39 @@ private:
int32_t pitch_limit_min_cd;
// Sensors
AP_GPS gps = AP_GPS::create();
AP_GPS gps;
// flight modes convenience array
AP_Int8 *flight_modes = &g.flight_mode1;
AP_Baro barometer = AP_Baro::create();
Compass compass = Compass::create();
AP_Baro barometer;
Compass compass;
AP_InertialSensor ins = AP_InertialSensor::create();
AP_InertialSensor ins;
RangeFinder rangefinder = RangeFinder::create(serial_manager, ROTATION_PITCH_270);
RangeFinder rangefinder{serial_manager, ROTATION_PITCH_270};
AP_Vehicle::FixedWing::Rangefinder_State rangefinder_state;
AP_RPM rpm_sensor = AP_RPM::create();
AP_RPM rpm_sensor;
// 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
AP_TECS TECS_controller = AP_TECS::create(ahrs, aparm, landing, g2.soaring_controller);
AP_L1_Control L1_controller = AP_L1_Control::create(ahrs, &TECS_controller);
AP_TECS TECS_controller{ahrs, aparm, landing, g2.soaring_controller};
AP_L1_Control L1_controller{ahrs, &TECS_controller};
// Attitude to servo controllers
AP_RollController rollController = AP_RollController::create(ahrs, aparm, DataFlash);
AP_PitchController pitchController = AP_PitchController::create(ahrs, aparm, DataFlash);
AP_YawController yawController = AP_YawController::create(ahrs, aparm);
AP_SteerController steerController = AP_SteerController::create(ahrs);
AP_RollController rollController{ahrs, aparm, DataFlash};
AP_PitchController pitchController{ahrs, aparm, DataFlash};
AP_YawController yawController{ahrs, aparm};
AP_SteerController steerController{ahrs};
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
SITL::SITL sitl;
@ -254,7 +254,7 @@ private:
// external failsafe boards during baro and airspeed calibration
bool in_calibration;
AP_SerialManager serial_manager = AP_SerialManager::create();
AP_SerialManager serial_manager;
// GCS selection
GCS_Plane _gcs; // avoid using this; use gcs()
@ -267,26 +267,26 @@ private:
AP_SpdHgtControl *SpdHgt_Controller = &TECS_controller;
// Relay
AP_Relay relay = AP_Relay::create();
AP_Relay relay;
// handle 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
#if OPTFLOW == ENABLED
// Optical flow sensor
OpticalFlow optflow = OpticalFlow::create(ahrs);
OpticalFlow optflow{ahrs};
#endif
// Rally Ponints
AP_Rally rally = AP_Rally::create(ahrs);
AP_Rally rally{ahrs};
// RSSI
AP_RSSI rssi = AP_RSSI::create();
AP_RSSI rssi;
// This is the state of the flight control system
// There are multiple states defined such as MANUAL, FBW-A, AUTO
@ -391,11 +391,11 @@ private:
int32_t altitude_error_cm;
// 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
// Variables for extended status MAVLink messages
@ -599,33 +599,33 @@ private:
float smoothed_airspeed;
// Mission library
AP_Mission mission = AP_Mission::create(ahrs,
AP_Mission mission{ahrs,
FUNCTOR_BIND_MEMBER(&Plane::start_command_callback, bool, const AP_Mission::Mission_Command &),
FUNCTOR_BIND_MEMBER(&Plane::verify_command_callback, bool, const AP_Mission::Mission_Command &),
FUNCTOR_BIND_MEMBER(&Plane::exit_mission_callback, void));
FUNCTOR_BIND_MEMBER(&Plane::exit_mission_callback, void)};
#if PARACHUTE == ENABLED
AP_Parachute parachute = AP_Parachute::create(relay);
AP_Parachute parachute{relay};
#endif
// terrain handling
#if AP_TERRAIN_AVAILABLE
AP_Terrain terrain = AP_Terrain::create(ahrs, mission, rally);
AP_Terrain terrain{ahrs, mission, rally};
#endif
AP_Landing landing = AP_Landing::create(mission,ahrs,SpdHgt_Controller,nav_controller,aparm,
FUNCTOR_BIND_MEMBER(&Plane::set_target_altitude_proportion, void, const Location&, float),
FUNCTOR_BIND_MEMBER(&Plane::constrain_target_altitude_location, void, const Location&, const Location&),
FUNCTOR_BIND_MEMBER(&Plane::adjusted_altitude_cm, int32_t),
FUNCTOR_BIND_MEMBER(&Plane::adjusted_relative_altitude_cm, int32_t),
FUNCTOR_BIND_MEMBER(&Plane::disarm_if_autoland_complete, void),
FUNCTOR_BIND_MEMBER(&Plane::update_flight_stage, void));
AP_Landing landing{mission,ahrs,SpdHgt_Controller,nav_controller,aparm,
FUNCTOR_BIND_MEMBER(&Plane::set_target_altitude_proportion, void, const Location&, float),
FUNCTOR_BIND_MEMBER(&Plane::constrain_target_altitude_location, void, const Location&, const Location&),
FUNCTOR_BIND_MEMBER(&Plane::adjusted_altitude_cm, int32_t),
FUNCTOR_BIND_MEMBER(&Plane::adjusted_relative_altitude_cm, int32_t),
FUNCTOR_BIND_MEMBER(&Plane::disarm_if_autoland_complete, void),
FUNCTOR_BIND_MEMBER(&Plane::update_flight_stage, void)};
AP_ADSB adsb = AP_ADSB::create(ahrs);
AP_ADSB adsb{ahrs};
// avoidance of adsb enabled vehicles (normally manned vheicles)
AP_Avoidance_Plane avoidance_adsb = AP_Avoidance_Plane::create(ahrs, adsb);
AP_Avoidance_Plane avoidance_adsb{ahrs, adsb};
// Outback Challenge Failsafe Support
AP_AdvancedFailsafe_Plane afs {mission, barometer, gps, rcmap};
@ -768,11 +768,11 @@ private:
// 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
// Arming/Disarming mangement class
AP_Arming_Plane arming = AP_Arming_Plane::create(ahrs, barometer, compass, battery);
AP_Arming_Plane arming{ahrs, barometer, compass, battery};
AP_Param param_loader {var_info};

View File

@ -8,22 +8,16 @@
// functionality - for example, not doing anything while landed.
class AP_Avoidance_Plane : public AP_Avoidance {
public:
static AP_Avoidance_Plane create(AP_AHRS &ahrs, class AP_ADSB &adsb) {
return AP_Avoidance_Plane{ahrs, adsb};
AP_Avoidance_Plane(AP_AHRS &ahrs, class AP_ADSB &adsb)
: AP_Avoidance(ahrs, adsb)
{
}
constexpr AP_Avoidance_Plane(AP_Avoidance_Plane &&other) = default;
/* Do not allow copies */
AP_Avoidance_Plane(const AP_Avoidance_Plane &other) = delete;
AP_Avoidance_Plane &operator=(const AP_Avoidance_Plane&) = delete;
protected:
AP_Avoidance_Plane(AP_AHRS &ahrs, class AP_ADSB &adsb)
: AP_Avoidance(ahrs, adsb)
{
}
// override avoidance handler
MAV_COLLISION_ACTION handle_avoidance(const AP_Avoidance::Obstacle *obstacle, MAV_COLLISION_ACTION requested_action) override;