#include #include #include #include #include #include #include #include #include #include #include "LogReader.h" #include #include #include #include #include #include "MsgHandler.h" #include "MsgHandler_PARM.h" #include "MsgHandler_GPS.h" #include "MsgHandler_GPS2.h" #include "MsgHandler_MSG.h" #include "MsgHandler_IMU.h" #include "MsgHandler_IMU2.h" #include "MsgHandler_IMU3.h" #include "MsgHandler_SIM.h" #include "MsgHandler_BARO.h" #include "MsgHandler_ARM.h" #include "MsgHandler_Event.h" #include "MsgHandler_AHR2.h" #include "MsgHandler_ATT.h" #include "MsgHandler_MAG.h" #include "MsgHandler_MAG2.h" #include "MsgHandler_NTUN_Copter.h" #include "MsgHandler_ARSP.h" #define streq(x, y) (!strcmp(x, y)) extern const AP_HAL::HAL& hal; LogReader::LogReader(AP_AHRS &_ahrs, AP_InertialSensor &_ins, AP_Baro &_baro, Compass &_compass, AP_GPS &_gps, AP_Airspeed &_airspeed, DataFlash_Class &_dataflash) : vehicle(VehicleType::VEHICLE_UNKNOWN), fd(-1), ahrs(_ahrs), ins(_ins), baro(_baro), compass(_compass), gps(_gps), airspeed(_airspeed), dataflash(_dataflash), accel_mask(7), gyro_mask(7), last_timestamp_usec(0), installed_vehicle_specific_parsers(false) {} bool LogReader::open_log(const char *logfile) { fd = ::open(logfile, O_RDONLY); if (fd == -1) { return false; } return true; } struct log_Format deferred_formats[LOGREADER_MAX_FORMATS]; // some log entries (e.g. "NTUN") are used by the different vehicle // types with wildy varying payloads. We thus can't use the same // parser for just any e.g. NTUN message. We defer the registration // of a parser for these messages until we know what model we're // dealing with. void LogReader::maybe_install_vehicle_specific_parsers() { if (! installed_vehicle_specific_parsers && vehicle != VehicleType::VEHICLE_UNKNOWN) { switch(vehicle) { case VehicleType::VEHICLE_COPTER: for (uint8_t i = 0; iprocess_message(msg); maybe_install_vehicle_specific_parsers(); return true; } bool LogReader::wait_type(const char *wtype) { while (true) { char type[5]; if (!update(type)) { return false; } if (streq(type,wtype)) { break; } } return true; } bool LogReader::set_parameter(const char *name, float value) { if (parameter_handler == NULL) { ::printf("No parameter format message found"); return false; } return parameter_handler->set_parameter(name, value); }