AP_Vehicle: remove runcam singleton

This commit is contained in:
Andy Piper 2024-09-12 09:56:16 +01:00
parent 72f56ee8fc
commit be49a06f04
2 changed files with 2 additions and 15 deletions

View File

@ -35,11 +35,8 @@ extern AP_IOMCU iomcu;
2nd group of parameters
*/
const AP_Param::GroupInfo AP_Vehicle::var_info[] = {
#if HAL_RUNCAM_ENABLED
// @Group: CAM_RC_
// @Path: ../AP_Camera/AP_RunCam.cpp
AP_SUBGROUPINFO(runcam, "CAM_RC_", 1, AP_Vehicle, AP_RunCam),
#endif
// 1: RunCam
#if HAL_GYROFFT_ENABLED
// @Group: FFT_
@ -450,9 +447,6 @@ void AP_Vehicle::setup()
gyro_fft.init(1000);
#endif
#endif
#if HAL_RUNCAM_ENABLED
runcam.init();
#endif
#if HAL_HOTT_TELEM_ENABLED
hott_telem.init();
#endif
@ -615,9 +609,6 @@ const AP_Scheduler::Task AP_Vehicle::scheduler_tasks[] = {
#if HAL_NMEA_OUTPUT_ENABLED
SCHED_TASK_CLASS(AP_NMEA_Output, &vehicle.nmea, update, 50, 50, 180),
#endif
#if HAL_RUNCAM_ENABLED
SCHED_TASK_CLASS(AP_RunCam, &vehicle.runcam, update, 50, 50, 200),
#endif
#if HAL_GYROFFT_ENABLED
SCHED_TASK_CLASS(AP_GyroFFT, &vehicle.gyro_fft, update, 400, 50, 205),
SCHED_TASK_CLASS(AP_GyroFFT, &vehicle.gyro_fft, update_parameters, 1, 50, 210),

View File

@ -47,7 +47,6 @@
#include <AP_Scheduler/AP_Scheduler.h>
#include <AP_SerialManager/AP_SerialManager.h> // Serial manager library
#include <AP_ServoRelayEvents/AP_ServoRelayEvents.h>
#include <AP_Camera/AP_RunCam.h>
#include <AP_OpenDroneID/AP_OpenDroneID.h>
#include <AP_Hott_Telem/AP_Hott_Telem.h>
#include <AP_ESC_Telem/AP_ESC_Telem.h>
@ -373,9 +372,6 @@ protected:
AP_RSSI rssi;
#endif
#if HAL_RUNCAM_ENABLED
AP_RunCam runcam;
#endif
#if HAL_GYROFFT_ENABLED
AP_GyroFFT gyro_fft;
#endif