Browse Source

AP_Mount: Gremsy only enabled on >1MB boards

apm_2208
Randy Mackay 3 years ago
parent
commit
34f327404a
  1. 2
      libraries/AP_Mount/AP_Mount.cpp
  2. 7
      libraries/AP_Mount/AP_Mount_Gremsy.cpp
  3. 17
      libraries/AP_Mount/AP_Mount_Gremsy.h

2
libraries/AP_Mount/AP_Mount.cpp

@ -468,10 +468,12 @@ void AP_Mount::init() @@ -468,10 +468,12 @@ void AP_Mount::init()
_backends[instance] = new AP_Mount_SToRM32_serial(*this, state[instance], instance);
_num_instances++;
#if HAL_MOUNT_GREMSY_ENABLED
// check for Gremsy mounts
} else if (mount_type == Mount_Type_Gremsy) {
_backends[instance] = new AP_Mount_Gremsy(*this, state[instance], instance);
_num_instances++;
#endif // HAL_MOUNT_GREMSY_ENABLED
}
// init new instance

7
libraries/AP_Mount/AP_Mount_Gremsy.cpp

@ -1,7 +1,6 @@ @@ -1,7 +1,6 @@
#include "AP_Mount_Gremsy.h"
#if HAL_MOUNT_ENABLED
#include <AP_HAL/AP_HAL.h>
#include <GCS_MAVLink/GCS.h>
#if HAL_MOUNT_GREMSY_ENABLED
extern const AP_HAL::HAL& hal;
@ -308,4 +307,4 @@ void AP_Mount_Gremsy::send_gimbal_device_set_attitude(float roll_rad, float pitc @@ -308,4 +307,4 @@ void AP_Mount_Gremsy::send_gimbal_device_set_attitude(float roll_rad, float pitc
NAN, NAN, NAN); // angular velocities
}
#endif // HAL_MOUNT_ENABLED
#endif // HAL_MOUNT_GREMSY_ENABLED

17
libraries/AP_Mount/AP_Mount_Gremsy.h

@ -1,18 +1,21 @@ @@ -1,18 +1,21 @@
/*
SToRM32 mount using serial protocol backend class
Gremsy mount backend class
*/
#pragma once
#include "AP_Mount_Backend.h"
#ifndef HAL_MOUNT_GREMSY_ENABLED
#define HAL_MOUNT_GREMSY_ENABLED (HAL_MOUNT_ENABLED && !HAL_MINIMIZE_FEATURES && BOARD_FLASH_SIZE > 1024)
#endif
#if HAL_MOUNT_GREMSY_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
class AP_Mount_Gremsy : public AP_Mount_Backend
{
@ -76,4 +79,4 @@ private: @@ -76,4 +79,4 @@ private:
mavlink_gimbal_device_attitude_status_t _gimbal_device_attitude_status; // copy of most recently received gimbal status
uint32_t _sent_gimbal_device_attitude_status_ms; // time_boot_ms field of gimbal_device_status message last forwarded to the GCS (used to prevent sending duplicates)
};
#endif // HAL_MOUNT_ENABLED
#endif // HAL_MOUNT_GREMSY_ENABLED

Loading…
Cancel
Save