SoloGimbal.cpp 18 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501
  1. #include <AP_HAL/AP_HAL.h>
  2. #include <AP_AHRS/AP_AHRS.h>
  3. #if AP_AHRS_NAVEKF_AVAILABLE
  4. #include "SoloGimbal.h"
  5. #include <stdio.h>
  6. #include <GCS_MAVLink/GCS.h>
  7. #include <AP_Logger/AP_Logger.h>
  8. extern const AP_HAL::HAL& hal;
  9. bool SoloGimbal::present()
  10. {
  11. if (_state != GIMBAL_STATE_NOT_PRESENT && AP_HAL::millis()-_last_report_msg_ms > 3000) {
  12. // gimbal went away
  13. _state = GIMBAL_STATE_NOT_PRESENT;
  14. return false;
  15. }
  16. return _state != GIMBAL_STATE_NOT_PRESENT;
  17. }
  18. bool SoloGimbal::aligned()
  19. {
  20. return present() && _state == GIMBAL_STATE_PRESENT_RUNNING;
  21. }
  22. gimbal_mode_t SoloGimbal::get_mode()
  23. {
  24. const AP_AHRS_NavEKF &_ahrs = AP::ahrs_navekf();
  25. if ((_gimbalParams.initialized() && is_zero(_gimbalParams.get_K_rate())) || (_ahrs.get_rotation_body_to_ned().c.z < 0 && !(_lockedToBody || _calibrator.running()))) {
  26. return GIMBAL_MODE_IDLE;
  27. } else if (!_ekf.getStatus()) {
  28. return GIMBAL_MODE_POS_HOLD;
  29. } else if (_calibrator.running() || _lockedToBody) {
  30. return GIMBAL_MODE_POS_HOLD_FF;
  31. } else {
  32. return GIMBAL_MODE_STABILIZE;
  33. }
  34. }
  35. void SoloGimbal::receive_feedback(mavlink_channel_t chan, const mavlink_message_t &msg)
  36. {
  37. mavlink_gimbal_report_t report_msg;
  38. mavlink_msg_gimbal_report_decode(&msg, &report_msg);
  39. uint32_t tnow_ms = AP_HAL::millis();
  40. _last_report_msg_ms = tnow_ms;
  41. _gimbalParams.set_channel(chan);
  42. if (report_msg.target_system != 1) {
  43. _state = GIMBAL_STATE_NOT_PRESENT;
  44. } else {
  45. GCS_MAVLINK::set_channel_private(chan);
  46. }
  47. switch(_state) {
  48. case GIMBAL_STATE_NOT_PRESENT:
  49. // gimbal was just connected or we just rebooted, transition to PRESENT_INITIALIZING
  50. _gimbalParams.reset();
  51. _gimbalParams.set_param(GMB_PARAM_GMB_SYSID, 1);
  52. _state = GIMBAL_STATE_PRESENT_INITIALIZING;
  53. break;
  54. case GIMBAL_STATE_PRESENT_INITIALIZING:
  55. _gimbalParams.update();
  56. if (_gimbalParams.initialized()) {
  57. // parameters done initializing, finalize initialization and transition to aligning
  58. extract_feedback(report_msg);
  59. _ang_vel_mag_filt = 20;
  60. _filtered_joint_angles = _measurement.joint_angles;
  61. _vehicle_to_gimbal_quat_filt.from_vector312(_filtered_joint_angles.x,_filtered_joint_angles.y,_filtered_joint_angles.z);
  62. _ekf.reset();
  63. _state = GIMBAL_STATE_PRESENT_ALIGNING;
  64. }
  65. break;
  66. case GIMBAL_STATE_PRESENT_ALIGNING:
  67. _gimbalParams.update();
  68. extract_feedback(report_msg);
  69. update_estimators();
  70. if (_ekf.getStatus()) {
  71. // EKF done aligning, transition to running
  72. _state = GIMBAL_STATE_PRESENT_RUNNING;
  73. }
  74. break;
  75. case GIMBAL_STATE_PRESENT_RUNNING:
  76. _gimbalParams.update();
  77. extract_feedback(report_msg);
  78. update_estimators();
  79. break;
  80. }
  81. send_controls(chan);
  82. }
  83. void SoloGimbal::send_controls(mavlink_channel_t chan)
  84. {
  85. if (_state == GIMBAL_STATE_PRESENT_RUNNING) {
  86. // get the gimbal quaternion estimate
  87. Quaternion quatEst;
  88. _ekf.getQuat(quatEst);
  89. // run rate controller
  90. _ang_vel_dem_rads.zero();
  91. switch(get_mode()) {
  92. case GIMBAL_MODE_POS_HOLD_FF: {
  93. _ang_vel_dem_rads += get_ang_vel_dem_body_lock();
  94. _ang_vel_dem_rads += get_ang_vel_dem_gyro_bias();
  95. float _ang_vel_dem_radsLen = _ang_vel_dem_rads.length();
  96. if (_ang_vel_dem_radsLen > radians(400)) {
  97. _ang_vel_dem_rads *= radians(400)/_ang_vel_dem_radsLen;
  98. }
  99. if (HAVE_PAYLOAD_SPACE(chan, GIMBAL_CONTROL)) {
  100. mavlink_msg_gimbal_control_send(chan, mavlink_system.sysid, _compid,
  101. _ang_vel_dem_rads.x, _ang_vel_dem_rads.y, _ang_vel_dem_rads.z);
  102. }
  103. break;
  104. }
  105. case GIMBAL_MODE_STABILIZE: {
  106. _ang_vel_dem_rads += get_ang_vel_dem_yaw(quatEst);
  107. _ang_vel_dem_rads += get_ang_vel_dem_tilt(quatEst);
  108. _ang_vel_dem_rads += get_ang_vel_dem_feedforward(quatEst);
  109. _ang_vel_dem_rads += get_ang_vel_dem_gyro_bias();
  110. float ang_vel_dem_norm = _ang_vel_dem_rads.length();
  111. if (ang_vel_dem_norm > radians(400)) {
  112. _ang_vel_dem_rads *= radians(400)/ang_vel_dem_norm;
  113. }
  114. if (HAVE_PAYLOAD_SPACE(chan, GIMBAL_CONTROL)) {
  115. mavlink_msg_gimbal_control_send(chan, mavlink_system.sysid, _compid,
  116. _ang_vel_dem_rads.x, _ang_vel_dem_rads.y, _ang_vel_dem_rads.z);
  117. }
  118. break;
  119. }
  120. default:
  121. case GIMBAL_MODE_IDLE:
  122. case GIMBAL_MODE_POS_HOLD:
  123. break;
  124. }
  125. }
  126. // set GMB_POS_HOLD
  127. if (get_mode() == GIMBAL_MODE_POS_HOLD) {
  128. _gimbalParams.set_param(GMB_PARAM_GMB_POS_HOLD, 1);
  129. } else {
  130. _gimbalParams.set_param(GMB_PARAM_GMB_POS_HOLD, 0);
  131. }
  132. // set GMB_MAX_TORQUE
  133. float max_torque;
  134. _gimbalParams.get_param(GMB_PARAM_GMB_MAX_TORQUE, max_torque, 0);
  135. if (!is_equal(max_torque,_max_torque) && !is_zero(max_torque)) {
  136. _max_torque = max_torque;
  137. }
  138. if (!hal.util->get_soft_armed() || joints_near_limits()) {
  139. _gimbalParams.set_param(GMB_PARAM_GMB_MAX_TORQUE, _max_torque);
  140. } else {
  141. _gimbalParams.set_param(GMB_PARAM_GMB_MAX_TORQUE, 0);
  142. }
  143. }
  144. void SoloGimbal::extract_feedback(const mavlink_gimbal_report_t& report_msg)
  145. {
  146. _measurement.delta_time = report_msg.delta_time;
  147. _measurement.delta_angles.x = report_msg.delta_angle_x;
  148. _measurement.delta_angles.y = report_msg.delta_angle_y;
  149. _measurement.delta_angles.z = report_msg.delta_angle_z;
  150. _measurement.delta_velocity.x = report_msg.delta_velocity_x,
  151. _measurement.delta_velocity.y = report_msg.delta_velocity_y;
  152. _measurement.delta_velocity.z = report_msg.delta_velocity_z;
  153. _measurement.joint_angles.x = report_msg.joint_roll;
  154. _measurement.joint_angles.y = report_msg.joint_el;
  155. _measurement.joint_angles.z = report_msg.joint_az;
  156. if (_calibrator.get_status() == ACCEL_CAL_COLLECTING_SAMPLE) {
  157. _calibrator.new_sample(_measurement.delta_velocity,_measurement.delta_time);
  158. }
  159. _measurement.delta_angles -= _gimbalParams.get_gyro_bias() * _measurement.delta_time;
  160. _measurement.joint_angles -= _gimbalParams.get_joint_bias();
  161. _measurement.delta_velocity -= _gimbalParams.get_accel_bias() * _measurement.delta_time;
  162. Vector3f accel_gain = _gimbalParams.get_accel_gain();
  163. _measurement.delta_velocity.x *= (is_zero(accel_gain.x) ? 1.0f : accel_gain.x);
  164. _measurement.delta_velocity.y *= (is_zero(accel_gain.y) ? 1.0f : accel_gain.y);
  165. _measurement.delta_velocity.z *= (is_zero(accel_gain.z) ? 1.0f : accel_gain.z);
  166. // update _ang_vel_mag_filt, used for accel sample readiness
  167. Vector3f ang_vel = _measurement.delta_angles / _measurement.delta_time;
  168. Vector3f ekf_gyro_bias;
  169. _ekf.getGyroBias(ekf_gyro_bias);
  170. ang_vel -= ekf_gyro_bias;
  171. float alpha = constrain_float(_measurement.delta_time/(_measurement.delta_time+0.5f),0.0f,1.0f);
  172. _ang_vel_mag_filt += (ang_vel.length()-_ang_vel_mag_filt)*alpha;
  173. _ang_vel_mag_filt = MIN(_ang_vel_mag_filt,20.0f);
  174. // get complementary filter inputs
  175. _vehicle_to_gimbal_quat.from_vector312(_measurement.joint_angles.x,_measurement.joint_angles.y,_measurement.joint_angles.z);
  176. // update log deltas
  177. _log_dt += _measurement.delta_time;
  178. _log_del_ang += _measurement.delta_angles;
  179. _log_del_vel += _measurement.delta_velocity;
  180. }
  181. void SoloGimbal::update_estimators()
  182. {
  183. if (_state == GIMBAL_STATE_NOT_PRESENT || _state == GIMBAL_STATE_PRESENT_INITIALIZING) {
  184. return;
  185. }
  186. // Run the gimbal attitude and gyro bias estimator
  187. _ekf.RunEKF(_measurement.delta_time, _measurement.delta_angles, _measurement.delta_velocity, _measurement.joint_angles);
  188. update_joint_angle_est();
  189. }
  190. void SoloGimbal::readVehicleDeltaAngle(uint8_t ins_index, Vector3f &dAng) {
  191. const AP_InertialSensor &ins = AP::ins();
  192. if (ins_index < ins.get_gyro_count()) {
  193. if (!ins.get_delta_angle(ins_index,dAng)) {
  194. dAng = ins.get_gyro(ins_index) / ins.get_sample_rate();
  195. }
  196. }
  197. }
  198. void SoloGimbal::update_fast() {
  199. const AP_InertialSensor &ins = AP::ins();
  200. if (ins.use_gyro(0) && ins.use_gyro(1)) {
  201. // dual gyro mode - average first two gyros
  202. Vector3f dAng;
  203. readVehicleDeltaAngle(0, dAng);
  204. _vehicle_delta_angles += dAng*0.5f;
  205. readVehicleDeltaAngle(1, dAng);
  206. _vehicle_delta_angles += dAng*0.5f;
  207. } else {
  208. // single gyro mode - one of the first two gyros are unhealthy or don't exist
  209. // just read primary gyro
  210. Vector3f dAng;
  211. readVehicleDeltaAngle(ins.get_primary_gyro(), dAng);
  212. _vehicle_delta_angles += dAng;
  213. }
  214. }
  215. void SoloGimbal::update_joint_angle_est()
  216. {
  217. static const float tc = 1.0f;
  218. float dt = _measurement.delta_time;
  219. float alpha = constrain_float(dt/(dt+tc),0.0f,1.0f);
  220. Matrix3f Tvg; // vehicle frame to gimbal frame
  221. _vehicle_to_gimbal_quat.inverse().rotation_matrix(Tvg);
  222. Vector3f delta_angle_bias;
  223. _ekf.getGyroBias(delta_angle_bias);
  224. delta_angle_bias *= dt;
  225. Vector3f joint_del_ang;
  226. gimbal_ang_vel_to_joint_rates((_measurement.delta_angles-delta_angle_bias) - Tvg*_vehicle_delta_angles, joint_del_ang);
  227. _filtered_joint_angles += joint_del_ang;
  228. _filtered_joint_angles += (_measurement.joint_angles-_filtered_joint_angles)*alpha;
  229. _vehicle_to_gimbal_quat_filt.from_vector312(_filtered_joint_angles.x,_filtered_joint_angles.y,_filtered_joint_angles.z);
  230. _vehicle_delta_angles.zero();
  231. }
  232. Vector3f SoloGimbal::get_ang_vel_dem_yaw(const Quaternion &quatEst)
  233. {
  234. static const float tc = 0.1f;
  235. static const float yawErrorLimit = radians(5.7f);
  236. float dt = _measurement.delta_time;
  237. float alpha = dt/(dt+tc);
  238. const AP_AHRS_NavEKF &_ahrs = AP::ahrs_navekf();
  239. Matrix3f Tve = _ahrs.get_rotation_body_to_ned();
  240. Matrix3f Teg;
  241. quatEst.inverse().rotation_matrix(Teg);
  242. //_vehicle_yaw_rate_ef_filt = _ahrs.get_yaw_rate_earth();
  243. // filter the vehicle yaw rate to remove noise
  244. _vehicle_yaw_rate_ef_filt += (_ahrs.get_yaw_rate_earth() - _vehicle_yaw_rate_ef_filt) * alpha;
  245. float yaw_rate_ff = 0;
  246. // calculate an earth-frame yaw rate feed-forward that prevents gimbal from exceeding the maximum yaw error
  247. if (_vehicle_yaw_rate_ef_filt > _gimbalParams.get_K_rate()*yawErrorLimit) {
  248. yaw_rate_ff = _vehicle_yaw_rate_ef_filt-_gimbalParams.get_K_rate()*yawErrorLimit;
  249. } else if (_vehicle_yaw_rate_ef_filt < -_gimbalParams.get_K_rate()*yawErrorLimit) {
  250. yaw_rate_ff = _vehicle_yaw_rate_ef_filt+_gimbalParams.get_K_rate()*yawErrorLimit;
  251. }
  252. // filter the feed-forward to remove noise
  253. //_yaw_rate_ff_ef_filt += (yaw_rate_ff - _yaw_rate_ff_ef_filt) * alpha;
  254. Vector3f gimbalRateDemVecYaw;
  255. gimbalRateDemVecYaw.z = yaw_rate_ff - _gimbalParams.get_K_rate() * _filtered_joint_angles.z / constrain_float(Tve.c.z,0.5f,1.0f);
  256. gimbalRateDemVecYaw.z /= constrain_float(Tve.c.z,0.5f,1.0f);
  257. // rotate the rate demand into gimbal frame
  258. gimbalRateDemVecYaw = Teg * gimbalRateDemVecYaw;
  259. return gimbalRateDemVecYaw;
  260. }
  261. Vector3f SoloGimbal::get_ang_vel_dem_tilt(const Quaternion &quatEst)
  262. {
  263. // Calculate the gimbal 321 Euler angle estimates relative to earth frame
  264. Vector3f eulerEst = quatEst.to_vector312();
  265. // Calculate a demanded quaternion using the demanded roll and pitch and estimated yaw (yaw is slaved to the vehicle)
  266. Quaternion quatDem;
  267. quatDem.from_vector312( _att_target_euler_rad.x,
  268. _att_target_euler_rad.y,
  269. eulerEst.z);
  270. //divide the demanded quaternion by the estimated to get the error
  271. Quaternion quatErr = quatDem / quatEst;
  272. // Convert to a delta rotation
  273. quatErr.normalize();
  274. Vector3f deltaAngErr;
  275. quatErr.to_axis_angle(deltaAngErr);
  276. // multiply the angle error vector by a gain to calculate a demanded gimbal rate required to control tilt
  277. Vector3f gimbalRateDemVecTilt = deltaAngErr * _gimbalParams.get_K_rate();
  278. return gimbalRateDemVecTilt;
  279. }
  280. Vector3f SoloGimbal::get_ang_vel_dem_feedforward(const Quaternion &quatEst)
  281. {
  282. // quaternion demanded at the previous time step
  283. static float lastDem;
  284. // calculate the delta rotation from the last to the current demand where the demand does not incorporate the copters yaw rotation
  285. float delta = _att_target_euler_rad.y - lastDem;
  286. lastDem = _att_target_euler_rad.y;
  287. Vector3f gimbalRateDemVecForward;
  288. gimbalRateDemVecForward.y = delta / _measurement.delta_time;
  289. return gimbalRateDemVecForward;
  290. }
  291. Vector3f SoloGimbal::get_ang_vel_dem_gyro_bias()
  292. {
  293. Vector3f gyroBias;
  294. _ekf.getGyroBias(gyroBias);
  295. return gyroBias + _gimbalParams.get_gyro_bias();
  296. }
  297. Vector3f SoloGimbal::get_ang_vel_dem_body_lock()
  298. {
  299. // Define rotation from vehicle to gimbal using a 312 rotation sequence
  300. Matrix3f Tvg;
  301. _vehicle_to_gimbal_quat_filt.inverse().rotation_matrix(Tvg);
  302. // multiply the joint angles by a gain to calculate a rate vector required to keep the joints centred
  303. Vector3f gimbalRateDemVecBodyLock;
  304. gimbalRateDemVecBodyLock = _filtered_joint_angles * -_gimbalParams.get_K_rate();
  305. joint_rates_to_gimbal_ang_vel(gimbalRateDemVecBodyLock, gimbalRateDemVecBodyLock);
  306. // Add a feedforward term from vehicle gyros
  307. const AP_AHRS_NavEKF &_ahrs = AP::ahrs_navekf();
  308. gimbalRateDemVecBodyLock += Tvg * _ahrs.get_gyro();
  309. return gimbalRateDemVecBodyLock;
  310. }
  311. void SoloGimbal::update_target(const Vector3f &newTarget)
  312. {
  313. // Low-pass filter
  314. _att_target_euler_rad.y = _att_target_euler_rad.y + 0.02f*(newTarget.y - _att_target_euler_rad.y);
  315. // Update tilt
  316. _att_target_euler_rad.y = constrain_float(_att_target_euler_rad.y,radians(-90),radians(0));
  317. }
  318. void SoloGimbal::write_logs()
  319. {
  320. AP_Logger *logger = AP_Logger::get_singleton();
  321. if (logger == nullptr) {
  322. return;
  323. }
  324. uint32_t tstamp = AP_HAL::millis();
  325. Vector3f eulerEst;
  326. Quaternion quatEst;
  327. _ekf.getQuat(quatEst);
  328. quatEst.to_euler(eulerEst.x, eulerEst.y, eulerEst.z);
  329. struct log_Gimbal1 pkt1 = {
  330. LOG_PACKET_HEADER_INIT(LOG_GIMBAL1_MSG),
  331. time_ms : tstamp,
  332. delta_time : _log_dt,
  333. delta_angles_x : _log_del_ang.x,
  334. delta_angles_y : _log_del_ang.y,
  335. delta_angles_z : _log_del_ang.z,
  336. delta_velocity_x : _log_del_vel.x,
  337. delta_velocity_y : _log_del_vel.y,
  338. delta_velocity_z : _log_del_vel.z,
  339. joint_angles_x : _measurement.joint_angles.x,
  340. joint_angles_y : _measurement.joint_angles.y,
  341. joint_angles_z : _measurement.joint_angles.z
  342. };
  343. logger->WriteBlock(&pkt1, sizeof(pkt1));
  344. struct log_Gimbal2 pkt2 = {
  345. LOG_PACKET_HEADER_INIT(LOG_GIMBAL2_MSG),
  346. time_ms : tstamp,
  347. est_sta : (uint8_t) _ekf.getStatus(),
  348. est_x : eulerEst.x,
  349. est_y : eulerEst.y,
  350. est_z : eulerEst.z,
  351. rate_x : _ang_vel_dem_rads.x,
  352. rate_y : _ang_vel_dem_rads.y,
  353. rate_z : _ang_vel_dem_rads.z,
  354. target_x: _att_target_euler_rad.x,
  355. target_y: _att_target_euler_rad.y,
  356. target_z: _att_target_euler_rad.z
  357. };
  358. logger->WriteBlock(&pkt2, sizeof(pkt2));
  359. _log_dt = 0;
  360. _log_del_ang.zero();
  361. _log_del_vel.zero();
  362. }
  363. bool SoloGimbal::joints_near_limits()
  364. {
  365. return fabsf(_measurement.joint_angles.x) > radians(40) || _measurement.joint_angles.y > radians(45) || _measurement.joint_angles.y < -radians(135);
  366. }
  367. AccelCalibrator* SoloGimbal::_acal_get_calibrator(uint8_t instance)
  368. {
  369. if(instance==0 && (present() || _calibrator.get_status() == ACCEL_CAL_SUCCESS)) {
  370. return &_calibrator;
  371. } else {
  372. return nullptr;
  373. }
  374. }
  375. bool SoloGimbal::_acal_get_ready_to_sample()
  376. {
  377. return _ang_vel_mag_filt < radians(10);
  378. }
  379. bool SoloGimbal::_acal_get_saving()
  380. {
  381. return _gimbalParams.flashing();
  382. }
  383. void SoloGimbal::_acal_save_calibrations()
  384. {
  385. if (_calibrator.get_status() != ACCEL_CAL_SUCCESS) {
  386. return;
  387. }
  388. Vector3f bias;
  389. Vector3f gain;
  390. _calibrator.get_calibration(bias,gain);
  391. _gimbalParams.set_accel_bias(bias);
  392. _gimbalParams.set_accel_gain(gain);
  393. _gimbalParams.flash();
  394. }
  395. void SoloGimbal::gimbal_ang_vel_to_joint_rates(const Vector3f& ang_vel, Vector3f& joint_rates)
  396. {
  397. float sin_theta = sinf(_measurement.joint_angles.y);
  398. float cos_theta = cosf(_measurement.joint_angles.y);
  399. float sin_phi = sinf(_measurement.joint_angles.x);
  400. float cos_phi = cosf(_measurement.joint_angles.x);
  401. float sec_phi = 1.0f/cos_phi;
  402. float tan_phi = sin_phi/cos_phi;
  403. joint_rates.x = ang_vel.x*cos_theta+ang_vel.z*sin_theta;
  404. joint_rates.y = ang_vel.x*sin_theta*tan_phi-ang_vel.z*cos_theta*tan_phi+ang_vel.y;
  405. joint_rates.z = sec_phi*(ang_vel.z*cos_theta-ang_vel.x*sin_theta);
  406. }
  407. void SoloGimbal::joint_rates_to_gimbal_ang_vel(const Vector3f& joint_rates, Vector3f& ang_vel)
  408. {
  409. float sin_theta = sinf(_measurement.joint_angles.y);
  410. float cos_theta = cosf(_measurement.joint_angles.y);
  411. float sin_phi = sinf(_measurement.joint_angles.x);
  412. float cos_phi = cosf(_measurement.joint_angles.x);
  413. ang_vel.x = cos_theta*joint_rates.x-sin_theta*cos_phi*joint_rates.z;
  414. ang_vel.y = joint_rates.y + sin_phi*joint_rates.z;
  415. ang_vel.z = sin_theta*joint_rates.x+cos_theta*cos_phi*joint_rates.z;
  416. }
  417. #endif // AP_AHRS_NAVEKF_AVAILABLE