mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 07:13:56 -04:00
Rover: move RPM sensor logging into AP_RPM
This commit is contained in:
parent
9b60443fa4
commit
94dca37d2e
@ -96,7 +96,7 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
|
||||
#if GRIPPER_ENABLED == ENABLED
|
||||
SCHED_TASK_CLASS(AP_Gripper, &rover.g2.gripper, update, 10, 75, 69),
|
||||
#endif
|
||||
SCHED_TASK(rpm_update, 10, 100, 72),
|
||||
SCHED_TASK_CLASS(AP_RPM, &rover.rpm_sensor, update, 10, 100, 72),
|
||||
#if HAL_MOUNT_ENABLED
|
||||
SCHED_TASK_CLASS(AP_Mount, &rover.camera_mount, update, 50, 200, 75),
|
||||
#endif
|
||||
|
@ -353,7 +353,6 @@ private:
|
||||
void update_wheel_encoder();
|
||||
void read_rangefinders(void);
|
||||
void read_airspeed();
|
||||
void rpm_update(void);
|
||||
|
||||
// Steering.cpp
|
||||
void set_servos(void);
|
||||
|
@ -101,14 +101,3 @@ void Rover::read_airspeed(void)
|
||||
{
|
||||
g2.airspeed.update(should_log(MASK_LOG_IMU));
|
||||
}
|
||||
|
||||
/*
|
||||
update RPM sensors
|
||||
*/
|
||||
void Rover::rpm_update(void)
|
||||
{
|
||||
rpm_sensor.update();
|
||||
if (rpm_sensor.enabled(0) || rpm_sensor.enabled(1)) {
|
||||
logger.Write_RPM(rpm_sensor);
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user