3 #if AP_AHRS_NAVEKF_AVAILABLE    16     _gimbal(frontend._ahrs)
    26 void AP_Mount_SoloGimbal::update_fast()
    28     _gimbal.update_fast();
    32 void AP_Mount_SoloGimbal::update()
    42         case MAV_MOUNT_MODE_RETRACT:
    43             _gimbal.set_lockedToBody(
true);
    47         case MAV_MOUNT_MODE_NEUTRAL:
    49             _gimbal.set_lockedToBody(
false);
    58         case MAV_MOUNT_MODE_MAVLINK_TARGETING:
    59             _gimbal.set_lockedToBody(
false);
    64         case MAV_MOUNT_MODE_RC_TARGETING:
    65             _gimbal.set_lockedToBody(
false);
    71         case MAV_MOUNT_MODE_GPS_POINT:
    72             _gimbal.set_lockedToBody(
false);
    85 bool AP_Mount_SoloGimbal::has_pan_control()
 const    92 void AP_Mount_SoloGimbal::set_mode(
enum MAV_MOUNT_MODE mode)
   104 void AP_Mount_SoloGimbal::status_msg(mavlink_channel_t 
chan)
   106     if (_gimbal.aligned()) {
   117 void AP_Mount_SoloGimbal::handle_gimbal_report(mavlink_channel_t chan, mavlink_message_t *msg)
   120     _gimbal.receive_feedback(chan,msg);
   128         _gimbal.fetch_params();       
   129         _params_saved = 
true;
   132     if (_gimbal.get_log_dt() > 1.0f/25.0f) {
   133         _gimbal.write_logs();
   137 void AP_Mount_SoloGimbal::handle_param_value(mavlink_message_t *msg)
   139     _gimbal.handle_param_value(msg);
   145 void AP_Mount_SoloGimbal::handle_gimbal_torque_report(mavlink_channel_t chan, mavlink_message_t *msg)
   147     _gimbal.disable_torque_report();
   153 void AP_Mount_SoloGimbal::send_gimbal_report(mavlink_channel_t chan)
   157 #endif // AP_AHRS_NAVEKF_AVAILABLE 
static AP_SerialManager serial_manager
 
Vector3f _angle_ef_target_rad
 
void update_targets_from_rc()
 
Interface definition for the various Ground Control System. 
 
bool logging_started(void)
 
AP_Mount::mount_state & _state
 
void calc_angle_to_location(const struct Location &target, Vector3f &angles_to_target_rad, bool calc_tilt, bool calc_pan, bool relative_pan=true)
 
struct Location _roi_target
 
static DataFlash_Class * instance(void)
 
Receiving valid messages and 2D lock. 
 
static void disable_channel_routing(mavlink_channel_t chan)
 
AP_Vector3f _neutral_angles
 
AP_HAL::AnalogSource * chan
 
void init()
Generic board initialization function. 
 
virtual void set_mode(enum MAV_MOUNT_MODE mode)
 
MAV_MOUNT_MODE get_mode(void) const