Replay: added vehicle class detection

This commit is contained in:
Andrew Tridgell 2014-04-21 18:11:20 +10:00
parent b1d82b37ff
commit 250deaa32f
3 changed files with 8 additions and 3 deletions

View File

@ -18,9 +18,10 @@
extern const AP_HAL::HAL& hal;
LogReader::LogReader(AP_InertialSensor &_ins, AP_Baro_HIL &_baro, AP_Compass_HIL &_compass, AP_GPS &_gps, AP_Airspeed &_airspeed) :
LogReader::LogReader(AP_AHRS &_ahrs, AP_InertialSensor &_ins, AP_Baro_HIL &_baro, AP_Compass_HIL &_compass, AP_GPS &_gps, AP_Airspeed &_airspeed) :
vehicle(VEHICLE_UNKNOWN),
fd(-1),
ahrs(_ahrs),
ins(_ins),
baro(_baro),
compass(_compass),
@ -323,12 +324,15 @@ bool LogReader::update(uint8_t &type)
if (strncmp(msg.msg, "ArduPlane", strlen("ArduPlane")) == 0) {
vehicle = VEHICLE_PLANE;
::printf("Detected Plane\n");
ahrs.set_vehicle_class(AHRS_VEHICLE_FIXED_WING);
} else if (strncmp(msg.msg, "ArduCopter", strlen("ArduCopter")) == 0) {
vehicle = VEHICLE_COPTER;
::printf("Detected Copter\n");
ahrs.set_vehicle_class(AHRS_VEHICLE_COPTER);
} else if (strncmp(msg.msg, "ArduRover", strlen("ArduRover")) == 0) {
vehicle = VEHICLE_ROVER;
::printf("Detected Rover\n");
ahrs.set_vehicle_class(AHRS_VEHICLE_GROUND);
}
break;
}

View File

@ -19,7 +19,7 @@ enum log_messages {
class LogReader
{
public:
LogReader(AP_InertialSensor &_ins, AP_Baro_HIL &_baro, AP_Compass_HIL &_compass, AP_GPS &_gps, AP_Airspeed &_airspeed);
LogReader(AP_AHRS &_ahrs, AP_InertialSensor &_ins, AP_Baro_HIL &_baro, AP_Compass_HIL &_compass, AP_GPS &_gps, AP_Airspeed &_airspeed);
bool open_log(const char *logfile);
bool update(uint8_t &type);
bool wait_type(uint8_t type);
@ -40,6 +40,7 @@ public:
private:
int fd;
AP_AHRS &ahrs;
AP_InertialSensor &ins;
AP_Baro_HIL &baro;
AP_Compass_HIL &compass;

View File

@ -73,7 +73,7 @@ SITL sitl;
static const NavEKF &NavEKF = ahrs.get_NavEKF();
static LogReader LogReader(ins, barometer, compass, gps, airspeed);
static LogReader LogReader(ahrs, ins, barometer, compass, gps, airspeed);
static FILE *plotf;
static FILE *plotf2;