Plane: make mount/gimbal inclusion configurable per-board
This commit is contained in:
parent
e91ae19544
commit
b649afe9e5
@ -69,9 +69,9 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
|
||||
SCHED_TASK(check_long_failsafe, 3, 400),
|
||||
SCHED_TASK(rpm_update, 10, 100),
|
||||
SCHED_TASK(airspeed_ratio_update, 1, 100),
|
||||
#if MOUNT == ENABLED
|
||||
#if HAL_MOUNT_ENABLED
|
||||
SCHED_TASK_CLASS(AP_Mount, &plane.camera_mount, update, 50, 100),
|
||||
#endif // MOUNT == ENABLED
|
||||
#endif // HAL_MOUNT_ENABLED
|
||||
#if CAMERA == ENABLED
|
||||
SCHED_TASK_CLASS(AP_Camera, &plane.camera, update, 50, 100),
|
||||
#endif // CAMERA == ENABLED
|
||||
|
@ -999,7 +999,7 @@ const AP_Param::Info Plane::var_info[] = {
|
||||
// @Path: ../libraries/AP_TECS/AP_TECS.cpp
|
||||
GOBJECT(TECS_controller, "TECS_", AP_TECS),
|
||||
|
||||
#if MOUNT == ENABLED
|
||||
#if HAL_MOUNT_ENABLED
|
||||
// @Group: MNT
|
||||
// @Path: ../libraries/AP_Mount/AP_Mount.cpp
|
||||
GOBJECT(camera_mount, "MNT", AP_Mount),
|
||||
|
@ -756,7 +756,7 @@ private:
|
||||
uint32_t last_home_update_ms;
|
||||
|
||||
// Camera/Antenna mount tracking and stabilisation stuff
|
||||
#if MOUNT == ENABLED
|
||||
#if HAL_MOUNT_ENABLED
|
||||
AP_Mount camera_mount;
|
||||
#endif
|
||||
|
||||
|
@ -152,7 +152,7 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
|
||||
autotune_enable(cmd.p1);
|
||||
break;
|
||||
|
||||
#if MOUNT == ENABLED
|
||||
#if HAL_MOUNT_ENABLED
|
||||
// Sets the region of interest (ROI) for a sensor set or the
|
||||
// vehicle itself. This can then be used by the vehicles control
|
||||
// system to control the vehicle attitude and the attitude of various
|
||||
|
@ -131,13 +131,6 @@
|
||||
# define CAMERA ENABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// MOUNT (ANTENNA OR CAMERA)
|
||||
//
|
||||
#ifndef MOUNT
|
||||
#define MOUNT ENABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// FLIGHT AND NAVIGATION CONTROL
|
||||
|
@ -108,7 +108,7 @@ void Plane::init_ardupilot()
|
||||
|
||||
init_rc_in(); // sets up rc channels from radio
|
||||
|
||||
#if MOUNT == ENABLED
|
||||
#if HAL_MOUNT_ENABLED
|
||||
// initialise camera mount
|
||||
camera_mount.init();
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user