mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
Replay: added vehicle class detection
This commit is contained in:
parent
b1d82b37ff
commit
250deaa32f
@ -18,9 +18,10 @@
|
|||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
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),
|
vehicle(VEHICLE_UNKNOWN),
|
||||||
fd(-1),
|
fd(-1),
|
||||||
|
ahrs(_ahrs),
|
||||||
ins(_ins),
|
ins(_ins),
|
||||||
baro(_baro),
|
baro(_baro),
|
||||||
compass(_compass),
|
compass(_compass),
|
||||||
@ -323,12 +324,15 @@ bool LogReader::update(uint8_t &type)
|
|||||||
if (strncmp(msg.msg, "ArduPlane", strlen("ArduPlane")) == 0) {
|
if (strncmp(msg.msg, "ArduPlane", strlen("ArduPlane")) == 0) {
|
||||||
vehicle = VEHICLE_PLANE;
|
vehicle = VEHICLE_PLANE;
|
||||||
::printf("Detected Plane\n");
|
::printf("Detected Plane\n");
|
||||||
|
ahrs.set_vehicle_class(AHRS_VEHICLE_FIXED_WING);
|
||||||
} else if (strncmp(msg.msg, "ArduCopter", strlen("ArduCopter")) == 0) {
|
} else if (strncmp(msg.msg, "ArduCopter", strlen("ArduCopter")) == 0) {
|
||||||
vehicle = VEHICLE_COPTER;
|
vehicle = VEHICLE_COPTER;
|
||||||
::printf("Detected Copter\n");
|
::printf("Detected Copter\n");
|
||||||
|
ahrs.set_vehicle_class(AHRS_VEHICLE_COPTER);
|
||||||
} else if (strncmp(msg.msg, "ArduRover", strlen("ArduRover")) == 0) {
|
} else if (strncmp(msg.msg, "ArduRover", strlen("ArduRover")) == 0) {
|
||||||
vehicle = VEHICLE_ROVER;
|
vehicle = VEHICLE_ROVER;
|
||||||
::printf("Detected Rover\n");
|
::printf("Detected Rover\n");
|
||||||
|
ahrs.set_vehicle_class(AHRS_VEHICLE_GROUND);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
@ -19,7 +19,7 @@ enum log_messages {
|
|||||||
class LogReader
|
class LogReader
|
||||||
{
|
{
|
||||||
public:
|
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 open_log(const char *logfile);
|
||||||
bool update(uint8_t &type);
|
bool update(uint8_t &type);
|
||||||
bool wait_type(uint8_t type);
|
bool wait_type(uint8_t type);
|
||||||
@ -40,6 +40,7 @@ public:
|
|||||||
|
|
||||||
private:
|
private:
|
||||||
int fd;
|
int fd;
|
||||||
|
AP_AHRS &ahrs;
|
||||||
AP_InertialSensor &ins;
|
AP_InertialSensor &ins;
|
||||||
AP_Baro_HIL &baro;
|
AP_Baro_HIL &baro;
|
||||||
AP_Compass_HIL &compass;
|
AP_Compass_HIL &compass;
|
||||||
|
@ -73,7 +73,7 @@ SITL sitl;
|
|||||||
|
|
||||||
static const NavEKF &NavEKF = ahrs.get_NavEKF();
|
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 *plotf;
|
||||||
static FILE *plotf2;
|
static FILE *plotf2;
|
||||||
|
Loading…
Reference in New Issue
Block a user