From e2f15e5fdba83e2761d2553f93916cc2951fdfee Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 23 Feb 2017 17:28:56 +1100 Subject: [PATCH] Tools: create a GCS_Replay class Avoids a segfault as we assume gcs() returns an object Provides some usefult debug as to what we're sending to the GCS as debug --- Tools/Replay/Replay.cpp | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/Tools/Replay/Replay.cpp b/Tools/Replay/Replay.cpp index 4126af0765..3f8ca298ce 100644 --- a/Tools/Replay/Replay.cpp +++ b/Tools/Replay/Replay.cpp @@ -14,6 +14,7 @@ */ #include +#include #include "Parameters.h" #include "VehicleType.h" #include "MsgHandler.h" @@ -927,4 +928,12 @@ bool Replay::check_user_param(const char *name) return false; } +class GCS_Replay : public GCS +{ + void send_statustext(MAV_SEVERITY severity, uint8_t dest_bitmask, const char *text) override { + ::fprintf(stderr, "GCS: %s\n", text); + } +}; +GCS_Replay _gcs; + AP_HAL_MAIN_CALLBACKS(&replay);