#include #include #include #include #include #include #include #include #include #include #include "LogReader.h" #include #include #include #include #include extern const AP_HAL::HAL& hal; LogReader::LogReader(AP_AHRS &_ahrs, AP_InertialSensor &_ins, AP_Baro &_baro, AP_Compass_HIL &_compass, AP_GPS &_gps, AP_Airspeed &_airspeed, DataFlash_Class &_dataflash) : vehicle(VEHICLE_UNKNOWN), fd(-1), ahrs(_ahrs), ins(_ins), baro(_baro), compass(_compass), gps(_gps), airspeed(_airspeed), dataflash(_dataflash), accel_mask(7), gyro_mask(7) {} bool LogReader::open_log(const char *logfile) { fd = ::open(logfile, O_RDONLY); if (fd == -1) { return false; } return true; } struct PACKED log_Plane_Compass_old { LOG_PACKET_HEADER; uint32_t time_ms; int16_t mag_x; int16_t mag_y; int16_t mag_z; int16_t offset_x; int16_t offset_y; int16_t offset_z; }; struct PACKED log_Copter_Compass_old { LOG_PACKET_HEADER; uint32_t time_ms; int16_t mag_x; int16_t mag_y; int16_t mag_z; int16_t offset_x; int16_t offset_y; int16_t offset_z; int16_t motor_offset_x; int16_t motor_offset_y; int16_t motor_offset_z; }; struct PACKED log_Plane_Attitude_old { LOG_PACKET_HEADER; uint32_t time_ms; int16_t roll; int16_t pitch; uint16_t yaw; uint16_t error_rp; uint16_t error_yaw; }; struct PACKED log_Copter_Attitude_old { LOG_PACKET_HEADER; uint32_t time_ms; int16_t control_roll; int16_t roll; int16_t control_pitch; int16_t pitch; uint16_t control_yaw; uint16_t yaw; uint16_t error_rp; uint16_t error_yaw; }; struct PACKED log_Copter_Nav_Tuning { LOG_PACKET_HEADER; uint32_t time_ms; float desired_pos_x; float desired_pos_y; float pos_x; float pos_y; float desired_vel_x; float desired_vel_y; float vel_x; float vel_y; float desired_accel_x; float desired_accel_y; }; struct PACKED log_Rover_Attitude_old { LOG_PACKET_HEADER; uint32_t time_ms; int16_t roll; int16_t pitch; uint16_t yaw; }; struct PACKED log_Rover_Compass_old { LOG_PACKET_HEADER; uint32_t time_ms; int16_t mag_x; int16_t mag_y; int16_t mag_z; int16_t offset_x; int16_t offset_y; int16_t offset_z; int16_t motor_offset_x; int16_t motor_offset_y; int16_t motor_offset_z; }; void LogReader::process_plane(uint8_t type, uint8_t *data, uint16_t length) { switch (type) { case LOG_PLANE_COMPASS_MSG: { struct log_Plane_Compass_old msg; if(sizeof(msg) != length) { printf("Bad plane COMPASS_OLD length\n"); exit(1); } memcpy(&msg, data, sizeof(msg)); wait_timestamp(msg.time_ms); compass.setHIL(Vector3f(msg.mag_x - msg.offset_x, msg.mag_y - msg.offset_y, msg.mag_z - msg.offset_z)); compass.set_offsets(0, Vector3f(msg.offset_x, msg.offset_y, msg.offset_z)); break; } case LOG_PLANE_ATTITUDE_MSG: { struct log_Plane_Attitude_old msg; if(sizeof(msg) != length) { printf("Bad ATTITUDE length %u should be %u\n", (unsigned)length, (unsigned)sizeof(msg)); exit(1); } memcpy(&msg, data, sizeof(msg)); wait_timestamp(msg.time_ms); attitude = Vector3f(msg.roll*0.01f, msg.pitch*0.01f, msg.yaw*0.01f); break; } case LOG_PLANE_AIRSPEED_MSG: case LOG_ARSP_MSG: { struct log_AIRSPEED msg; if (sizeof(msg) != length && length != sizeof(msg)+8) { printf("Bad AIRSPEED length\n"); exit(1); } memcpy(&msg, data, sizeof(msg)); wait_timestamp(msg.timestamp); airspeed.setHIL(msg.airspeed, msg.diffpressure, msg.temperature); dataflash.Log_Write_Airspeed(airspeed); break; } } } void LogReader::process_rover(uint8_t type, uint8_t *data, uint16_t length) { switch (type) { case LOG_ROVER_COMPASS_MSG: { struct log_Rover_Compass_old msg; if(sizeof(msg) != length) { printf("Bad rover COMPASS length\n"); exit(1); } memcpy(&msg, data, sizeof(msg)); wait_timestamp(msg.time_ms); compass.setHIL(Vector3f(msg.mag_x - msg.offset_x, msg.mag_y - msg.offset_y, msg.mag_z - msg.offset_z)); compass.set_offsets(0, Vector3f(msg.offset_x, msg.offset_y, msg.offset_z)); break; } case LOG_ROVER_ATTITUDE_MSG: { struct log_Rover_Attitude_old msg; if(sizeof(msg) != length) { printf("Bad ATTITUDE length\n"); exit(1); } memcpy(&msg, data, sizeof(msg)); wait_timestamp(msg.time_ms); attitude = Vector3f(msg.roll*0.01f, msg.pitch*0.01f, msg.yaw*0.01f); break; } } } void LogReader::process_copter(uint8_t type, uint8_t *data, uint16_t length) { switch (type) { case LOG_COPTER_COMPASS_MSG: { struct log_Copter_Compass_old msg; if(sizeof(msg) != length) { printf("Bad copter COMPASS length %u expected %u\n", (unsigned)length, (unsigned)sizeof(msg)); exit(1); } memcpy(&msg, data, sizeof(msg)); wait_timestamp(msg.time_ms); compass.setHIL(Vector3f(msg.mag_x - msg.offset_x, msg.mag_y - msg.offset_y, msg.mag_z - msg.offset_z)); compass.set_offsets(0, Vector3f(msg.offset_x, msg.offset_y, msg.offset_z)); break; } case LOG_COPTER_ATTITUDE_MSG: { struct log_Copter_Attitude_old msg; if (sizeof(msg) == length+sizeof(uint16_t)*2) { // old style, without errors memset(&msg, 0, sizeof(msg)); memcpy(&msg, data, length); } else if (sizeof(msg) == length) { memcpy(&msg, data, sizeof(msg)); } else { printf("Bad ATTITUDE length %u should be %u\n", (unsigned)length, (unsigned)sizeof(msg)); exit(1); } memcpy(&msg, data, sizeof(msg)); wait_timestamp(msg.time_ms); attitude = Vector3f(msg.roll*0.01f, msg.pitch*0.01f, msg.yaw*0.01f); break; } case LOG_COPTER_NAV_TUNING_MSG: { struct log_Copter_Nav_Tuning msg; if(sizeof(msg) != length) { printf("Bad copter NAV_TUNING length\n"); exit(1); } memcpy(&msg, data, sizeof(msg)); wait_timestamp(msg.time_ms); inavpos = Vector3f(msg.pos_x * 0.01f, msg.pos_y * 0.01f, 0); break; } } } bool LogReader::set_parameter(const char *name, float value) { const char *ignore_parms[] = { "GPS_TYPE", "AHRS_EKF_USE" }; for (uint8_t i=0; iset(value); ::printf("Set %s to %f\n", name, value); } else if (var_type == AP_PARAM_INT32) { ((AP_Int32 *)vp)->set(value); ::printf("Set %s to %d\n", name, (int)value); } else if (var_type == AP_PARAM_INT16) { ((AP_Int16 *)vp)->set(value); ::printf("Set %s to %d\n", name, (int)value); } else if (var_type == AP_PARAM_INT8) { ((AP_Int8 *)vp)->set(value); ::printf("Set %s to %d\n", name, (int)value); } else { // we don't support mavlink set on this parameter return false; } return true; } bool LogReader::update(uint8_t &type) { uint8_t hdr[3]; if (::read(fd, hdr, 3) != 3) { return false; } if (hdr[0] != HEAD_BYTE1 || hdr[1] != HEAD_BYTE2) { printf("bad log header\n"); return false; } if (hdr[2] == LOG_FORMAT_MSG) { struct log_Format &f = formats[num_formats]; memcpy(&f, hdr, 3); if (::read(fd, &f.type, sizeof(f)-3) != sizeof(f)-3) { return false; } if (num_formats < LOGREADER_MAX_FORMATS-1) { num_formats++; } type = f.type; return true; } uint8_t i; for (i=0; istop_clock(timestamp*1000UL); } bool LogReader::wait_type(uint8_t wtype) { while (true) { uint8_t type; if (!update(type)) { return false; } if (wtype == type) { break; } } return true; }