mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
Replay: keep airspeed msgs in log
This commit is contained in:
parent
5a01933b7b
commit
ad8480d5f7
@ -77,14 +77,6 @@ struct PACKED log_Plane_Attitude {
|
|||||||
uint16_t error_yaw;
|
uint16_t error_yaw;
|
||||||
};
|
};
|
||||||
|
|
||||||
struct PACKED log_AIRSPEED {
|
|
||||||
LOG_PACKET_HEADER;
|
|
||||||
uint32_t timestamp;
|
|
||||||
float airspeed;
|
|
||||||
float diffpressure;
|
|
||||||
int16_t temperature;
|
|
||||||
};
|
|
||||||
|
|
||||||
struct PACKED log_Copter_Attitude {
|
struct PACKED log_Copter_Attitude {
|
||||||
LOG_PACKET_HEADER;
|
LOG_PACKET_HEADER;
|
||||||
uint32_t time_ms;
|
uint32_t time_ms;
|
||||||
@ -163,7 +155,8 @@ void LogReader::process_plane(uint8_t type, uint8_t *data, uint16_t length)
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
case LOG_PLANE_AIRSPEED_MSG: {
|
case LOG_PLANE_AIRSPEED_MSG:
|
||||||
|
case LOG_ARSP_MSG: {
|
||||||
struct log_AIRSPEED msg;
|
struct log_AIRSPEED msg;
|
||||||
if (sizeof(msg) != length && length != sizeof(msg)+8) {
|
if (sizeof(msg) != length && length != sizeof(msg)+8) {
|
||||||
printf("Bad AIRSPEED length\n");
|
printf("Bad AIRSPEED length\n");
|
||||||
@ -172,6 +165,7 @@ void LogReader::process_plane(uint8_t type, uint8_t *data, uint16_t length)
|
|||||||
memcpy(&msg, data, sizeof(msg));
|
memcpy(&msg, data, sizeof(msg));
|
||||||
wait_timestamp(msg.timestamp);
|
wait_timestamp(msg.timestamp);
|
||||||
airspeed.setHIL(msg.airspeed, msg.diffpressure, msg.temperature);
|
airspeed.setHIL(msg.airspeed, msg.diffpressure, msg.temperature);
|
||||||
|
dataflash.Log_Write_Airspeed(airspeed);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -359,11 +353,12 @@ bool LogReader::update(uint8_t &type)
|
|||||||
|
|
||||||
case LOG_IMU_MSG: {
|
case LOG_IMU_MSG: {
|
||||||
struct log_IMU msg;
|
struct log_IMU msg;
|
||||||
if(sizeof(msg) != f.length) {
|
if (sizeof(msg) != f.length && sizeof(msg) != f.length+8) {
|
||||||
printf("Bad IMU length\n");
|
printf("Bad IMU length %u expected %u\n",
|
||||||
|
(unsigned)sizeof(msg), (unsigned)f.length);
|
||||||
exit(1);
|
exit(1);
|
||||||
}
|
}
|
||||||
memcpy(&msg, data, sizeof(msg));
|
memcpy(&msg, data, f.length);
|
||||||
wait_timestamp(msg.timestamp);
|
wait_timestamp(msg.timestamp);
|
||||||
if (gyro_mask & 1) {
|
if (gyro_mask & 1) {
|
||||||
ins.set_gyro(0, Vector3f(msg.gyro_x, msg.gyro_y, msg.gyro_z));
|
ins.set_gyro(0, Vector3f(msg.gyro_x, msg.gyro_y, msg.gyro_z));
|
||||||
@ -377,11 +372,12 @@ bool LogReader::update(uint8_t &type)
|
|||||||
|
|
||||||
case LOG_IMU2_MSG: {
|
case LOG_IMU2_MSG: {
|
||||||
struct log_IMU msg;
|
struct log_IMU msg;
|
||||||
if(sizeof(msg) != f.length) {
|
if (sizeof(msg) != f.length && sizeof(msg) != f.length+8) {
|
||||||
printf("Bad IMU2 length\n");
|
printf("Bad IMU2 length %u expected %u\n",
|
||||||
|
(unsigned)sizeof(msg), (unsigned)f.length);
|
||||||
exit(1);
|
exit(1);
|
||||||
}
|
}
|
||||||
memcpy(&msg, data, sizeof(msg));
|
memcpy(&msg, data, f.length);
|
||||||
wait_timestamp(msg.timestamp);
|
wait_timestamp(msg.timestamp);
|
||||||
if (gyro_mask & 2) {
|
if (gyro_mask & 2) {
|
||||||
ins.set_gyro(1, Vector3f(msg.gyro_x, msg.gyro_y, msg.gyro_z));
|
ins.set_gyro(1, Vector3f(msg.gyro_x, msg.gyro_y, msg.gyro_z));
|
||||||
@ -528,7 +524,6 @@ bool LogReader::update(uint8_t &type)
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
default:
|
default:
|
||||||
if (vehicle == VEHICLE_PLANE) {
|
if (vehicle == VEHICLE_PLANE) {
|
||||||
process_plane(f.type, data, f.length);
|
process_plane(f.type, data, f.length);
|
||||||
|
@ -209,6 +209,8 @@ void setup()
|
|||||||
|
|
||||||
if (arm_time_ms != 0) {
|
if (arm_time_ms != 0) {
|
||||||
ahrs.set_armed(false);
|
ahrs.set_armed(false);
|
||||||
|
} else {
|
||||||
|
ahrs.set_armed(true);
|
||||||
}
|
}
|
||||||
|
|
||||||
barometer.init();
|
barometer.init();
|
||||||
|
Loading…
Reference in New Issue
Block a user