Browse Source

allow follow to work with ardupilot copter and rover (#10187)

QGC4.4
Andrew Tridgell 3 years ago committed by GitHub
parent
commit
e3c4827e5b
  1. 18
      src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
  2. 10
      src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h
  3. 4
      src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc
  4. 6
      src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h

18
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc

@ -43,11 +43,12 @@ APMCopterMode::APMCopterMode(uint32_t mode, bool settable) :
{ GUIDED_NOGPS, "Guided No GPS"}, { GUIDED_NOGPS, "Guided No GPS"},
{ SMART_RTL, "Smart RTL"}, { SMART_RTL, "Smart RTL"},
{ FLOWHOLD, "Flow Hold" }, { FLOWHOLD, "Flow Hold" },
#if 0
// Follow me not ready for Stable
{ FOLLOW, "Follow" }, { FOLLOW, "Follow" },
#endif
{ ZIGZAG, "ZigZag" }, { ZIGZAG, "ZigZag" },
{ SYSTEMID, "SystemID" },
{ AUTOROTATE, "AutoRotate" },
{ AUTO_RTL, "AutoRTL" },
{ TURTLE, "Turtle" },
}); });
} }
@ -74,11 +75,13 @@ ArduCopterFirmwarePlugin::ArduCopterFirmwarePlugin(void)
APMCopterMode(APMCopterMode::GUIDED_NOGPS, true), APMCopterMode(APMCopterMode::GUIDED_NOGPS, true),
APMCopterMode(APMCopterMode::SMART_RTL, true), APMCopterMode(APMCopterMode::SMART_RTL, true),
APMCopterMode(APMCopterMode::FLOWHOLD, true), APMCopterMode(APMCopterMode::FLOWHOLD, true),
#if 0
// Follow me not ready for Stable
APMCopterMode(APMCopterMode::FOLLOW, true), APMCopterMode(APMCopterMode::FOLLOW, true),
#endif
APMCopterMode(APMCopterMode::ZIGZAG, true), APMCopterMode(APMCopterMode::ZIGZAG, true),
APMCopterMode(APMCopterMode::ZIGZAG, true),
APMCopterMode(APMCopterMode::SYSTEMID, true),
APMCopterMode(APMCopterMode::AUTOROTATE, true),
APMCopterMode(APMCopterMode::AUTO_RTL, true),
APMCopterMode(APMCopterMode::TURTLE, true),
}); });
if (!_remapParamNameIntialized) { if (!_remapParamNameIntialized) {
@ -134,10 +137,7 @@ 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;
} }
#if 0
// 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)
{ {
_sendGCSMotionReport(vehicle, motionReport, estimatationCapabilities); _sendGCSMotionReport(vehicle, motionReport, estimatationCapabilities);
} }
#endif

10
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h

@ -43,11 +43,12 @@ public:
GUIDED_NOGPS= 20, GUIDED_NOGPS= 20,
SMART_RTL = 21, // SMART_RTL returns to home by retracing its steps SMART_RTL = 21, // SMART_RTL returns to home by retracing its steps
FLOWHOLD = 22, // FLOWHOLD holds position with optical flow without rangefinder FLOWHOLD = 22, // FLOWHOLD holds position with optical flow without rangefinder
#if 0
// Follow me not ready for Stable
FOLLOW = 23, // follow attempts to follow another vehicle or ground station FOLLOW = 23, // follow attempts to follow another vehicle or ground station
#endif
ZIGZAG = 24, // ZIGZAG mode is able to fly in a zigzag manner with predefined point A and point B ZIGZAG = 24, // ZIGZAG mode is able to fly in a zigzag manner with predefined point A and point B
SYSTEMID = 25,
AUTOROTATE = 26,
AUTO_RTL = 27,
TURTLE = 28,
}; };
APMCopterMode(uint32_t mode, bool settable); APMCopterMode(uint32_t mode, bool settable);
@ -73,10 +74,7 @@ public:
QString followFlightMode (void) const override { return QStringLiteral("Follow"); } QString followFlightMode (void) const override { return QStringLiteral("Follow"); }
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
// Follow me not ready for Stable
void sendGCSMotionReport (Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities) override; void sendGCSMotionReport (Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities) override;
#endif
private: private:
static bool _remapParamNameIntialized; static bool _remapParamNameIntialized;

4
src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc

@ -81,10 +81,8 @@ bool ArduRoverFirmwarePlugin::supportsNegativeThrust(Vehicle* /*vehicle*/)
return true; return true;
} }
#if 0
// Follow me not ready for Stable
void ArduRoverFirmwarePlugin::sendGCSMotionReport(Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities) void ArduRoverFirmwarePlugin::sendGCSMotionReport(Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities)
{ {
_sendGCSMotionReport(vehicle, motionReport, estimatationCapabilities); _sendGCSMotionReport(vehicle, motionReport, estimatationCapabilities);
} }
#endif

6
src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h

@ -25,10 +25,7 @@ public:
STEERING = 3, STEERING = 3,
HOLD = 4, HOLD = 4,
LOITER = 5, LOITER = 5,
#if 0
// Follow me not ready for Stable
FOLLOW = 6, FOLLOW = 6,
#endif
SIMPLE = 7, SIMPLE = 7,
AUTO = 10, AUTO = 10,
RTL = 11, RTL = 11,
@ -56,10 +53,7 @@ public:
bool supportsNegativeThrust (Vehicle *) final; bool supportsNegativeThrust (Vehicle *) final;
bool supportsSmartRTL (void) const override { return true; } bool supportsSmartRTL (void) const override { return true; }
QString offlineEditingParamFile (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/APM/Rover.OfflineEditing.params"); } QString offlineEditingParamFile (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/APM/Rover.OfflineEditing.params"); }
#if 0
// Follow me not ready for Stable
void sendGCSMotionReport (Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities) override; void sendGCSMotionReport (Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities) override;
#endif
private: private:
static bool _remapParamNameIntialized; static bool _remapParamNameIntialized;

Loading…
Cancel
Save