mirror of https://github.com/ArduPilot/ardupilot
Plane: always instantiate AC_AttitudeControl_TS
This commit is contained in:
parent
24508f08dc
commit
dd7a860f23
|
@ -709,12 +709,7 @@ bool QuadPlane::setup(void)
|
|||
AP_BoardConfig::config_error("Unable to allocate %s", "ahrs_view");
|
||||
}
|
||||
|
||||
if (((frame_class == AP_Motors::MOTOR_FRAME_TAILSITTER) || (tailsitter.motor_mask != 0))
|
||||
&& (tilt.tilt_type != TILT_TYPE_BICOPTER)) {
|
||||
attitude_control = new AC_AttitudeControl_TS(*ahrs_view, aparm, *motors, loop_delta_t);
|
||||
} else {
|
||||
attitude_control = new AC_AttitudeControl_Multi(*ahrs_view, aparm, *motors, loop_delta_t);
|
||||
}
|
||||
attitude_control = new AC_AttitudeControl_TS(*ahrs_view, aparm, *motors, loop_delta_t);
|
||||
if (!attitude_control) {
|
||||
AP_BoardConfig::config_error("Unable to allocate %s", "attitude_control");
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue