Skip to content

Commit

Permalink
AP_Vehicle: remove runcam singleton
Browse files Browse the repository at this point in the history
  • Loading branch information
andyp1per committed Sep 12, 2024
1 parent be8a392 commit 302a30b
Show file tree
Hide file tree
Showing 2 changed files with 0 additions and 15 deletions.
11 changes: 0 additions & 11 deletions libraries/AP_Vehicle/AP_Vehicle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,11 +34,6 @@ 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

#if HAL_GYROFFT_ENABLED
// @Group: FFT_
Expand Down Expand Up @@ -449,9 +444,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
Expand Down Expand Up @@ -614,9 +606,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),
Expand Down
4 changes: 0 additions & 4 deletions libraries/AP_Vehicle/AP_Vehicle.h
Original file line number Diff line number Diff line change
Expand Up @@ -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>
Expand Down Expand Up @@ -364,9 +363,6 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks {
AP_RSSI rssi;
#endif

#if HAL_RUNCAM_ENABLED
AP_RunCam runcam;
#endif
#if HAL_GYROFFT_ENABLED
AP_GyroFFT gyro_fft;
#endif
Expand Down

0 comments on commit 302a30b

Please sign in to comment.