mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Replay: use IMT in preference to IMU
This commit is contained in:
parent
3fcda53d11
commit
45d80080c3
@ -516,12 +516,16 @@ bool Replay::find_log_info(struct log_information &info)
|
|||||||
}
|
}
|
||||||
|
|
||||||
if (strlen(clock_source) == 0) {
|
if (strlen(clock_source) == 0) {
|
||||||
// if you want to add a clock source, also add it to
|
// If you want to add a clock source, also add it to
|
||||||
// handle_msg and handle_log_format_msg, above
|
// handle_msg and handle_log_format_msg, above. Note that
|
||||||
if (streq(type, "IMU")) {
|
// ordering is important here. For example, when we log
|
||||||
memcpy(clock_source, "IMU", 3);
|
// IMT we may reduce the logging speed of IMU, so then
|
||||||
} else if (streq(type, "IMT")) {
|
// using IMU as your clock source will lead to incorrect
|
||||||
|
// behaviour.
|
||||||
|
if (streq(type, "IMT")) {
|
||||||
memcpy(clock_source, "IMT", 3);
|
memcpy(clock_source, "IMT", 3);
|
||||||
|
} else if (streq(type, "IMU")) {
|
||||||
|
memcpy(clock_source, "IMU", 3);
|
||||||
} else {
|
} else {
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user