mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-07 09:13:32 +08:00
Commander: updated mag calibration routine, matlab script updates
This commit is contained in:
@@ -243,7 +243,7 @@ enum detect_orientation_return detect_orientation(int mavlink_fd, int cancel_sub
|
||||
const float normal_still_thr = 0.25; // normal still threshold
|
||||
float still_thr2 = powf(lenient_still_position ? (normal_still_thr * 3) : normal_still_thr, 2);
|
||||
float accel_err_thr = 5.0f; // set accel error threshold to 5m/s^2
|
||||
hrt_abstime still_time = lenient_still_position ? 1000000 : 1500000; // still time required in us
|
||||
hrt_abstime still_time = lenient_still_position ? 500000 : 1300000; // still time required in us
|
||||
|
||||
struct pollfd fds[1];
|
||||
fds[0].fd = accel_sub;
|
||||
@@ -324,7 +324,7 @@ enum detect_orientation_return detect_orientation(int mavlink_fd, int cancel_sub
|
||||
/* not still, reset still start time */
|
||||
if (t_still != 0) {
|
||||
mavlink_and_console_log_info(mavlink_fd, "[cal] detected motion, hold still...");
|
||||
usleep(500000);
|
||||
usleep(200000);
|
||||
t_still = 0;
|
||||
}
|
||||
}
|
||||
@@ -488,7 +488,7 @@ calibrate_return calibrate_from_orientation(int mavlink_fd,
|
||||
// Note that this side is complete
|
||||
side_data_collected[orient] = true;
|
||||
tune_neutral(true);
|
||||
usleep(500000);
|
||||
usleep(200000);
|
||||
}
|
||||
|
||||
if (sub_accel >= 0) {
|
||||
|
||||
Reference in New Issue
Block a user