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