diff --git a/libraries/AP_Follow/AP_Follow.cpp b/libraries/AP_Follow/AP_Follow.cpp index a5f3896652..0ef860cbae 100644 --- a/libraries/AP_Follow/AP_Follow.cpp +++ b/libraries/AP_Follow/AP_Follow.cpp @@ -322,6 +322,18 @@ void AP_Follow::handle_msg(const mavlink_message_t &msg) } // log lead's estimated vs reported position +// @LoggerMessage: FOLL +// @Description: Follow library diagnostic data +// @Field: TimeUS: Time since system startup +// @Field: Lat: Target latitude +// @Field: Lon: Target longitude +// @Field: Alt: Target absolute altitude +// @Field: VelN: Target earth-frame velocity, North +// @Field: VelE: Target earth-frame velocity, East +// @Field: VelD: Target earth-frame velocity, Down +// @Field: LatE: Vehicle latitude +// @Field: LonE: Vehicle longitude +// @Field: AltE: Vehicle absolute altitude AP::logger().Write("FOLL", "TimeUS,Lat,Lon,Alt,VelN,VelE,VelD,LatE,LonE,AltE", // labels "sDUmnnnDUm", // units