mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-25 10:08:28 -04:00
Along track fix for negative.
This commit is contained in:
parent
28b835713a
commit
fbbf1aa4a2
@ -196,10 +196,13 @@ float AP_MavlinkCommand::crossTrack(const AP_MavlinkCommand & previous,
|
|||||||
// calculates along track distance of a current location
|
// calculates along track distance of a current location
|
||||||
float AP_MavlinkCommand::alongTrack(const AP_MavlinkCommand & previous,
|
float AP_MavlinkCommand::alongTrack(const AP_MavlinkCommand & previous,
|
||||||
int32_t lat_degInt, int32_t lon_degInt) const {
|
int32_t lat_degInt, int32_t lon_degInt) const {
|
||||||
// ignores lat/lon since single prec.
|
|
||||||
float dXt = crossTrack(previous,lat_degInt,lon_degInt);
|
float dXt = crossTrack(previous,lat_degInt,lon_degInt);
|
||||||
float d = previous.distanceTo(getLat_degInt(),getLon_degInt());
|
float d = previous.distanceTo(getLat_degInt(),getLon_degInt());
|
||||||
return acos(cos(d/rEarth)/cos(dXt/rEarth))*rEarth;
|
float bCurrent = previous.bearingTo(lat_degInt, lon_degInt);
|
||||||
|
float bNext = previous.bearingTo(*this);
|
||||||
|
float y = acos(cos(d/rEarth)/cos(dXt/rEarth))*rEarth;
|
||||||
|
if (cos(bCurrent-bNext) < 0) y = -y;
|
||||||
|
return y;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user