Rover: make mount/gimbal inclusion configurable per-board
This commit is contained in:
parent
b649afe9e5
commit
6d87d61c7b
@ -298,7 +298,7 @@ const AP_Param::Info Rover::var_info[] = {
|
||||
GOBJECT(camera, "CAM_", AP_Camera),
|
||||
#endif
|
||||
|
||||
#if MOUNT == ENABLED
|
||||
#if HAL_MOUNT_ENABLED
|
||||
// @Group: MNT
|
||||
// @Path: ../libraries/AP_Mount/AP_Mount.cpp
|
||||
GOBJECT(camera_mount, "MNT", AP_Mount),
|
||||
|
@ -74,7 +74,7 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
|
||||
SCHED_TASK_CLASS(AP_Gripper, &rover.g2.gripper, update, 10, 75),
|
||||
#endif
|
||||
SCHED_TASK(rpm_update, 10, 100),
|
||||
#if MOUNT == ENABLED
|
||||
#if HAL_MOUNT_ENABLED
|
||||
SCHED_TASK_CLASS(AP_Mount, &rover.camera_mount, update, 50, 200),
|
||||
#endif
|
||||
#if CAMERA == ENABLED
|
||||
|
@ -186,7 +186,7 @@ private:
|
||||
#endif
|
||||
|
||||
// Camera/Antenna mount tracking and stabilisation stuff
|
||||
#if MOUNT == ENABLED
|
||||
#if HAL_MOUNT_ENABLED
|
||||
AP_Mount camera_mount;
|
||||
#endif
|
||||
|
||||
|
@ -59,13 +59,6 @@
|
||||
#define GROUND_START_DELAY 0
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// MOUNT (ANTENNA OR CAMERA)
|
||||
//
|
||||
#ifndef MOUNT
|
||||
#define MOUNT ENABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// CAMERA control
|
||||
//
|
||||
|
@ -387,7 +387,7 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd)
|
||||
do_set_home(cmd);
|
||||
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
|
||||
|
@ -92,7 +92,7 @@ void Rover::init_ardupilot()
|
||||
|
||||
relay.init();
|
||||
|
||||
#if MOUNT == ENABLED
|
||||
#if HAL_MOUNT_ENABLED
|
||||
// initialise camera mount
|
||||
camera_mount.init();
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user