mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_Mount: add HAL_MOUNT_STORM32MAVLINK_ENABLED build option
This commit is contained in:
parent
4f0ee1276b
commit
59916d0327
@ -462,10 +462,12 @@ void AP_Mount::init()
|
|||||||
_num_instances++;
|
_num_instances++;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if HAL_MOUNT_STORM32MAVLINK_ENABLED
|
||||||
// check for SToRM32 mounts using MAVLink protocol
|
// check for SToRM32 mounts using MAVLink protocol
|
||||||
} else if (mount_type == Mount_Type_SToRM32) {
|
} else if (mount_type == Mount_Type_SToRM32) {
|
||||||
_backends[instance] = new AP_Mount_SToRM32(*this, state[instance], instance);
|
_backends[instance] = new AP_Mount_SToRM32(*this, state[instance], instance);
|
||||||
_num_instances++;
|
_num_instances++;
|
||||||
|
#endif
|
||||||
|
|
||||||
// check for SToRM32 mounts using serial protocol
|
// check for SToRM32 mounts using serial protocol
|
||||||
} else if (mount_type == Mount_Type_SToRM32_serial) {
|
} else if (mount_type == Mount_Type_SToRM32_serial) {
|
||||||
|
@ -1,5 +1,6 @@
|
|||||||
#include "AP_Mount_SToRM32.h"
|
#include "AP_Mount_SToRM32.h"
|
||||||
#if HAL_MOUNT_ENABLED
|
|
||||||
|
#if HAL_MOUNT_STORM32MAVLINK_ENABLED
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
|
|
||||||
@ -172,4 +173,4 @@ void AP_Mount_SToRM32::send_do_mount_control(float pitch_deg, float roll_deg, fl
|
|||||||
// store time of send
|
// store time of send
|
||||||
_last_send = AP_HAL::millis();
|
_last_send = AP_HAL::millis();
|
||||||
}
|
}
|
||||||
#endif // HAL_MOUNT_ENABLED
|
#endif // HAL_MOUNT_STORM32MAVLINK_ENABLED
|
||||||
|
@ -5,7 +5,11 @@
|
|||||||
|
|
||||||
#include "AP_Mount_Backend.h"
|
#include "AP_Mount_Backend.h"
|
||||||
|
|
||||||
#if HAL_MOUNT_ENABLED
|
#ifndef HAL_MOUNT_STORM32MAVLINK_ENABLED
|
||||||
|
#define HAL_MOUNT_STORM32MAVLINK_ENABLED HAL_MOUNT_ENABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HAL_MOUNT_STORM32MAVLINK_ENABLED
|
||||||
|
|
||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
@ -49,4 +53,4 @@ private:
|
|||||||
mavlink_channel_t _chan; // mavlink channel used to communicate with gimbal
|
mavlink_channel_t _chan; // mavlink channel used to communicate with gimbal
|
||||||
uint32_t _last_send; // system time of last do_mount_control sent to gimbal
|
uint32_t _last_send; // system time of last do_mount_control sent to gimbal
|
||||||
};
|
};
|
||||||
#endif // HAL_MOUNT_ENABLED
|
#endif // HAL_MOUNT_STORM32MAVLINK_ENABLED
|
||||||
|
Loading…
Reference in New Issue
Block a user