mirror of https://github.com/ArduPilot/ardupilot
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
This commit is contained in:
parent
d6807d749c
commit
e2f15e5fdb
|
@ -14,6 +14,7 @@
|
|||
*/
|
||||
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
#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);
|
||||
|
|
Loading…
Reference in New Issue