Commit 630f9e56 authored by DonLakeFlyer's avatar DonLakeFlyer

parent aece8fa6
...@@ -134,19 +134,6 @@ bool ArduCopterFirmwarePlugin::multiRotorXConfig(Vehicle* vehicle) ...@@ -134,19 +134,6 @@ bool ArduCopterFirmwarePlugin::multiRotorXConfig(Vehicle* vehicle)
return vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, "FRAME")->rawValue().toInt() != 0; return vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, "FRAME")->rawValue().toInt() != 0;
} }
bool ArduCopterFirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle* vehicle) const
{
if (vehicle->isOfflineEditingVehicle()) {
return FirmwarePlugin::vehicleYawsToNextWaypointInMission(vehicle);
} else {
if (vehicle->multiRotor() && vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, QStringLiteral("WP_YAW_BEHAVIOR"))) {
Fact* yawMode = vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("WP_YAW_BEHAVIOR"));
return yawMode && yawMode->rawValue().toInt() != 0;
}
}
return true;
}
#if 0 #if 0
// Follow me not ready for Stable // Follow me not ready for Stable
void ArduCopterFirmwarePlugin::sendGCSMotionReport(Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities) void ArduCopterFirmwarePlugin::sendGCSMotionReport(Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities)
......
...@@ -71,7 +71,6 @@ public: ...@@ -71,7 +71,6 @@ public:
QString landFlightMode (void) const override { return QStringLiteral("Land"); } QString landFlightMode (void) const override { return QStringLiteral("Land"); }
QString takeControlFlightMode (void) const override { return QStringLiteral("Loiter"); } QString takeControlFlightMode (void) const override { return QStringLiteral("Loiter"); }
QString followFlightMode (void) const override { return QStringLiteral("Follow"); } QString followFlightMode (void) const override { return QStringLiteral("Follow"); }
bool vehicleYawsToNextWaypointInMission (const Vehicle* vehicle) const override;
QString autoDisarmParameter (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral("DISARM_DELAY"); } QString autoDisarmParameter (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral("DISARM_DELAY"); }
bool supportsSmartRTL (void) const override { return true; } bool supportsSmartRTL (void) const override { return true; }
#if 0 #if 0
......
...@@ -698,11 +698,6 @@ QMap<QString, FactGroup*>* FirmwarePlugin::factGroups(void) { ...@@ -698,11 +698,6 @@ QMap<QString, FactGroup*>* FirmwarePlugin::factGroups(void) {
return nullptr; return nullptr;
} }
bool FirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle* vehicle) const
{
return vehicle->multiRotor() ? false : true;
}
bool FirmwarePlugin::_armVehicleAndValidate(Vehicle* vehicle) bool FirmwarePlugin::_armVehicleAndValidate(Vehicle* vehicle)
{ {
if (vehicle->armed()) { if (vehicle->armed()) {
......
...@@ -297,9 +297,6 @@ public: ...@@ -297,9 +297,6 @@ public:
/// Returns a pointer to a dictionary of firmware-specific FactGroups /// Returns a pointer to a dictionary of firmware-specific FactGroups
virtual QMap<QString, FactGroup*>* factGroups(void); virtual QMap<QString, FactGroup*>* factGroups(void);
/// @true: When flying a mission the vehicle is always facing towards the next waypoint
virtual bool vehicleYawsToNextWaypointInMission(const Vehicle* vehicle) const;
/// Returns the data needed to do battery consumption calculations /// Returns the data needed to do battery consumption calculations
/// @param[out] mAhBattery Battery milliamp-hours rating (0 for no battery data available) /// @param[out] mAhBattery Battery milliamp-hours rating (0 for no battery data available)
/// @param[out] hoverAmps Current draw in amps during hover /// @param[out] hoverAmps Current draw in amps during hover
......
...@@ -9,6 +9,11 @@ ...@@ -9,6 +9,11 @@
"comment": "MAV_CMD_NAV_LOITER_UNLIM", "comment": "MAV_CMD_NAV_LOITER_UNLIM",
"paramRemove": "3" "paramRemove": "3"
}, },
{
"id": 18,
"comment": "MAV_CMD_NAV_LOITER_TURNS",
"paramRemove": "1,2,3,4"
},
{ {
"id": 19, "id": 19,
"comment": "MAV_CMD_NAV_LOITER_TIME", "comment": "MAV_CMD_NAV_LOITER_TIME",
......
...@@ -501,10 +501,6 @@ void SimpleMissionItem::_rebuildNaNFacts(void) ...@@ -501,10 +501,6 @@ void SimpleMissionItem::_rebuildNaNFacts(void)
if (!firmwareVehicle) { if (!firmwareVehicle) {
firmwareVehicle = _controllerVehicle; firmwareVehicle = _controllerVehicle;
} }
bool hideWaypointHeading = (command == MAV_CMD_NAV_WAYPOINT || command == MAV_CMD_NAV_TAKEOFF) && (i == 4) && firmwareVehicle->firmwarePlugin()->vehicleYawsToNextWaypointInMission(firmwareVehicle);
if (hideWaypointHeading) {
continue;
}
Fact* paramFact = rgParamFacts[i-1]; Fact* paramFact = rgParamFacts[i-1];
FactMetaData* paramMetaData = rgParamMetaData[i-1]; FactMetaData* paramMetaData = rgParamMetaData[i-1];
......
...@@ -3835,11 +3835,6 @@ const QVariantList& Vehicle::staticCameraList() const ...@@ -3835,11 +3835,6 @@ const QVariantList& Vehicle::staticCameraList() const
return emptyList; return emptyList;
} }
bool Vehicle::vehicleYawsToNextWaypointInMission() const
{
return _firmwarePlugin->vehicleYawsToNextWaypointInMission(this);
}
void Vehicle::_setupAutoDisarmSignalling() void Vehicle::_setupAutoDisarmSignalling()
{ {
QString param = _firmwarePlugin->autoDisarmParameter(this); QString param = _firmwarePlugin->autoDisarmParameter(this);
......
...@@ -1125,9 +1125,6 @@ public: ...@@ -1125,9 +1125,6 @@ public:
QGCCameraManager* dynamicCameras () { return _cameras; } QGCCameraManager* dynamicCameras () { return _cameras; }
QString hobbsMeter (); QString hobbsMeter ();
/// @true: When flying a mission the vehicle is always facing towards the next waypoint
bool vehicleYawsToNextWaypointInMission() const;
/// The vehicle is responsible for making the initial request for the Plan. /// The vehicle is responsible for making the initial request for the Plan.
/// @return: true: initial request is complete, false: initial request is still in progress; /// @return: true: initial request is complete, false: initial request is still in progress;
bool initialPlanRequestComplete() const { return _initialPlanRequestComplete; } bool initialPlanRequestComplete() const { return _initialPlanRequestComplete; }
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment