mavextra.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 '''
3 useful extra functions for use by mavlink clients
4 
5 Copyright Andrew Tridgell 2011
6 Released under GNU GPL version 3 or later
7 '''
8 from __future__ import print_function
9 from __future__ import absolute_import
10 from builtins import object
11 
12 from math import *
13 
14 try:
15  # in case numpy isn't installed
16  from .quaternion import Quaternion
17 except:
18  pass
19 
20 try:
21  # rotmat doesn't work on Python3.2 yet
22  from .rotmat import Vector3, Matrix3
23 except Exception:
24  pass
25 
26 
27 def kmh(mps):
28  '''convert m/s to Km/h'''
29  return mps*3.6
30 
31 def altitude(SCALED_PRESSURE, ground_pressure=None, ground_temp=None):
32  '''calculate barometric altitude'''
33  from . import mavutil
34  self = mavutil.mavfile_global
35  if ground_pressure is None:
36  if self.param('GND_ABS_PRESS', None) is None:
37  return 0
38  ground_pressure = self.param('GND_ABS_PRESS', 1)
39  if ground_temp is None:
40  ground_temp = self.param('GND_TEMP', 0)
41  scaling = ground_pressure / (SCALED_PRESSURE.press_abs*100.0)
42  temp = ground_temp + 273.15
43  return log(scaling) * temp * 29271.267 * 0.001
44 
45 def altitude2(SCALED_PRESSURE, ground_pressure=None, ground_temp=None):
46  '''calculate barometric altitude'''
47  from . import mavutil
48  self = mavutil.mavfile_global
49  if ground_pressure is None:
50  if self.param('GND_ABS_PRESS', None) is None:
51  return 0
52  ground_pressure = self.param('GND_ABS_PRESS', 1)
53  if ground_temp is None:
54  ground_temp = self.param('GND_TEMP', 0)
55  scaling = SCALED_PRESSURE.press_abs*100.0 / ground_pressure
56  temp = ground_temp + 273.15
57  return 153.8462 * temp * (1.0 - exp(0.190259 * log(scaling)))
58 
59 def mag_heading(RAW_IMU, ATTITUDE, declination=None, SENSOR_OFFSETS=None, ofs=None):
60  '''calculate heading from raw magnetometer'''
61  if declination is None:
62  from . import mavutil
63  declination = degrees(mavutil.mavfile_global.param('COMPASS_DEC', 0))
64  mag_x = RAW_IMU.xmag
65  mag_y = RAW_IMU.ymag
66  mag_z = RAW_IMU.zmag
67  if SENSOR_OFFSETS is not None and ofs is not None:
68  mag_x += ofs[0] - SENSOR_OFFSETS.mag_ofs_x
69  mag_y += ofs[1] - SENSOR_OFFSETS.mag_ofs_y
70  mag_z += ofs[2] - SENSOR_OFFSETS.mag_ofs_z
71 
72  # go via a DCM matrix to match the APM calculation
73  dcm_matrix = rotation(ATTITUDE)
74  cos_pitch_sq = 1.0-(dcm_matrix.c.x*dcm_matrix.c.x)
75  headY = mag_y * dcm_matrix.c.z - mag_z * dcm_matrix.c.y
76  headX = mag_x * cos_pitch_sq - dcm_matrix.c.x * (mag_y * dcm_matrix.c.y + mag_z * dcm_matrix.c.z)
77 
78  heading = degrees(atan2(-headY,headX)) + declination
79  if heading < 0:
80  heading += 360
81  return heading
82 
83 def mag_heading_motors(RAW_IMU, ATTITUDE, declination, SENSOR_OFFSETS, ofs, SERVO_OUTPUT_RAW, motor_ofs):
84  '''calculate heading from raw magnetometer'''
85  ofs = get_motor_offsets(SERVO_OUTPUT_RAW, ofs, motor_ofs)
86 
87  if declination is None:
88  from . import mavutil
89  declination = degrees(mavutil.mavfile_global.param('COMPASS_DEC', 0))
90  mag_x = RAW_IMU.xmag
91  mag_y = RAW_IMU.ymag
92  mag_z = RAW_IMU.zmag
93  if SENSOR_OFFSETS is not None and ofs is not None:
94  mag_x += ofs[0] - SENSOR_OFFSETS.mag_ofs_x
95  mag_y += ofs[1] - SENSOR_OFFSETS.mag_ofs_y
96  mag_z += ofs[2] - SENSOR_OFFSETS.mag_ofs_z
97 
98  headX = mag_x*cos(ATTITUDE.pitch) + mag_y*sin(ATTITUDE.roll)*sin(ATTITUDE.pitch) + mag_z*cos(ATTITUDE.roll)*sin(ATTITUDE.pitch)
99  headY = mag_y*cos(ATTITUDE.roll) - mag_z*sin(ATTITUDE.roll)
100  heading = degrees(atan2(-headY,headX)) + declination
101  if heading < 0:
102  heading += 360
103  return heading
104 
105 def mag_field(RAW_IMU, SENSOR_OFFSETS=None, ofs=None):
106  '''calculate magnetic field strength from raw magnetometer'''
107  mag_x = RAW_IMU.xmag
108  mag_y = RAW_IMU.ymag
109  mag_z = RAW_IMU.zmag
110  if SENSOR_OFFSETS is not None and ofs is not None:
111  mag_x += ofs[0] - SENSOR_OFFSETS.mag_ofs_x
112  mag_y += ofs[1] - SENSOR_OFFSETS.mag_ofs_y
113  mag_z += ofs[2] - SENSOR_OFFSETS.mag_ofs_z
114  return sqrt(mag_x**2 + mag_y**2 + mag_z**2)
115 
116 def mag_field_df(MAG, ofs=None):
117  '''calculate magnetic field strength from raw magnetometer (dataflash version)'''
118  mag = Vector3(MAG.MagX, MAG.MagY, MAG.MagZ)
119  offsets = Vector3(MAG.OfsX, MAG.OfsY, MAG.OfsZ)
120  if ofs is not None:
121  mag = (mag - offsets) + Vector3(ofs[0], ofs[1], ofs[2])
122  return mag.length()
123 
124 def get_motor_offsets(SERVO_OUTPUT_RAW, ofs, motor_ofs):
125  '''calculate magnetic field strength from raw magnetometer'''
126  from . import mavutil
127  self = mavutil.mavfile_global
128 
129  m = SERVO_OUTPUT_RAW
130  motor_pwm = m.servo1_raw + m.servo2_raw + m.servo3_raw + m.servo4_raw
131  motor_pwm *= 0.25
132  rc3_min = self.param('RC3_MIN', 1100)
133  rc3_max = self.param('RC3_MAX', 1900)
134  motor = (motor_pwm - rc3_min) / (rc3_max - rc3_min)
135  if motor > 1.0:
136  motor = 1.0
137  if motor < 0.0:
138  motor = 0.0
139 
140  motor_offsets0 = motor_ofs[0] * motor
141  motor_offsets1 = motor_ofs[1] * motor
142  motor_offsets2 = motor_ofs[2] * motor
143  ofs = (ofs[0] + motor_offsets0, ofs[1] + motor_offsets1, ofs[2] + motor_offsets2)
144 
145  return ofs
146 
147 def mag_field_motors(RAW_IMU, SENSOR_OFFSETS, ofs, SERVO_OUTPUT_RAW, motor_ofs):
148  '''calculate magnetic field strength from raw magnetometer'''
149  mag_x = RAW_IMU.xmag
150  mag_y = RAW_IMU.ymag
151  mag_z = RAW_IMU.zmag
152 
153  ofs = get_motor_offsets(SERVO_OUTPUT_RAW, ofs, motor_ofs)
154 
155  if SENSOR_OFFSETS is not None and ofs is not None:
156  mag_x += ofs[0] - SENSOR_OFFSETS.mag_ofs_x
157  mag_y += ofs[1] - SENSOR_OFFSETS.mag_ofs_y
158  mag_z += ofs[2] - SENSOR_OFFSETS.mag_ofs_z
159  return sqrt(mag_x**2 + mag_y**2 + mag_z**2)
160 
161 def angle_diff(angle1, angle2):
162  '''show the difference between two angles in degrees'''
163  ret = angle1 - angle2
164  if ret > 180:
165  ret -= 360;
166  if ret < -180:
167  ret += 360
168  return ret
169 
170 average_data = {}
171 
172 def average(var, key, N):
173  '''average over N points'''
174  global average_data
175  if not key in average_data:
176  average_data[key] = [var]*N
177  return var
178  average_data[key].pop(0)
179  average_data[key].append(var)
180  return sum(average_data[key])/N
181 
182 derivative_data = {}
183 
184 def second_derivative_5(var, key):
185  '''5 point 2nd derivative'''
186  global derivative_data
187  from . import mavutil
188  tnow = mavutil.mavfile_global.timestamp
189 
190  if not key in derivative_data:
191  derivative_data[key] = (tnow, [var]*5)
192  return 0
193  (last_time, data) = derivative_data[key]
194  data.pop(0)
195  data.append(var)
196  derivative_data[key] = (tnow, data)
197  h = (tnow - last_time)
198  # N=5 2nd derivative from
199  # http://www.holoborodko.com/pavel/numerical-methods/numerical-derivative/smooth-low-noise-differentiators/
200  ret = ((data[4] + data[0]) - 2*data[2]) / (4*h**2)
201  return ret
202 
203 def second_derivative_9(var, key):
204  '''9 point 2nd derivative'''
205  global derivative_data
206  from . import mavutil
207  tnow = mavutil.mavfile_global.timestamp
208 
209  if not key in derivative_data:
210  derivative_data[key] = (tnow, [var]*9)
211  return 0
212  (last_time, data) = derivative_data[key]
213  data.pop(0)
214  data.append(var)
215  derivative_data[key] = (tnow, data)
216  h = (tnow - last_time)
217  # N=5 2nd derivative from
218  # http://www.holoborodko.com/pavel/numerical-methods/numerical-derivative/smooth-low-noise-differentiators/
219  f = data
220  ret = ((f[8] + f[0]) + 4*(f[7] + f[1]) + 4*(f[6]+f[2]) - 4*(f[5]+f[3]) - 10*f[4])/(64*h**2)
221  return ret
222 
223 lowpass_data = {}
224 
225 def lowpass(var, key, factor):
226  '''a simple lowpass filter'''
227  global lowpass_data
228  if not key in lowpass_data:
229  lowpass_data[key] = var
230  else:
231  lowpass_data[key] = factor*lowpass_data[key] + (1.0 - factor)*var
232  return lowpass_data[key]
233 
234 last_diff = {}
235 
236 def diff(var, key):
237  '''calculate differences between values'''
238  global last_diff
239  ret = 0
240  if not key in last_diff:
241  last_diff[key] = var
242  return 0
243  ret = var - last_diff[key]
244  last_diff[key] = var
245  return ret
246 
247 last_delta = {}
248 
249 def delta(var, key, tusec=None):
250  '''calculate slope'''
251  global last_delta
252  if tusec is not None:
253  tnow = tusec * 1.0e-6
254  else:
255  from . import mavutil
256  tnow = mavutil.mavfile_global.timestamp
257  ret = 0
258  if key in last_delta:
259  (last_v, last_t, last_ret) = last_delta[key]
260  if last_t == tnow:
261  return last_ret
262  if tnow == last_t:
263  ret = 0
264  else:
265  ret = (var - last_v) / (tnow - last_t)
266  last_delta[key] = (var, tnow, ret)
267  return ret
268 
269 def delta_angle(var, key, tusec=None):
270  '''calculate slope of an angle'''
271  global last_delta
272  if tusec is not None:
273  tnow = tusec * 1.0e-6
274  else:
275  from . import mavutil
276  tnow = mavutil.mavfile_global.timestamp
277  dv = 0
278  ret = 0
279  if key in last_delta:
280  (last_v, last_t, last_ret) = last_delta[key]
281  if last_t == tnow:
282  return last_ret
283  if tnow == last_t:
284  ret = 0
285  else:
286  dv = var - last_v
287  if dv > 180:
288  dv -= 360
289  if dv < -180:
290  dv += 360
291  ret = dv / (tnow - last_t)
292  last_delta[key] = (var, tnow, ret)
293  return ret
294 
295 def roll_estimate(RAW_IMU,GPS_RAW_INT=None,ATTITUDE=None,SENSOR_OFFSETS=None, ofs=None, mul=None,smooth=0.7):
296  '''estimate roll from accelerometer'''
297  rx = RAW_IMU.xacc * 9.81 / 1000.0
298  ry = RAW_IMU.yacc * 9.81 / 1000.0
299  rz = RAW_IMU.zacc * 9.81 / 1000.0
300  if ATTITUDE is not None and GPS_RAW_INT is not None:
301  ry -= ATTITUDE.yawspeed * GPS_RAW_INT.vel*0.01
302  rz += ATTITUDE.pitchspeed * GPS_RAW_INT.vel*0.01
303  if SENSOR_OFFSETS is not None and ofs is not None:
304  rx += SENSOR_OFFSETS.accel_cal_x
305  ry += SENSOR_OFFSETS.accel_cal_y
306  rz += SENSOR_OFFSETS.accel_cal_z
307  rx -= ofs[0]
308  ry -= ofs[1]
309  rz -= ofs[2]
310  if mul is not None:
311  rx *= mul[0]
312  ry *= mul[1]
313  rz *= mul[2]
314  return lowpass(degrees(-asin(ry/sqrt(rx**2+ry**2+rz**2))),'_roll',smooth)
315 
316 def pitch_estimate(RAW_IMU, GPS_RAW_INT=None,ATTITUDE=None, SENSOR_OFFSETS=None, ofs=None, mul=None, smooth=0.7):
317  '''estimate pitch from accelerometer'''
318  rx = RAW_IMU.xacc * 9.81 / 1000.0
319  ry = RAW_IMU.yacc * 9.81 / 1000.0
320  rz = RAW_IMU.zacc * 9.81 / 1000.0
321  if ATTITUDE is not None and GPS_RAW_INT is not None:
322  ry -= ATTITUDE.yawspeed * GPS_RAW_INT.vel*0.01
323  rz += ATTITUDE.pitchspeed * GPS_RAW_INT.vel*0.01
324  if SENSOR_OFFSETS is not None and ofs is not None:
325  rx += SENSOR_OFFSETS.accel_cal_x
326  ry += SENSOR_OFFSETS.accel_cal_y
327  rz += SENSOR_OFFSETS.accel_cal_z
328  rx -= ofs[0]
329  ry -= ofs[1]
330  rz -= ofs[2]
331  if mul is not None:
332  rx *= mul[0]
333  ry *= mul[1]
334  rz *= mul[2]
335  return lowpass(degrees(asin(rx/sqrt(rx**2+ry**2+rz**2))),'_pitch',smooth)
336 
337 def rotation(ATTITUDE):
338  '''return the current DCM rotation matrix'''
339  r = Matrix3()
340  r.from_euler(ATTITUDE.roll, ATTITUDE.pitch, ATTITUDE.yaw)
341  return r
342 
343 def mag_rotation(RAW_IMU, inclination, declination):
344  '''return an attitude rotation matrix that is consistent with the current mag
345  vector'''
346  m_body = Vector3(RAW_IMU.xmag, RAW_IMU.ymag, RAW_IMU.zmag)
347  m_earth = Vector3(m_body.length(), 0, 0)
348 
349  r = Matrix3()
350  r.from_euler(0, -radians(inclination), radians(declination))
351  m_earth = r * m_earth
352 
353  r.from_two_vectors(m_earth, m_body)
354  return r
355 
356 def mag_yaw(RAW_IMU, inclination, declination):
357  '''estimate yaw from mag'''
358  m = mag_rotation(RAW_IMU, inclination, declination)
359  (r, p, y) = m.to_euler()
360  y = degrees(y)
361  if y < 0:
362  y += 360
363  return y
364 
365 def mag_pitch(RAW_IMU, inclination, declination):
366  '''estimate pithc from mag'''
367  m = mag_rotation(RAW_IMU, inclination, declination)
368  (r, p, y) = m.to_euler()
369  return degrees(p)
370 
371 def mag_roll(RAW_IMU, inclination, declination):
372  '''estimate roll from mag'''
373  m = mag_rotation(RAW_IMU, inclination, declination)
374  (r, p, y) = m.to_euler()
375  return degrees(r)
376 
377 def expected_mag(RAW_IMU, ATTITUDE, inclination, declination):
378  '''return expected mag vector'''
379  m_body = Vector3(RAW_IMU.xmag, RAW_IMU.ymag, RAW_IMU.zmag)
380  field_strength = m_body.length()
381 
382  m = rotation(ATTITUDE)
383 
384  r = Matrix3()
385  r.from_euler(0, -radians(inclination), radians(declination))
386  m_earth = r * Vector3(field_strength, 0, 0)
387 
388  return m.transposed() * m_earth
389 
390 def mag_discrepancy(RAW_IMU, ATTITUDE, inclination, declination=None):
391  '''give the magnitude of the discrepancy between observed and expected magnetic field'''
392  if declination is None:
393  from . import mavutil
394  declination = degrees(mavutil.mavfile_global.param('COMPASS_DEC', 0))
395  expected = expected_mag(RAW_IMU, ATTITUDE, inclination, declination)
396  mag = Vector3(RAW_IMU.xmag, RAW_IMU.ymag, RAW_IMU.zmag)
397  return degrees(expected.angle(mag))
398 
399 
400 def mag_inclination(RAW_IMU, ATTITUDE, declination=None):
401  '''give the magnitude of the discrepancy between observed and expected magnetic field'''
402  if declination is None:
403  from . import mavutil
404  declination = degrees(mavutil.mavfile_global.param('COMPASS_DEC', 0))
405  r = rotation(ATTITUDE)
406  mag1 = Vector3(RAW_IMU.xmag, RAW_IMU.ymag, RAW_IMU.zmag)
407  mag1 = r * mag1
408  mag2 = Vector3(cos(radians(declination)), sin(radians(declination)), 0)
409  inclination = degrees(mag1.angle(mag2))
410  if RAW_IMU.zmag < 0:
411  inclination = -inclination
412  return inclination
413 
414 def expected_magx(RAW_IMU, ATTITUDE, inclination, declination):
415  '''estimate from mag'''
416  v = expected_mag(RAW_IMU, ATTITUDE, inclination, declination)
417  return v.x
418 
419 def expected_magy(RAW_IMU, ATTITUDE, inclination, declination):
420  '''estimate from mag'''
421  v = expected_mag(RAW_IMU, ATTITUDE, inclination, declination)
422  return v.y
423 
424 def expected_magz(RAW_IMU, ATTITUDE, inclination, declination):
425  '''estimate from mag'''
426  v = expected_mag(RAW_IMU, ATTITUDE, inclination, declination)
427  return v.z
428 
429 def gravity(RAW_IMU, SENSOR_OFFSETS=None, ofs=None, mul=None, smooth=0.7):
430  '''estimate pitch from accelerometer'''
431  if hasattr(RAW_IMU, 'xacc'):
432  rx = RAW_IMU.xacc * 9.81 / 1000.0
433  ry = RAW_IMU.yacc * 9.81 / 1000.0
434  rz = RAW_IMU.zacc * 9.81 / 1000.0
435  else:
436  rx = RAW_IMU.AccX
437  ry = RAW_IMU.AccY
438  rz = RAW_IMU.AccZ
439  if SENSOR_OFFSETS is not None and ofs is not None:
440  rx += SENSOR_OFFSETS.accel_cal_x
441  ry += SENSOR_OFFSETS.accel_cal_y
442  rz += SENSOR_OFFSETS.accel_cal_z
443  rx -= ofs[0]
444  ry -= ofs[1]
445  rz -= ofs[2]
446  if mul is not None:
447  rx *= mul[0]
448  ry *= mul[1]
449  rz *= mul[2]
450  return sqrt(rx**2+ry**2+rz**2)
451 
452 
453 
454 def pitch_sim(SIMSTATE, GPS_RAW):
455  '''estimate pitch from SIMSTATE accels'''
456  xacc = SIMSTATE.xacc - lowpass(delta(GPS_RAW.v,"v")*6.6, "v", 0.9)
457  zacc = SIMSTATE.zacc
458  zacc += SIMSTATE.ygyro * GPS_RAW.v;
459  if xacc/zacc >= 1:
460  return 0
461  if xacc/zacc <= -1:
462  return -0
463  return degrees(-asin(xacc/zacc))
464 
465 def distance_two(GPS_RAW1, GPS_RAW2, horizontal=True):
466  '''distance between two points'''
467  if hasattr(GPS_RAW1, 'Lat'):
468  lat1 = radians(GPS_RAW1.Lat)
469  lat2 = radians(GPS_RAW2.Lat)
470  lon1 = radians(GPS_RAW1.Lng)
471  lon2 = radians(GPS_RAW2.Lng)
472  alt1 = GPS_RAW1.Alt
473  alt2 = GPS_RAW2.Alt
474  elif hasattr(GPS_RAW1, 'cog'):
475  lat1 = radians(GPS_RAW1.lat)*1.0e-7
476  lat2 = radians(GPS_RAW2.lat)*1.0e-7
477  lon1 = radians(GPS_RAW1.lon)*1.0e-7
478  lon2 = radians(GPS_RAW2.lon)*1.0e-7
479  alt1 = GPS_RAW1.alt*0.001
480  alt2 = GPS_RAW2.alt*0.001
481  else:
482  lat1 = radians(GPS_RAW1.lat)
483  lat2 = radians(GPS_RAW2.lat)
484  lon1 = radians(GPS_RAW1.lon)
485  lon2 = radians(GPS_RAW2.lon)
486  alt1 = GPS_RAW1.alt*0.001
487  alt2 = GPS_RAW2.alt*0.001
488  dLat = lat2 - lat1
489  dLon = lon2 - lon1
490 
491  a = sin(0.5*dLat)**2 + sin(0.5*dLon)**2 * cos(lat1) * cos(lat2)
492  c = 2.0 * atan2(sqrt(a), sqrt(1.0-a))
493  ground_dist = 6371 * 1000 * c
494  if horizontal:
495  return ground_dist
496  return sqrt(ground_dist**2 + (alt2-alt1)**2)
497 
498 
499 first_fix = None
500 
501 def distance_home(GPS_RAW):
502  '''distance from first fix point'''
503  global first_fix
504  if (hasattr(GPS_RAW, 'fix_type') and GPS_RAW.fix_type < 2) or \
505  (hasattr(GPS_RAW, 'Status') and GPS_RAW.Status < 2):
506  return 0
507 
508  if first_fix is None:
509  first_fix = GPS_RAW
510  return 0
511  return distance_two(GPS_RAW, first_fix)
512 
513 def sawtooth(ATTITUDE, amplitude=2.0, period=5.0):
514  '''sawtooth pattern based on uptime'''
515  mins = (ATTITUDE.usec * 1.0e-6)/60
516  p = fmod(mins, period*2)
517  if p < period:
518  return amplitude * (p/period)
519  return amplitude * (period - (p-period))/period
520 
521 def rate_of_turn(speed, bank):
522  '''return expected rate of turn in degrees/s for given speed in m/s and
523  bank angle in degrees'''
524  if abs(speed) < 2 or abs(bank) > 80:
525  return 0
526  ret = degrees(9.81*tan(radians(bank))/speed)
527  return ret
528 
529 def wingloading(bank):
530  '''return expected wing loading factor for a bank angle in radians'''
531  return 1.0/cos(bank)
532 
533 def airspeed(VFR_HUD, ratio=None, used_ratio=None, offset=None):
534  '''recompute airspeed with a different ARSPD_RATIO'''
535  from . import mavutil
536  mav = mavutil.mavfile_global
537  if ratio is None:
538  ratio = 1.9936 # APM default
539  if used_ratio is None:
540  if 'ARSPD_RATIO' in mav.params:
541  used_ratio = mav.params['ARSPD_RATIO']
542  else:
543  print("no ARSPD_RATIO in mav.params")
544  used_ratio = ratio
545  if hasattr(VFR_HUD,'airspeed'):
546  airspeed = VFR_HUD.airspeed
547  else:
548  airspeed = VFR_HUD.Airspeed
549  airspeed_pressure = (airspeed**2) / used_ratio
550  if offset is not None:
551  airspeed_pressure += offset
552  if airspeed_pressure < 0:
553  airspeed_pressure = 0
554  airspeed = sqrt(airspeed_pressure * ratio)
555  return airspeed
556 
557 def EAS2TAS(ARSP,GPS,BARO,ground_temp=25):
558  '''EAS2TAS from ARSP.Temp'''
559  tempK = ground_temp + 273.15 - 0.0065 * GPS.Alt
560  return sqrt(1.225 / (BARO.Press / (287.26 * tempK)))
561 
562 
563 def airspeed_ratio(VFR_HUD):
564  '''recompute airspeed with a different ARSPD_RATIO'''
565  from . import mavutil
566  mav = mavutil.mavfile_global
567  airspeed_pressure = (VFR_HUD.airspeed**2) / ratio
568  airspeed = sqrt(airspeed_pressure * ratio)
569  return airspeed
570 
571 def airspeed_voltage(VFR_HUD, ratio=None):
572  '''back-calculate the voltage the airspeed sensor must have seen'''
573  from . import mavutil
574  mav = mavutil.mavfile_global
575  if ratio is None:
576  ratio = 1.9936 # APM default
577  if 'ARSPD_RATIO' in mav.params:
578  used_ratio = mav.params['ARSPD_RATIO']
579  else:
580  used_ratio = ratio
581  if 'ARSPD_OFFSET' in mav.params:
582  offset = mav.params['ARSPD_OFFSET']
583  else:
584  return -1
585  airspeed_pressure = (pow(VFR_HUD.airspeed,2)) / used_ratio
586  raw = airspeed_pressure + offset
587  SCALING_OLD_CALIBRATION = 204.8
588  voltage = 5.0 * raw / 4096
589  return voltage
590 
591 
592 def earth_rates(ATTITUDE):
593  '''return angular velocities in earth frame'''
594  from math import sin, cos, tan, fabs
595 
596  p = ATTITUDE.rollspeed
597  q = ATTITUDE.pitchspeed
598  r = ATTITUDE.yawspeed
599  phi = ATTITUDE.roll
600  theta = ATTITUDE.pitch
601  psi = ATTITUDE.yaw
602 
603  phiDot = p + tan(theta)*(q*sin(phi) + r*cos(phi))
604  thetaDot = q*cos(phi) - r*sin(phi)
605  if fabs(cos(theta)) < 1.0e-20:
606  theta += 1.0e-10
607  psiDot = (q*sin(phi) + r*cos(phi))/cos(theta)
608  return (phiDot, thetaDot, psiDot)
609 
610 def roll_rate(ATTITUDE):
611  '''return roll rate in earth frame'''
612  (phiDot, thetaDot, psiDot) = earth_rates(ATTITUDE)
613  return phiDot
614 
615 def pitch_rate(ATTITUDE):
616  '''return pitch rate in earth frame'''
617  (phiDot, thetaDot, psiDot) = earth_rates(ATTITUDE)
618  return thetaDot
619 
620 def yaw_rate(ATTITUDE):
621  '''return yaw rate in earth frame'''
622  (phiDot, thetaDot, psiDot) = earth_rates(ATTITUDE)
623  return psiDot
624 
625 
626 def gps_velocity(GLOBAL_POSITION_INT):
627  '''return GPS velocity vector'''
628  return Vector3(GLOBAL_POSITION_INT.vx, GLOBAL_POSITION_INT.vy, GLOBAL_POSITION_INT.vz) * 0.01
629 
630 
631 def gps_velocity_old(GPS_RAW_INT):
632  '''return GPS velocity vector'''
633  return Vector3(GPS_RAW_INT.vel*0.01*cos(radians(GPS_RAW_INT.cog*0.01)),
634  GPS_RAW_INT.vel*0.01*sin(radians(GPS_RAW_INT.cog*0.01)), 0)
635 
636 def gps_velocity_body(GPS_RAW_INT, ATTITUDE):
637  '''return GPS velocity vector in body frame'''
638  r = rotation(ATTITUDE)
639  return r.transposed() * Vector3(GPS_RAW_INT.vel*0.01*cos(radians(GPS_RAW_INT.cog*0.01)),
640  GPS_RAW_INT.vel*0.01*sin(radians(GPS_RAW_INT.cog*0.01)),
641  -tan(ATTITUDE.pitch)*GPS_RAW_INT.vel*0.01)
642 
643 def earth_accel(RAW_IMU,ATTITUDE):
644  '''return earth frame acceleration vector'''
645  r = rotation(ATTITUDE)
646  accel = Vector3(RAW_IMU.xacc, RAW_IMU.yacc, RAW_IMU.zacc) * 9.81 * 0.001
647  return r * accel
648 
649 def earth_gyro(RAW_IMU,ATTITUDE):
650  '''return earth frame gyro vector'''
651  r = rotation(ATTITUDE)
652  accel = Vector3(degrees(RAW_IMU.xgyro), degrees(RAW_IMU.ygyro), degrees(RAW_IMU.zgyro)) * 0.001
653  return r * accel
654 
655 def airspeed_energy_error(NAV_CONTROLLER_OUTPUT, VFR_HUD):
656  '''return airspeed energy error matching APM internals
657  This is positive when we are going too slow
658  '''
659  aspeed_cm = VFR_HUD.airspeed*100
660  target_airspeed = NAV_CONTROLLER_OUTPUT.aspd_error + aspeed_cm
661  airspeed_energy_error = ((target_airspeed*target_airspeed) - (aspeed_cm*aspeed_cm))*0.00005
662  return airspeed_energy_error
663 
664 
665 def energy_error(NAV_CONTROLLER_OUTPUT, VFR_HUD):
666  '''return energy error matching APM internals
667  This is positive when we are too low or going too slow
668  '''
669  aspeed_energy_error = airspeed_energy_error(NAV_CONTROLLER_OUTPUT, VFR_HUD)
670  alt_error = NAV_CONTROLLER_OUTPUT.alt_error*100
671  energy_error = aspeed_energy_error + alt_error*0.098
672  return energy_error
673 
674 def rover_turn_circle(SERVO_OUTPUT_RAW):
675  '''return turning circle (diameter) in meters for steering_angle in degrees
676  '''
677 
678  # this matches Toms slash
679  max_wheel_turn = 35
680  wheelbase = 0.335
681  wheeltrack = 0.296
682 
683  steering_angle = max_wheel_turn * (SERVO_OUTPUT_RAW.servo1_raw - 1500) / 400.0
684  theta = radians(steering_angle)
685  return (wheeltrack/2) + (wheelbase/sin(theta))
686 
687 def rover_yaw_rate(VFR_HUD, SERVO_OUTPUT_RAW):
688  '''return yaw rate in degrees/second given steering_angle and speed'''
689  max_wheel_turn=35
690  speed = VFR_HUD.groundspeed
691  # assume 1100 to 1900 PWM on steering
692  steering_angle = max_wheel_turn * (SERVO_OUTPUT_RAW.servo1_raw - 1500) / 400.0
693  if abs(steering_angle) < 1.0e-6 or abs(speed) < 1.0e-6:
694  return 0
695  d = rover_turn_circle(SERVO_OUTPUT_RAW)
696  c = pi * d
697  t = c / speed
698  rate = 360.0 / t
699  return rate
700 
701 def rover_lat_accel(VFR_HUD, SERVO_OUTPUT_RAW):
702  '''return lateral acceleration in m/s/s'''
703  speed = VFR_HUD.groundspeed
704  yaw_rate = rover_yaw_rate(VFR_HUD, SERVO_OUTPUT_RAW)
705  accel = radians(yaw_rate) * speed
706  return accel
707 
708 
709 def demix1(servo1, servo2, gain=0.5):
710  '''de-mix a mixed servo output'''
711  s1 = servo1 - 1500
712  s2 = servo2 - 1500
713  out1 = (s1+s2)*gain
714  out2 = (s1-s2)*gain
715  return out1+1500
716 
717 def demix2(servo1, servo2, gain=0.5):
718  '''de-mix a mixed servo output'''
719  s1 = servo1 - 1500
720  s2 = servo2 - 1500
721  out1 = (s1+s2)*gain
722  out2 = (s1-s2)*gain
723  return out2+1500
724 
725 def mixer(servo1, servo2, mixtype=1, gain=0.5):
726  '''mix two servos'''
727  s1 = servo1 - 1500
728  s2 = servo2 - 1500
729  v1 = (s1-s2)*gain
730  v2 = (s1+s2)*gain
731  if mixtype == 2:
732  v2 = -v2
733  elif mixtype == 3:
734  v1 = -v1
735  elif mixtype == 4:
736  v1 = -v1
737  v2 = -v2
738  if v1 > 600:
739  v1 = 600
740  elif v1 < -600:
741  v1 = -600
742  if v2 > 600:
743  v2 = 600
744  elif v2 < -600:
745  v2 = -600
746  return (1500+v1,1500+v2)
747 
748 def mix1(servo1, servo2, mixtype=1, gain=0.5):
749  '''de-mix a mixed servo output'''
750  (v1,v2) = mixer(servo1, servo2, mixtype=mixtype, gain=gain)
751  return v1
752 
753 def mix2(servo1, servo2, mixtype=1, gain=0.5):
754  '''de-mix a mixed servo output'''
755  (v1,v2) = mixer(servo1, servo2, mixtype=mixtype, gain=gain)
756  return v2
757 
758 def wrap_180(angle):
759  if angle > 180:
760  angle -= 360.0
761  if angle < -180:
762  angle += 360.0
763  return angle
764 
765 
766 def wrap_360(angle):
767  if angle > 360:
768  angle -= 360.0
769  if angle < 0:
770  angle += 360.0
771  return angle
772 
773 class DCM_State(object):
774  '''DCM state object'''
775  def __init__(self, roll, pitch, yaw):
776  self.dcm = Matrix3()
777  self.dcm2 = Matrix3()
778  self.dcm.from_euler(radians(roll), radians(pitch), radians(yaw))
779  self.dcm2.from_euler(radians(roll), radians(pitch), radians(yaw))
780  self.mag = Vector3()
781  self.gyro = Vector3()
782  self.accel = Vector3()
783  self.gps = None
784  self.rate = 50.0
785  self.kp = 0.2
786  self.kp_yaw = 0.3
787  self.omega_P = Vector3()
788  self.omega_P_yaw = Vector3()
789  self.omega_I = Vector3() # (-0.00199045287445, -0.00653007719666, -0.00714212376624)
790  self.omega_I_sum = Vector3()
792  self.omega = Vector3()
793  self.ra_sum = Vector3()
794  self.last_delta_angle = Vector3()
795  self.last_velocity = Vector3()
796  (self.roll, self.pitch, self.yaw) = self.dcm.to_euler()
797  (self.roll2, self.pitch2, self.yaw2) = self.dcm2.to_euler()
798 
799  def update(self, gyro, accel, mag, GPS):
800  if self.gyro != gyro or self.accel != accel:
801  delta_angle = old_div((gyro+self.omega_I), self.rate)
802  self.dcm.rotate(delta_angle)
803  correction = self.last_delta_angle % delta_angle
804  #print (delta_angle - self.last_delta_angle) * 58.0
805  corrected_delta = delta_angle + 0.0833333 * correction
806  self.dcm2.rotate(corrected_delta)
807  self.last_delta_angle = delta_angle
808 
809  self.dcm.normalize()
810  self.dcm2.normalize()
811 
812  self.gyro = gyro
813  self.accel = accel
814  (self.roll, self.pitch, self.yaw) = self.dcm.to_euler()
815  (self.roll2, self.pitch2, self.yaw2) = self.dcm2.to_euler()
816 
817 dcm_state = None
818 
819 def DCM_update(IMU, ATT, MAG, GPS):
820  '''implement full DCM system'''
821  global dcm_state
822  if dcm_state is None:
823  dcm_state = DCM_State(ATT.Roll, ATT.Pitch, ATT.Yaw)
824 
825  mag = Vector3(MAG.MagX, MAG.MagY, MAG.MagZ)
826  gyro = Vector3(IMU.GyrX, IMU.GyrY, IMU.GyrZ)
827  accel = Vector3(IMU.AccX, IMU.AccY, IMU.AccZ)
828  accel2 = Vector3(IMU.AccX, IMU.AccY, IMU.AccZ)
829  dcm_state.update(gyro, accel, mag, GPS)
830  return dcm_state
831 
832 class PX4_State(object):
833  '''PX4 DCM state object'''
834  def __init__(self, roll, pitch, yaw, timestamp):
835  self.dcm = Matrix3()
836  self.dcm.from_euler(radians(roll), radians(pitch), radians(yaw))
837  self.gyro = Vector3()
838  self.accel = Vector3()
839  self.timestamp = timestamp
840  (self.roll, self.pitch, self.yaw) = self.dcm.to_euler()
841 
842  def update(self, gyro, accel, timestamp):
843  if self.gyro != gyro or self.accel != accel:
844  delta_angle = gyro * (timestamp - self.timestamp)
845  self.timestamp = timestamp
846  self.dcm.rotate(delta_angle)
847  self.dcm.normalize()
848  self.gyro = gyro
849  self.accel = accel
850  (self.roll, self.pitch, self.yaw) = self.dcm.to_euler()
851 
852 px4_state = None
853 
854 def PX4_update(IMU, ATT):
855  '''implement full DCM using PX4 native SD log data'''
856  global px4_state
857  if px4_state is None:
858  px4_state = PX4_State(degrees(ATT.Roll), degrees(ATT.Pitch), degrees(ATT.Yaw), IMU._timestamp)
859 
860  gyro = Vector3(IMU.GyroX, IMU.GyroY, IMU.GyroZ)
861  accel = Vector3(IMU.AccX, IMU.AccY, IMU.AccZ)
862  px4_state.update(gyro, accel, IMU._timestamp)
863  return px4_state
864 
865 _downsample_N = 0
866 
867 def downsample(N):
868  '''conditional that is true on every Nth sample'''
869  global _downsample_N
870  _downsample_N = (_downsample_N + 1) % N
871  return _downsample_N == 0
872 
873 def armed(HEARTBEAT):
874  '''return 1 if armed, 0 if not'''
875  from . import mavutil
876  if HEARTBEAT.type == mavutil.mavlink.MAV_TYPE_GCS:
877  self = mavutil.mavfile_global
878  if self.motors_armed():
879  return 1
880  return 0
881  if HEARTBEAT.base_mode & mavutil.mavlink.MAV_MODE_FLAG_SAFETY_ARMED:
882  return 1
883  return 0
884 
885 def rotation_df(ATT):
886  '''return the current DCM rotation matrix'''
887  r = Matrix3()
888  r.from_euler(radians(ATT.Roll), radians(ATT.Pitch), radians(ATT.Yaw))
889  return r
890 
891 def rotation2(AHRS2):
892  '''return the current DCM rotation matrix'''
893  r = Matrix3()
894  r.from_euler(AHRS2.roll, AHRS2.pitch, AHRS2.yaw)
895  return r
896 
897 def earth_accel2(RAW_IMU,ATTITUDE):
898  '''return earth frame acceleration vector from AHRS2'''
899  r = rotation2(ATTITUDE)
900  accel = Vector3(RAW_IMU.xacc, RAW_IMU.yacc, RAW_IMU.zacc) * 9.81 * 0.001
901  return r * accel
902 
903 def earth_accel_df(IMU,ATT):
904  '''return earth frame acceleration vector from df log'''
905  r = rotation_df(ATT)
906  accel = Vector3(IMU.AccX, IMU.AccY, IMU.AccZ)
907  return r * accel
908 
909 def earth_accel2_df(IMU,IMU2,ATT):
910  '''return earth frame acceleration vector from df log'''
911  r = rotation_df(ATT)
912  accel1 = Vector3(IMU.AccX, IMU.AccY, IMU.AccZ)
913  accel2 = Vector3(IMU2.AccX, IMU2.AccY, IMU2.AccZ)
914  accel = 0.5 * (accel1 + accel2)
915  return r * accel
916 
918  '''return GPS velocity vector'''
919  vx = GPS.Spd * cos(radians(GPS.GCrs))
920  vy = GPS.Spd * sin(radians(GPS.GCrs))
921  return Vector3(vx, vy, GPS.VZ)
922 
923 def distance_gps2(GPS, GPS2):
924  '''distance between two points'''
925  if GPS.TimeMS != GPS2.TimeMS:
926  # reject messages not time aligned
927  return None
928  return distance_two(GPS, GPS2)
929 
930 
931 radius_of_earth = 6378100.0 # in meters
932 
934  ''' wrap a longitude value around to always have a value in the range
935  [-180, +180) i.e 0 => 0, 1 => 1, -1 => -1, 181 => -179, -181 => 179
936  '''
937  return (((lon + 180.0) % 360.0) - 180.0)
938 
939 def gps_newpos(lat, lon, bearing, distance):
940  '''extrapolate latitude/longitude given a heading and distance
941  thanks to http://www.movable-type.co.uk/scripts/latlong.html
942  '''
943  import math
944  lat1 = math.radians(lat)
945  lon1 = math.radians(lon)
946  brng = math.radians(bearing)
947  dr = distance/radius_of_earth
948 
949  lat2 = math.asin(math.sin(lat1)*math.cos(dr) +
950  math.cos(lat1)*math.sin(dr)*math.cos(brng))
951  lon2 = lon1 + math.atan2(math.sin(brng)*math.sin(dr)*math.cos(lat1),
952  math.cos(dr)-math.sin(lat1)*math.sin(lat2))
953  return (math.degrees(lat2), wrap_valid_longitude(math.degrees(lon2)))
954 
955 def gps_offset(lat, lon, east, north):
956  '''return new lat/lon after moving east/north
957  by the given number of meters'''
958  import math
959  bearing = math.degrees(math.atan2(east, north))
960  distance = math.sqrt(east**2 + north**2)
961  return gps_newpos(lat, lon, bearing, distance)
962 
963 ekf_home = None
964 
965 def ekf1_pos(EKF1):
966  '''calculate EKF position when EKF disabled'''
967  global ekf_home
968  from . import mavutil
969  self = mavutil.mavfile_global
970  if ekf_home is None:
971  if not 'GPS' in self.messages or self.messages['GPS'].Status != 3:
972  return None
973  ekf_home = self.messages['GPS']
974  (ekf_home.Lat, ekf_home.Lng) = gps_offset(ekf_home.Lat, ekf_home.Lng, -EKF1.PE, -EKF1.PN)
975  (lat,lon) = gps_offset(ekf_home.Lat, ekf_home.Lng, EKF1.PE, EKF1.PN)
976  return (lat, lon)
977 
979  '''
980  Get Euler angles from a quaternion
981  :param q: quaternion [w, x, y , z]
982  :returns: euler angles [roll, pitch, yaw]
983  '''
984  quat = Quaternion(q)
985  return quat.euler
986 
988  '''
989  Get quaternion from euler angles
990  :param e: euler angles [roll, pitch, yaw]
991  :returns: quaternion [w, x, y , z]
992  '''
993  quat = Quaternion(e)
994  return quat.q
995 
996 def rotate_quat(attitude, roll, pitch, yaw):
997  '''
998  Returns rotated quaternion
999  :param attitude: quaternion [w, x, y , z]
1000  :param roll: rotation in rad
1001  :param pitch: rotation in rad
1002  :param yaw: rotation in rad
1003  :returns: quaternion [w, x, y , z]
1004  '''
1005  quat = Quaternion(attitude)
1006  rotation = Quaternion([roll, pitch, yaw])
1007  res = rotation * quat
1008 
1009  return res.q
1010 
1011 def qroll(MSG):
1012  '''return quaternion roll in degrees'''
1013  q = Quaternion([MSG.Q1,MSG.Q2,MSG.Q3,MSG.Q4])
1014  return degrees(q.euler[0])
1015 
1016 
1017 def qpitch(MSG):
1018  '''return quaternion pitch in degrees'''
1019  q = Quaternion([MSG.Q1,MSG.Q2,MSG.Q3,MSG.Q4])
1020  return degrees(q.euler[1])
1021 
1022 
1023 def qyaw(MSG):
1024  '''return quaternion yaw in degrees'''
1025  q = Quaternion([MSG.Q1,MSG.Q2,MSG.Q3,MSG.Q4])
1026  return degrees(q.euler[2])
1027 
1028 def euler_rotated(MSG, roll, pitch, yaw):
1029  '''return eulers in radians from quaternion for view at given attitude in euler radians'''
1030  rot_view = Matrix3()
1031  rot_view.from_euler(roll, pitch, yaw)
1032  q = Quaternion([MSG.Q1,MSG.Q2,MSG.Q3,MSG.Q4])
1033  dcm = (rot_view * q.dcm.transposed()).transposed()
1034  return dcm.to_euler()
1035 
1036 def euler_p90(MSG):
1037  '''return eulers in radians from quaternion for view at pitch 90'''
1038  return euler_rotated(MSG, 0, radians(90), 0);
1039 
1040 def qroll_p90(MSG):
1041  '''return quaternion roll in degrees for view at pitch 90'''
1042  return degrees(euler_p90(MSG)[0])
1043 
1044 def qpitch_p90(MSG):
1045  '''return quaternion roll in degrees for view at pitch 90'''
1046  return degrees(euler_p90(MSG)[1])
1047 
1048 def qyaw_p90(MSG):
1049  '''return quaternion roll in degrees for view at pitch 90'''
1050  return degrees(euler_p90(MSG)[2])


mavlink
Author(s): Lorenz Meier
autogenerated on Sun Jul 7 2019 03:22:06