mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: add and use AP_CAMERA_ENABLED
This commit is contained in:
parent
9b5d70f7b5
commit
71f77fea6e
@ -300,7 +300,7 @@ const AP_Param::Info Rover::var_info[] = {
|
|||||||
// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp
|
// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp
|
||||||
GOBJECT(ahrs, "AHRS_", AP_AHRS),
|
GOBJECT(ahrs, "AHRS_", AP_AHRS),
|
||||||
|
|
||||||
#if CAMERA == ENABLED
|
#if AP_CAMERA_ENABLED
|
||||||
// @Group: CAM_
|
// @Group: CAM_
|
||||||
// @Path: ../libraries/AP_Camera/AP_Camera.cpp
|
// @Path: ../libraries/AP_Camera/AP_Camera.cpp
|
||||||
GOBJECT(camera, "CAM_", AP_Camera),
|
GOBJECT(camera, "CAM_", AP_Camera),
|
||||||
|
@ -104,7 +104,7 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
|
|||||||
#if HAL_MOUNT_ENABLED
|
#if HAL_MOUNT_ENABLED
|
||||||
SCHED_TASK_CLASS(AP_Mount, &rover.camera_mount, update, 50, 200, 75),
|
SCHED_TASK_CLASS(AP_Mount, &rover.camera_mount, update, 50, 200, 75),
|
||||||
#endif
|
#endif
|
||||||
#if CAMERA == ENABLED
|
#if AP_CAMERA_ENABLED
|
||||||
SCHED_TASK_CLASS(AP_Camera, &rover.camera, update, 50, 200, 78),
|
SCHED_TASK_CLASS(AP_Camera, &rover.camera, update, 50, 200, 78),
|
||||||
#endif
|
#endif
|
||||||
SCHED_TASK(gcs_failsafe_check, 10, 200, 81),
|
SCHED_TASK(gcs_failsafe_check, 10, 200, 81),
|
||||||
|
@ -158,7 +158,7 @@ private:
|
|||||||
struct Location current_loc;
|
struct Location current_loc;
|
||||||
|
|
||||||
// Camera
|
// Camera
|
||||||
#if CAMERA == ENABLED
|
#if AP_CAMERA_ENABLED
|
||||||
AP_Camera camera{MASK_LOG_CAMERA};
|
AP_Camera camera{MASK_LOG_CAMERA};
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -31,13 +31,6 @@
|
|||||||
#error XXX
|
#error XXX
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
|
||||||
// CAMERA control
|
|
||||||
//
|
|
||||||
#ifndef CAMERA
|
|
||||||
#define CAMERA ENABLED
|
|
||||||
#endif
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// GRIPPER control
|
// GRIPPER control
|
||||||
//
|
//
|
||||||
|
@ -234,7 +234,7 @@ bool Rover::set_mode(Mode &new_mode, ModeReason reason)
|
|||||||
fence.manual_recovery_start();
|
fence.manual_recovery_start();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if CAMERA == ENABLED
|
#if AP_CAMERA_ENABLED
|
||||||
camera.set_is_auto_mode(control_mode->mode_number() == Mode::Number::AUTO);
|
camera.set_is_auto_mode(control_mode->mode_number() == Mode::Number::AUTO);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user