From 2acddb9696fec77180863f3915080a69245084ec Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 27 Apr 2014 15:37:02 +1000 Subject: [PATCH] Replay: fixed ahrs.set_fly_forward() in Replay for copter --- Tools/Replay/LogReader.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/Tools/Replay/LogReader.cpp b/Tools/Replay/LogReader.cpp index 5a5906ca0c..2f8b62abf7 100644 --- a/Tools/Replay/LogReader.cpp +++ b/Tools/Replay/LogReader.cpp @@ -325,14 +325,17 @@ bool LogReader::update(uint8_t &type) vehicle = VEHICLE_PLANE; ::printf("Detected Plane\n"); ahrs.set_vehicle_class(AHRS_VEHICLE_FIXED_WING); + ahrs.set_fly_forward(true); } else if (strncmp(msg.msg, "ArduCopter", strlen("ArduCopter")) == 0) { vehicle = VEHICLE_COPTER; ::printf("Detected Copter\n"); ahrs.set_vehicle_class(AHRS_VEHICLE_COPTER); + ahrs.set_fly_forward(false); } else if (strncmp(msg.msg, "ArduRover", strlen("ArduRover")) == 0) { vehicle = VEHICLE_ROVER; ::printf("Detected Rover\n"); ahrs.set_vehicle_class(AHRS_VEHICLE_GROUND); + ahrs.set_fly_forward(true); } break; }