#include #include #include #include #include #include #include #include #include #include #include "LogReader.h" #include #include #include #include #include "MsgHandler.h" #include "Replay.h" #define DEBUG 1 #if DEBUG # define debug(fmt, args...) printf(fmt "\n", ##args) #else # define debug(fmt, args...) #endif #define streq(x, y) (!strcmp(x, y)) extern const AP_HAL::HAL& hal; const struct LogStructure running_codes_log_structure[] = { LOG_COMMON_STRUCTURES, }; LogReader::LogReader(AP_AHRS &_ahrs, AP_InertialSensor &_ins, Compass &_compass, AP_GPS &_gps, AP_Airspeed &_airspeed, AP_Logger &_logger, struct LogStructure *log_structure, uint8_t log_structure_count, const char **&_nottypes): AP_LoggerFileReader(), vehicle(VehicleType::VEHICLE_UNKNOWN), ahrs(_ahrs), ins(_ins), compass(_compass), gps(_gps), airspeed(_airspeed), logger(_logger), accel_mask(7), gyro_mask(7), last_timestamp_usec(0), installed_vehicle_specific_parsers(false), _log_structure(log_structure), nottypes(_nottypes) { if (log_structure_count != 0) { ::fprintf(stderr, "Do NOT put anything in the log_structure before passing it in here"); abort(); // so there. } initialise_fmt_map(); } 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; istop_clock(last_timestamp_usec); } LR_MsgHandler *p = msgparser[f.type]; if (p == NULL) { return true; } p->process_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) { enum ap_var_type var_type; AP_Param *vp = AP_Param::find(name, &var_type); if (vp == NULL) { return false; } float old_value = 0; if (var_type == AP_PARAM_FLOAT) { old_value = ((AP_Float *)vp)->cast_to_float(); ((AP_Float *)vp)->set(value); } else if (var_type == AP_PARAM_INT32) { old_value = ((AP_Int32 *)vp)->cast_to_float(); ((AP_Int32 *)vp)->set(value); } else if (var_type == AP_PARAM_INT16) { old_value = ((AP_Int16 *)vp)->cast_to_float(); ((AP_Int16 *)vp)->set(value); } else if (var_type == AP_PARAM_INT8) { old_value = ((AP_Int8 *)vp)->cast_to_float(); ((AP_Int8 *)vp)->set(value); } else { // we don't support mavlink set on this parameter return false; } if (fabsf(old_value - value) > 1.0e-12) { ::printf("Changed %s to %.8f from %.8f\n", name, value, old_value); } return true; }