AP_Mount: add HAL_MOUNT_STORMSERIAL_ENABLED build option
This commit is contained in:
parent
59916d0327
commit
d24d3c0af8
@ -469,10 +469,12 @@ void AP_Mount::init()
|
||||
_num_instances++;
|
||||
#endif
|
||||
|
||||
#if HAL_MOUNT_STORM32SERIAL_ENABLED
|
||||
// check for SToRM32 mounts using serial protocol
|
||||
} else if (mount_type == Mount_Type_SToRM32_serial) {
|
||||
_backends[instance] = new AP_Mount_SToRM32_serial(*this, state[instance], instance);
|
||||
_num_instances++;
|
||||
#endif
|
||||
|
||||
#if HAL_MOUNT_GREMSY_ENABLED
|
||||
// check for Gremsy mounts
|
||||
|
@ -1,5 +1,6 @@
|
||||
#include "AP_Mount_SToRM32_serial.h"
|
||||
#if HAL_MOUNT_ENABLED
|
||||
|
||||
#if HAL_MOUNT_STORM32SERIAL_ENABLED
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
#include <GCS_MAVLink/include/mavlink/v2.0/checksum.h>
|
||||
@ -296,4 +297,4 @@ void AP_Mount_SToRM32_serial::parse_reply() {
|
||||
break;
|
||||
}
|
||||
}
|
||||
#endif // HAL_MOUNT_ENABLED
|
||||
#endif // HAL_MOUNT_STORM32SERIAL_ENABLED
|
||||
|
@ -3,14 +3,19 @@
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include "AP_Mount_Backend.h"
|
||||
|
||||
#ifndef HAL_MOUNT_STORM32SERIAL_ENABLED
|
||||
#define HAL_MOUNT_STORM32SERIAL_ENABLED HAL_MOUNT_ENABLED
|
||||
#endif
|
||||
|
||||
#if HAL_MOUNT_STORM32SERIAL_ENABLED
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
#include "AP_Mount_Backend.h"
|
||||
#if HAL_MOUNT_ENABLED
|
||||
|
||||
#define AP_MOUNT_STORM32_SERIAL_RESEND_MS 1000 // resend angle targets to gimbal once per second
|
||||
|
||||
@ -148,4 +153,4 @@ private:
|
||||
// keep the last _current_angle values
|
||||
Vector3l _current_angle;
|
||||
};
|
||||
#endif // HAL_MOUNT_ENABLED
|
||||
#endif // HAL_MOUNT_STORM32SERIAL_ENABLED
|
||||
|
Loading…
Reference in New Issue
Block a user