29#ifndef QGC_NO_SERIAL_LINK
41#ifndef QGC_NO_SERIAL_LINK
57 _components.append(QVariant::fromValue(qobject_cast<VehicleComponent*>(
_airframeComponent)));
62 _components.append(QVariant::fromValue(qobject_cast<VehicleComponent*>(
_radioComponent)));
74 _components.append(QVariant::fromValue(qobject_cast<VehicleComponent*>(
_sensorsComponent)));
78 _components.append(QVariant::fromValue(qobject_cast<VehicleComponent*>(
_powerComponent)));
83 _components.append(QVariant::fromValue(qobject_cast<VehicleComponent*>(
_motorComponent)));
88 _components.append(QVariant::fromValue(qobject_cast<VehicleComponent*>(
_safetyComponent)));
95 _components.append(QVariant::fromValue(qobject_cast<VehicleComponent*>(
_followComponent)));
102 _components.append(QVariant::fromValue(qobject_cast<VehicleComponent*>(
_heliComponent)));
107 _components.append(QVariant::fromValue(qobject_cast<VehicleComponent*>(
_tuningComponent)));
111 _components.append(QVariant::fromValue(qobject_cast<VehicleComponent*>(
_gimbalComponent)));
116 _components.append(QVariant::fromValue(qobject_cast<VehicleComponent*>(
_lightsComponent)));
121 _components.append(QVariant::fromValue(qobject_cast<VehicleComponent*>(
_subFrameComponent)));
129 _components.append(QVariant::fromValue(qobject_cast<VehicleComponent*>(
_esp8266Component)));
138 _components.append(QVariant::fromValue(qobject_cast<VehicleComponent*>(
_joystickComponent)));
142 _components.append(QVariant::fromValue(qobject_cast<VehicleComponent*>(
_scriptingComponent)));
144 qCWarning(APMAutoPilotPluginLog) <<
"Call to vehicleComponents prior to parametersReady";
153 bool requiresAirframeCheck =
false;
155 if (qobject_cast<const APMFlightModesComponent*>(component)) {
162 requiresAirframeCheck =
true;
163 }
else if (qobject_cast<const APMRadioComponent*>(component)) {
164 requiresAirframeCheck =
true;
165 }
else if (qobject_cast<const APMPowerComponent*>(component)) {
166 requiresAirframeCheck =
true;
167 }
else if (qobject_cast<const APMSafetyComponent*>(component)) {
168 requiresAirframeCheck =
true;
169 }
else if (qobject_cast<const APMTuningComponent*>(component)) {
170 requiresAirframeCheck =
true;
171 }
else if (qobject_cast<const APMSensorsComponent*>(component)) {
172 requiresAirframeCheck =
true;
175 if (requiresAirframeCheck) {
184#ifndef QGC_NO_SERIAL_LINK
185void APMAutoPilotPlugin::_checkForBadCubeBlack(
bool parametersReady)
187 if (!parametersReady) {
196 if (sharedLink->linkConfiguration()->type() != LinkConfiguration::TypeSerial) {
200 const SerialLink *serialLink = qobject_cast<const SerialLink*>(sharedLink.get());
211 static const QString paramAcc3 = QStringLiteral(
"INS_ACC3_ID");
212 static const QString paramGyr3 = QStringLiteral(
"INS_GYR3_ID");
213 static const QString paramEnableMask = QStringLiteral(
"INS_ENABLE_MASK");
218 qgcApp()->showAppMessage(tr(
219 "WARNING: The flight board you are using has a critical service bulletin against it which advises against flying. "
220 "For details see: https://discuss.cubepilot.org/t/sb-0000002-critical-service-bulletin-for-cubes-purchased-between-january-2019-to-present-do-not-fly/406"
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
#define QGC_LOGGING_CATEGORY(name, categoryStr)
QString name() const final
bool setupComplete() const final
This is the AutoPilotPlugin implementation for the MAV_AUTOPILOT_ARDUPILOT type.
QString prerequisiteSetup(VehicleComponent *component) const override
Returns the name of the vehicle component which must complete setup prior to this one....
ScriptingComponent * _scriptingComponent
APMAirframeComponent * _airframeComponent
APMHeliComponent * _heliComponent
const QVariantList & vehicleComponents() override
APMRadioComponent * _radioComponent
APMFlightModesComponent * _flightModesComponent
APMSafetyComponent * _safetyComponent
APMMotorComponent * _motorComponent
APMLightsComponent * _lightsComponent
APMFollowComponent * _followComponent
APMTuningComponent * _tuningComponent
ESP8266Component * _esp8266Component
JoystickComponent * _joystickComponent
APMGimbalComponent * _gimbalComponent
APMSensorsComponent * _sensorsComponent
APMPowerComponent * _powerComponent
bool _incorrectParameterVersion
true: parameter version incorrect, setup not allowed
APMRemoteSupportComponent * _apmRemoteSupportComponent
APMSubFrameComponent * _subFrameComponent
bool setupComplete() const final
QString name() const final
bool parameterExists(int componentId, const QString ¶mName) const
Fact * getParameter(int componentId, const QString ¶mName)
void parametersReadyChanged(bool parametersReady)
bool parametersReady() const
const QSerialPort * port() const
WeakLinkInterfacePtr primaryLink() const
MAV_TYPE vehicleType() const
VehicleLinkManager * vehicleLinkManager()
FirmwarePlugin * firmwarePlugin()
Provides access to the Firmware Plugin for this Vehicle.
ParameterManager * parameterManager()
VehicleSupports * supports()
int versionCompare(const QString &compare) const
Used to check if running current version is equal or higher than the one being compared.