Commit 94ab6fc9 authored by DonLakeFlyer's avatar DonLakeFlyer

Finish up follow me support

parent d3b1e88d
......@@ -1088,7 +1088,7 @@ void APMFirmwarePlugin::_handleRCChannelsRaw(Vehicle* vehicle, mavlink_message_t
void APMFirmwarePlugin::_sendGCSMotionReport(Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimationCapabilities)
{
if (vehicle->homePosition().isValid()) {
if (!vehicle->homePosition().isValid()) {
static bool sentOnce = false;
if (!sentOnce) {
sentOnce = true;
......
......@@ -43,7 +43,7 @@ APMCopterMode::APMCopterMode(uint32_t mode, bool settable) :
{ GUIDED_NOGPS, "Guided No GPS"},
{ SMART_RTL, "Smart RTL"},
{ FLOWHOLD, "Flow Hold" },
{ FOLLOW, "Follow Vehicle" },
{ FOLLOW, "Follow" },
{ ZIGZAG, "ZigZag" },
});
}
......@@ -136,3 +136,7 @@ bool ArduCopterFirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle*
return true;
}
void ArduCopterFirmwarePlugin::sendGCSMotionReport(Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities)
{
_sendGCSMotionReport(vehicle, motionReport, estimatationCapabilities);
}
......@@ -71,6 +71,7 @@ public:
bool vehicleYawsToNextWaypointInMission (const Vehicle* vehicle) const override;
QString autoDisarmParameter (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral("DISARM_DELAY"); }
bool supportsSmartRTL (void) const override { return true; }
void sendGCSMotionReport (Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities) override;
private:
static bool _remapParamNameIntialized;
......
......@@ -77,3 +77,8 @@ bool ArduRoverFirmwarePlugin::supportsNegativeThrust(Vehicle* /*vehicle*/)
{
return true;
}
void ArduRoverFirmwarePlugin::sendGCSMotionReport(Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities)
{
_sendGCSMotionReport(vehicle, motionReport, estimatationCapabilities);
}
......@@ -53,6 +53,7 @@ public:
bool supportsNegativeThrust (Vehicle *) final;
bool supportsSmartRTL (void) const override { return true; }
QString offlineEditingParamFile (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/APM/Rover.OfflineEditing.params"); }
void sendGCSMotionReport (Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities) override;
private:
static bool _remapParamNameIntialized;
......
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