17 #define AP_MOUNT_STORM32_RESEND_MS 1000 // resend angle targets to gimbal once per second 18 #define AP_MOUNT_STORM32_SEARCH_MS 60000 // search for gimbal for 1 minute after startup 37 virtual void set_mode(
enum MAV_MOUNT_MODE mode);
48 void send_do_mount_control(
float pitch_deg,
float roll_deg,
float yaw_deg,
enum MAV_MOUNT_MODE mount_mode);
static AP_SerialManager serial_manager
virtual void set_mode(enum MAV_MOUNT_MODE mode)
Interface definition for the various Ground Control System.
virtual bool has_pan_control() const
virtual void status_msg(mavlink_channel_t chan)
virtual void init(const AP_SerialManager &serial_manager)
void send_do_mount_control(float pitch_deg, float roll_deg, float yaw_deg, enum MAV_MOUNT_MODE mount_mode)
RC_Channel manager, with EEPROM-backed storage of constants.
Common definitions and utility routines for the ArduPilot libraries.
AP_Mount_SToRM32(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance)
AP_HAL::AnalogSource * chan