Browse Source

Replay: fixed for changes to AP_Compass HIL API

master
Andrew Tridgell 11 years ago
parent
commit
47926dc6ea
  1. 6
      Tools/Replay/LogReader.cpp
  2. 2
      Tools/Replay/Replay.pde

6
Tools/Replay/LogReader.cpp

@ -143,7 +143,7 @@ void LogReader::process_plane(uint8_t type, uint8_t *data, uint16_t length) @@ -143,7 +143,7 @@ void LogReader::process_plane(uint8_t type, uint8_t *data, uint16_t length)
}
memcpy(&msg, data, sizeof(msg));
wait_timestamp(msg.time_ms);
compass.setHIL(Vector3i(msg.mag_x - msg.offset_x, msg.mag_y - msg.offset_y, msg.mag_z - msg.offset_z));
compass.setHIL(Vector3f(msg.mag_x - msg.offset_x, msg.mag_y - msg.offset_y, msg.mag_z - msg.offset_z));
compass.set_offsets(msg.offset_x, msg.offset_y, msg.offset_z);
break;
}
@ -185,7 +185,7 @@ void LogReader::process_rover(uint8_t type, uint8_t *data, uint16_t length) @@ -185,7 +185,7 @@ void LogReader::process_rover(uint8_t type, uint8_t *data, uint16_t length)
}
memcpy(&msg, data, sizeof(msg));
wait_timestamp(msg.time_ms);
compass.setHIL(Vector3i(msg.mag_x - msg.offset_x, msg.mag_y - msg.offset_y, msg.mag_z - msg.offset_z));
compass.setHIL(Vector3f(msg.mag_x - msg.offset_x, msg.mag_y - msg.offset_y, msg.mag_z - msg.offset_z));
compass.set_offsets(msg.offset_x, msg.offset_y, msg.offset_z);
break;
}
@ -215,7 +215,7 @@ void LogReader::process_copter(uint8_t type, uint8_t *data, uint16_t length) @@ -215,7 +215,7 @@ void LogReader::process_copter(uint8_t type, uint8_t *data, uint16_t length)
}
memcpy(&msg, data, sizeof(msg));
wait_timestamp(msg.time_ms);
compass.setHIL(Vector3i(msg.mag_x - msg.offset_x, msg.mag_y - msg.offset_y, msg.mag_z - msg.offset_z));
compass.setHIL(Vector3f(msg.mag_x - msg.offset_x, msg.mag_y - msg.offset_y, msg.mag_z - msg.offset_z));
compass.set_offsets(msg.offset_x, msg.offset_y, msg.offset_z);
break;
}

2
Tools/Replay/Replay.pde

@ -49,8 +49,10 @@ @@ -49,8 +49,10 @@
#include <errno.h>
#include <fenv.h>
#ifndef INT16_MIN
#define INT16_MIN -32768
#define INT16_MAX 32767
#endif
#include "LogReader.h"

Loading…
Cancel
Save