APM:Libraries
AP_Mount_SoloGimbal.h
Go to the documentation of this file.
1 /*
2  MAVLink enabled mount backend class
3  */
4 #pragma once
5 
6 
7 #include <AP_HAL/AP_HAL.h>
8 #include <AP_AHRS/AP_AHRS.h>
9 
10 #if AP_AHRS_NAVEKF_AVAILABLE
11 #include <AP_Math/AP_Math.h>
12 #include <AP_Common/AP_Common.h>
13 #include <AP_GPS/AP_GPS.h>
15 #include <RC_Channel/RC_Channel.h>
16 #include "AP_Mount_Backend.h"
17 #include "SoloGimbal.h"
18 
19 
20 class AP_Mount_SoloGimbal : public AP_Mount_Backend
21 {
22 
23 public:
24  // Constructor
25  AP_Mount_SoloGimbal(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  // handle a GIMBAL_REPORT message
43  virtual void handle_gimbal_report(mavlink_channel_t chan, mavlink_message_t *msg);
44  virtual void handle_gimbal_torque_report(mavlink_channel_t chan, mavlink_message_t *msg);
45  virtual void handle_param_value(mavlink_message_t *msg);
46 
47  // send a GIMBAL_REPORT message to the GCS
48  virtual void send_gimbal_report(mavlink_channel_t chan);
49 
50  virtual void update_fast();
51 
52 private:
53  // internal variables
54  bool _initialised; // true once the driver has been initialised
55 
56  // Write a gimbal measurament and estimation data packet
57  void Log_Write_Gimbal(SoloGimbal &gimbal);
58 
59  bool _params_saved;
60 
61  SoloGimbal _gimbal;
62 };
63 
64 #endif // AP_AHRS_NAVEKF_AVAILABLE
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
virtual void handle_gimbal_report(mavlink_channel_t chan, mavlink_message_t *msg)
virtual void set_mode(enum MAV_MOUNT_MODE mode)=0
virtual void update()=0
virtual void status_msg(mavlink_channel_t chan)
virtual void send_gimbal_report(mavlink_channel_t chan)
virtual void update_fast()
RC_Channel manager, with EEPROM-backed storage of constants.
static int state
Definition: Util.cpp:20
Common definitions and utility routines for the ArduPilot libraries.
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
virtual void handle_param_value(mavlink_message_t *msg)
virtual void init(const AP_SerialManager &serial_manager)=0
virtual bool has_pan_control() const =0