APM:Libraries
AP_Mount_SToRM32.h
Go to the documentation of this file.
1 /*
2  SToRM32 mount backend class
3  */
4 #pragma once
5 
6 #include <AP_HAL/AP_HAL.h>
7 #include <AP_AHRS/AP_AHRS.h>
8 
9 #include <AP_Math/AP_Math.h>
10 #include <AP_Common/AP_Common.h>
11 #include <AP_GPS/AP_GPS.h>
12 #include <GCS_MAVLink/GCS.h>
14 #include <RC_Channel/RC_Channel.h>
15 #include "AP_Mount_Backend.h"
16 
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
19 
21 {
22 
23 public:
24  // Constructor
25  AP_Mount_SToRM32(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance);
26 
27  // init - performs any required initialisation for this instance
28  virtual void init(const AP_SerialManager& serial_manager) {}
29 
30  // update mount position - should be called periodically
31  virtual void update();
32 
33  // has_pan_control - returns true if this mount can control it's pan (required for multicopters)
34  virtual bool has_pan_control() const;
35 
36  // set_mode - sets mount's mode
37  virtual void set_mode(enum MAV_MOUNT_MODE mode);
38 
39  // status_msg - called to allow mounts to send their status to GCS using the MOUNT_STATUS message
40  virtual void status_msg(mavlink_channel_t chan);
41 
42 private:
43 
44  // search for gimbal in GCS_MAVLink routing table
45  void find_gimbal();
46 
47  // send_do_mount_control - send a COMMAND_LONG containing a do_mount_control message
48  void send_do_mount_control(float pitch_deg, float roll_deg, float yaw_deg, enum MAV_MOUNT_MODE mount_mode);
49 
50  // internal variables
51  bool _initialised; // true once the driver has been initialised
52  uint8_t _sysid; // sysid of gimbal
53  uint8_t _compid; // component id of gimbal
54  mavlink_channel_t _chan; // mavlink channel used to communicate with gimbal. Currently hard-coded to Telem2
55  uint32_t _last_send; // system time of last do_mount_control sent to gimbal
56 };
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
virtual void set_mode(enum MAV_MOUNT_MODE mode)
mavlink_channel_t _chan
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.
static int state
Definition: Util.cpp:20
virtual void update()
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
Definition: AnalogIn.cpp:8