Rover: moved accel cal update to vehicle code

This commit is contained in:
Andrew Tridgell 2021-08-17 12:52:49 +10:00
parent 65c878c06f
commit 608f316698
3 changed files with 0 additions and 16 deletions

View File

@ -93,7 +93,6 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
#endif
SCHED_TASK_CLASS(Compass, &rover.compass, cal_update, 50, 200),
SCHED_TASK(compass_save, 0.1, 200),
SCHED_TASK(accel_cal_update, 10, 200),
#if LOGGING_ENABLED == ENABLED
SCHED_TASK_CLASS(AP_Logger, &rover.logger, periodic_tasks, 50, 300),
#endif

View File

@ -359,7 +359,6 @@ private:
void update_compass(void);
void compass_save(void);
void update_wheel_encoder();
void accel_cal_update(void);
void read_rangefinders(void);
void read_airspeed();
void rpm_update(void);

View File

@ -87,20 +87,6 @@ void Rover::update_wheel_encoder()
#endif
}
// Accel calibration
void Rover::accel_cal_update() {
if (hal.util->get_soft_armed()) {
return;
}
ins.acal_update();
// check if new trim values, and set them float trim_roll, trim_pitch;
float trim_roll, trim_pitch;
if (ins.get_new_trim(trim_roll, trim_pitch)) {
ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0));
}
}
// read the rangefinders
void Rover::read_rangefinders(void)
{