mirror of https://github.com/ArduPilot/ardupilot
Sub: moved accel cal update to vehicle code
This commit is contained in:
parent
baec0d83f2
commit
dbe0bef58b
|
@ -58,7 +58,6 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = {
|
||||||
SCHED_TASK(rpm_update, 10, 200),
|
SCHED_TASK(rpm_update, 10, 200),
|
||||||
#endif
|
#endif
|
||||||
SCHED_TASK_CLASS(Compass, &sub.compass, cal_update, 100, 100),
|
SCHED_TASK_CLASS(Compass, &sub.compass, cal_update, 100, 100),
|
||||||
SCHED_TASK(accel_cal_update, 10, 100),
|
|
||||||
SCHED_TASK(terrain_update, 10, 100),
|
SCHED_TASK(terrain_update, 10, 100),
|
||||||
#if GRIPPER_ENABLED == ENABLED
|
#if GRIPPER_ENABLED == ENABLED
|
||||||
SCHED_TASK_CLASS(AP_Gripper, &sub.g2.gripper, update, 10, 75),
|
SCHED_TASK_CLASS(AP_Gripper, &sub.g2.gripper, update, 10, 75),
|
||||||
|
|
|
@ -591,7 +591,6 @@ private:
|
||||||
bool verify_nav_delay(const AP_Mission::Mission_Command& cmd);
|
bool verify_nav_delay(const AP_Mission::Mission_Command& cmd);
|
||||||
|
|
||||||
void log_init(void);
|
void log_init(void);
|
||||||
void accel_cal_update(void);
|
|
||||||
void read_airspeed();
|
void read_airspeed();
|
||||||
|
|
||||||
void failsafe_leak_check();
|
void failsafe_leak_check();
|
||||||
|
|
|
@ -86,19 +86,6 @@ void Sub::rpm_update(void)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
void Sub::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;
|
|
||||||
if (ins.get_new_trim(trim_roll, trim_pitch)) {
|
|
||||||
ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0));
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
ask airspeed sensor for a new value, duplicated from plane
|
ask airspeed sensor for a new value, duplicated from plane
|
||||||
*/
|
*/
|
||||||
|
|
Loading…
Reference in New Issue