APM:Libraries
SoloGimbal.h
Go to the documentation of this file.
1 /************************************************************
2 * SoloGimbal -- library to control a 3 axis rate gimbal. *
3 * *
4 * Author: Arthur Benemann, Paul Riseborough; *
5 * *
6 ************************************************************/
7 #pragma once
8 
9 #include <AP_HAL/AP_HAL.h>
10 #include <AP_AHRS/AP_AHRS.h>
11 #if AP_AHRS_NAVEKF_AVAILABLE
12 
13 #include "AP_Mount.h"
14 #include "SoloGimbalEKF.h"
15 #include <AP_Math/AP_Math.h>
16 #include <AP_Common/AP_Common.h>
17 #include <AP_GPS/AP_GPS.h>
20 
21 #include "SoloGimbal_Parameters.h"
22 
23 enum gimbal_state_t {
24  GIMBAL_STATE_NOT_PRESENT = 0,
25  GIMBAL_STATE_PRESENT_INITIALIZING,
26  GIMBAL_STATE_PRESENT_ALIGNING,
27  GIMBAL_STATE_PRESENT_RUNNING
28 };
29 
30 enum gimbal_mode_t {
31  GIMBAL_MODE_IDLE = 0,
32  GIMBAL_MODE_POS_HOLD,
33  GIMBAL_MODE_POS_HOLD_FF,
34  GIMBAL_MODE_STABILIZE
35 };
36 
37 class SoloGimbal : AP_AccelCal_Client
38 {
39 public:
40  //Constructor
41  SoloGimbal(const AP_AHRS_NavEKF &ahrs) :
42  _ekf(ahrs),
43  _ahrs(ahrs),
44  _state(GIMBAL_STATE_NOT_PRESENT),
45  _vehicle_yaw_rate_ef_filt(0.0f),
46  _vehicle_to_gimbal_quat(),
47  _vehicle_to_gimbal_quat_filt(),
48  _filtered_joint_angles(),
49  _last_report_msg_ms(0),
50  _max_torque(5000.0f),
51  _ang_vel_mag_filt(0),
52  _lockedToBody(false),
53  _log_dt(0),
54  _log_del_ang(),
55  _log_del_vel()
56  {
58  }
59 
60  void update_target(Vector3f newTarget);
61  void receive_feedback(mavlink_channel_t chan, mavlink_message_t *msg);
62 
63  void update_fast();
64 
65  bool present();
66  bool aligned();
67 
68  void set_lockedToBody(bool val) { _lockedToBody = val; }
69 
70  void write_logs();
71 
72  float get_log_dt() { return _log_dt; }
73 
74  void disable_torque_report() { _gimbalParams.set_param(GMB_PARAM_GMB_SND_TORQUE, 0); }
75  void fetch_params() { _gimbalParams.fetch_params(); }
76 
77  void handle_param_value(mavlink_message_t *msg) {
78  _gimbalParams.handle_param_value(msg);
79  }
80 
81 private:
82  // private methods
83  void update_estimators();
84  void send_controls(mavlink_channel_t chan);
85  void extract_feedback(const mavlink_gimbal_report_t& report_msg);
86  void update_joint_angle_est();
87 
88  Vector3f get_ang_vel_dem_yaw(const Quaternion &quatEst);
89  Vector3f get_ang_vel_dem_tilt(const Quaternion &quatEst);
90  Vector3f get_ang_vel_dem_feedforward(const Quaternion &quatEst);
91  Vector3f get_ang_vel_dem_gyro_bias();
92  Vector3f get_ang_vel_dem_body_lock();
93 
94  void gimbal_ang_vel_to_joint_rates(const Vector3f& ang_vel, Vector3f& joint_rates);
95  void joint_rates_to_gimbal_ang_vel(const Vector3f& joint_rates, Vector3f& ang_vel);
96 
97  void readVehicleDeltaAngle(uint8_t ins_index, Vector3f &dAng);
98 
101  bool _acal_get_saving();
102  AccelCalibrator* _acal_get_calibrator(uint8_t instance);
103 
104  gimbal_mode_t get_mode();
105 
106  bool joints_near_limits();
107 
108  // private member variables
109  SoloGimbalEKF _ekf; // state of small EKF for gimbal
110  const AP_AHRS_NavEKF &_ahrs; // Main EKF
111 
112  gimbal_state_t _state;
113 
114  struct {
115  float delta_time;
116  Vector3f delta_angles;
117  Vector3f delta_velocity;
118  Vector3f joint_angles;
119  } _measurement;
120 
121  float _vehicle_yaw_rate_ef_filt;
122 
123  static const uint8_t _compid = MAV_COMP_ID_GIMBAL;
124 
125  // joint angle filter states
126  Vector3f _vehicle_delta_angles;
127 
128  Quaternion _vehicle_to_gimbal_quat;
129  Quaternion _vehicle_to_gimbal_quat_filt;
130  Vector3f _filtered_joint_angles;
131 
132  uint32_t _last_report_msg_ms;
133 
134  float _max_torque;
135 
136  float _ang_vel_mag_filt;
137 
138  Vector3f _ang_vel_dem_rads; // rad/s
139  Vector3f _att_target_euler_rad; // desired earth-frame roll, tilt and pan angles in radians
140 
141  bool _lockedToBody;
142 
143  SoloGimbal_Parameters _gimbalParams;
144 
145  AccelCalibrator _calibrator;
146 
147  float _log_dt;
148  Vector3f _log_del_ang;
149  Vector3f _log_del_vel;
150 };
151 
152 #endif // AP_AHRS_NAVEKF_AVAILABLE
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
static void register_client(AP_AccelCal_Client *client)
virtual bool _acal_get_saving()
Definition: AP_AccelCal.h:84
#define f(i)
virtual AccelCalibrator * _acal_get_calibrator(uint8_t instance)=0
Common definitions and utility routines for the ArduPilot libraries.
virtual void _acal_save_calibrations()=0
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
virtual bool _acal_get_ready_to_sample()
Definition: AP_AccelCal.h:85