diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index a8e334f6ef..373e1d9e7f 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -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(); diff --git a/ArduCopter/mode_guided.cpp b/ArduCopter/mode_guided.cpp index 00f661fe5d..5cf4b0627a 100644 --- a/ArduCopter/mode_guided.cpp +++ b/ArduCopter/mode_guided.cpp @@ -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;