mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: Guided and Loiter mode returns Crosstrack error
This commit is contained in:
parent
ce254153c1
commit
6d6ab89a72
@ -1028,6 +1028,7 @@ protected:
|
||||
|
||||
uint32_t wp_distance() const override;
|
||||
int32_t wp_bearing() const override;
|
||||
float crosstrack_error() const override { return pos_control->crosstrack_error();}
|
||||
|
||||
#if PRECISION_LANDING == ENABLED
|
||||
bool do_precision_loiter();
|
||||
|
@ -1024,6 +1024,7 @@ float ModeGuided::crosstrack_error() const
|
||||
case SubMode::Accel:
|
||||
case SubMode::VelAccel:
|
||||
case SubMode::PosVelAccel:
|
||||
return pos_control->crosstrack_error();
|
||||
case SubMode::Angle:
|
||||
// no track to have a crosstrack to
|
||||
return 0;
|
||||
|
Loading…
Reference in New Issue
Block a user