mavextra.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 '''
00003 useful extra functions for use by mavlink clients
00004 
00005 Copyright Andrew Tridgell 2011
00006 Released under GNU GPL version 3 or later
00007 '''
00008 
00009 import os, sys
00010 from math import *
00011 from .quaternion import Quaternion
00012 
00013 try:
00014     # rotmat doesn't work on Python3.2 yet
00015     from .rotmat import Vector3, Matrix3
00016 except Exception:
00017     pass
00018 
00019 
00020 def kmh(mps):
00021     '''convert m/s to Km/h'''
00022     return mps*3.6
00023 
00024 def altitude(SCALED_PRESSURE, ground_pressure=None, ground_temp=None):
00025     '''calculate barometric altitude'''
00026     from . import mavutil
00027     self = mavutil.mavfile_global
00028     if ground_pressure is None:
00029         if self.param('GND_ABS_PRESS', None) is None:
00030             return 0
00031         ground_pressure = self.param('GND_ABS_PRESS', 1)
00032     if ground_temp is None:
00033         ground_temp = self.param('GND_TEMP', 0)
00034     scaling = ground_pressure / (SCALED_PRESSURE.press_abs*100.0)
00035     temp = ground_temp + 273.15
00036     return log(scaling) * temp * 29271.267 * 0.001
00037 
00038 def altitude2(SCALED_PRESSURE, ground_pressure=None, ground_temp=None):
00039     '''calculate barometric altitude'''
00040     from . import mavutil
00041     self = mavutil.mavfile_global
00042     if ground_pressure is None:
00043         if self.param('GND_ABS_PRESS', None) is None:
00044             return 0
00045         ground_pressure = self.param('GND_ABS_PRESS', 1)
00046     if ground_temp is None:
00047         ground_temp = self.param('GND_TEMP', 0)
00048     scaling = SCALED_PRESSURE.press_abs*100.0 / ground_pressure
00049     temp = ground_temp + 273.15
00050     return 153.8462 * temp * (1.0 - exp(0.190259 * log(scaling)))
00051 
00052 def mag_heading(RAW_IMU, ATTITUDE, declination=None, SENSOR_OFFSETS=None, ofs=None):
00053     '''calculate heading from raw magnetometer'''
00054     if declination is None:
00055         import mavutil
00056         declination = degrees(mavutil.mavfile_global.param('COMPASS_DEC', 0))
00057     mag_x = RAW_IMU.xmag
00058     mag_y = RAW_IMU.ymag
00059     mag_z = RAW_IMU.zmag
00060     if SENSOR_OFFSETS is not None and ofs is not None:
00061         mag_x += ofs[0] - SENSOR_OFFSETS.mag_ofs_x
00062         mag_y += ofs[1] - SENSOR_OFFSETS.mag_ofs_y
00063         mag_z += ofs[2] - SENSOR_OFFSETS.mag_ofs_z
00064 
00065     # go via a DCM matrix to match the APM calculation
00066     dcm_matrix = rotation(ATTITUDE)
00067     cos_pitch_sq = 1.0-(dcm_matrix.c.x*dcm_matrix.c.x)
00068     headY = mag_y * dcm_matrix.c.z - mag_z * dcm_matrix.c.y
00069     headX = mag_x * cos_pitch_sq - dcm_matrix.c.x * (mag_y * dcm_matrix.c.y + mag_z * dcm_matrix.c.z)
00070 
00071     heading = degrees(atan2(-headY,headX)) + declination
00072     if heading < 0:
00073         heading += 360
00074     return heading
00075 
00076 def mag_heading_motors(RAW_IMU, ATTITUDE, declination, SENSOR_OFFSETS, ofs, SERVO_OUTPUT_RAW, motor_ofs):
00077     '''calculate heading from raw magnetometer'''
00078     ofs = get_motor_offsets(SERVO_OUTPUT_RAW, ofs, motor_ofs)
00079 
00080     if declination is None:
00081         import mavutil
00082         declination = degrees(mavutil.mavfile_global.param('COMPASS_DEC', 0))
00083     mag_x = RAW_IMU.xmag
00084     mag_y = RAW_IMU.ymag
00085     mag_z = RAW_IMU.zmag
00086     if SENSOR_OFFSETS is not None and ofs is not None:
00087         mag_x += ofs[0] - SENSOR_OFFSETS.mag_ofs_x
00088         mag_y += ofs[1] - SENSOR_OFFSETS.mag_ofs_y
00089         mag_z += ofs[2] - SENSOR_OFFSETS.mag_ofs_z
00090 
00091     headX = mag_x*cos(ATTITUDE.pitch) + mag_y*sin(ATTITUDE.roll)*sin(ATTITUDE.pitch) + mag_z*cos(ATTITUDE.roll)*sin(ATTITUDE.pitch)
00092     headY = mag_y*cos(ATTITUDE.roll) - mag_z*sin(ATTITUDE.roll)
00093     heading = degrees(atan2(-headY,headX)) + declination
00094     if heading < 0:
00095         heading += 360
00096     return heading
00097 
00098 def mag_field(RAW_IMU, SENSOR_OFFSETS=None, ofs=None):
00099     '''calculate magnetic field strength from raw magnetometer'''
00100     mag_x = RAW_IMU.xmag
00101     mag_y = RAW_IMU.ymag
00102     mag_z = RAW_IMU.zmag
00103     if SENSOR_OFFSETS is not None and ofs is not None:
00104         mag_x += ofs[0] - SENSOR_OFFSETS.mag_ofs_x
00105         mag_y += ofs[1] - SENSOR_OFFSETS.mag_ofs_y
00106         mag_z += ofs[2] - SENSOR_OFFSETS.mag_ofs_z
00107     return sqrt(mag_x**2 + mag_y**2 + mag_z**2)
00108 
00109 def mag_field_df(MAG, ofs=None):
00110     '''calculate magnetic field strength from raw magnetometer (dataflash version)'''
00111     mag = Vector3(MAG.MagX, MAG.MagY, MAG.MagZ)
00112     offsets = Vector3(MAG.OfsX, MAG.OfsY, MAG.OfsZ)
00113     if ofs is not None:
00114         mag = (mag - offsets) + Vector3(ofs[0], ofs[1], ofs[2])
00115     return mag.length()
00116 
00117 def get_motor_offsets(SERVO_OUTPUT_RAW, ofs, motor_ofs):
00118     '''calculate magnetic field strength from raw magnetometer'''
00119     import mavutil
00120     self = mavutil.mavfile_global
00121 
00122     m = SERVO_OUTPUT_RAW
00123     motor_pwm = m.servo1_raw + m.servo2_raw + m.servo3_raw + m.servo4_raw
00124     motor_pwm *= 0.25
00125     rc3_min = self.param('RC3_MIN', 1100)
00126     rc3_max = self.param('RC3_MAX', 1900)
00127     motor = (motor_pwm - rc3_min) / (rc3_max - rc3_min)
00128     if motor > 1.0:
00129         motor = 1.0
00130     if motor < 0.0:
00131         motor = 0.0
00132 
00133     motor_offsets0 = motor_ofs[0] * motor
00134     motor_offsets1 = motor_ofs[1] * motor
00135     motor_offsets2 = motor_ofs[2] * motor
00136     ofs = (ofs[0] + motor_offsets0, ofs[1] + motor_offsets1, ofs[2] + motor_offsets2)
00137 
00138     return ofs
00139 
00140 def mag_field_motors(RAW_IMU, SENSOR_OFFSETS, ofs, SERVO_OUTPUT_RAW, motor_ofs):
00141     '''calculate magnetic field strength from raw magnetometer'''
00142     mag_x = RAW_IMU.xmag
00143     mag_y = RAW_IMU.ymag
00144     mag_z = RAW_IMU.zmag
00145 
00146     ofs = get_motor_offsets(SERVO_OUTPUT_RAW, ofs, motor_ofs)
00147 
00148     if SENSOR_OFFSETS is not None and ofs is not None:
00149         mag_x += ofs[0] - SENSOR_OFFSETS.mag_ofs_x
00150         mag_y += ofs[1] - SENSOR_OFFSETS.mag_ofs_y
00151         mag_z += ofs[2] - SENSOR_OFFSETS.mag_ofs_z
00152     return sqrt(mag_x**2 + mag_y**2 + mag_z**2)
00153 
00154 def angle_diff(angle1, angle2):
00155     '''show the difference between two angles in degrees'''
00156     ret = angle1 - angle2
00157     if ret > 180:
00158         ret -= 360;
00159     if ret < -180:
00160         ret += 360
00161     return ret
00162 
00163 average_data = {}
00164 
00165 def average(var, key, N):
00166     '''average over N points'''
00167     global average_data
00168     if not key in average_data:
00169         average_data[key] = [var]*N
00170         return var
00171     average_data[key].pop(0)
00172     average_data[key].append(var)
00173     return sum(average_data[key])/N
00174 
00175 derivative_data = {}
00176 
00177 def second_derivative_5(var, key):
00178     '''5 point 2nd derivative'''
00179     global derivative_data
00180     import mavutil
00181     tnow = mavutil.mavfile_global.timestamp
00182 
00183     if not key in derivative_data:
00184         derivative_data[key] = (tnow, [var]*5)
00185         return 0
00186     (last_time, data) = derivative_data[key]
00187     data.pop(0)
00188     data.append(var)
00189     derivative_data[key] = (tnow, data)
00190     h = (tnow - last_time)
00191     # N=5 2nd derivative from
00192     # http://www.holoborodko.com/pavel/numerical-methods/numerical-derivative/smooth-low-noise-differentiators/
00193     ret = ((data[4] + data[0]) - 2*data[2]) / (4*h**2)
00194     return ret
00195 
00196 def second_derivative_9(var, key):
00197     '''9 point 2nd derivative'''
00198     global derivative_data
00199     import mavutil
00200     tnow = mavutil.mavfile_global.timestamp
00201 
00202     if not key in derivative_data:
00203         derivative_data[key] = (tnow, [var]*9)
00204         return 0
00205     (last_time, data) = derivative_data[key]
00206     data.pop(0)
00207     data.append(var)
00208     derivative_data[key] = (tnow, data)
00209     h = (tnow - last_time)
00210     # N=5 2nd derivative from
00211     # http://www.holoborodko.com/pavel/numerical-methods/numerical-derivative/smooth-low-noise-differentiators/
00212     f = data
00213     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)
00214     return ret
00215 
00216 lowpass_data = {}
00217 
00218 def lowpass(var, key, factor):
00219     '''a simple lowpass filter'''
00220     global lowpass_data
00221     if not key in lowpass_data:
00222         lowpass_data[key] = var
00223     else:
00224         lowpass_data[key] = factor*lowpass_data[key] + (1.0 - factor)*var
00225     return lowpass_data[key]
00226 
00227 last_diff = {}
00228 
00229 def diff(var, key):
00230     '''calculate differences between values'''
00231     global last_diff
00232     ret = 0
00233     if not key in last_diff:
00234         last_diff[key] = var
00235         return 0
00236     ret = var - last_diff[key]
00237     last_diff[key] = var
00238     return ret
00239 
00240 last_delta = {}
00241 
00242 def delta(var, key, tusec=None):
00243     '''calculate slope'''
00244     global last_delta
00245     if tusec is not None:
00246         tnow = tusec * 1.0e-6
00247     else:
00248         import mavutil
00249         tnow = mavutil.mavfile_global.timestamp
00250     dv = 0
00251     ret = 0
00252     if key in last_delta:
00253         (last_v, last_t, last_ret) = last_delta[key]
00254         if last_t == tnow:
00255             return last_ret
00256         if tnow == last_t:
00257             ret = 0
00258         else:
00259             ret = (var - last_v) / (tnow - last_t)
00260     last_delta[key] = (var, tnow, ret)
00261     return ret
00262 
00263 def delta_angle(var, key, tusec=None):
00264     '''calculate slope of an angle'''
00265     global last_delta
00266     if tusec is not None:
00267         tnow = tusec * 1.0e-6
00268     else:
00269         import mavutil
00270         tnow = mavutil.mavfile_global.timestamp
00271     dv = 0
00272     ret = 0
00273     if key in last_delta:
00274         (last_v, last_t, last_ret) = last_delta[key]
00275         if last_t == tnow:
00276             return last_ret
00277         if tnow == last_t:
00278             ret = 0
00279         else:
00280             dv = var - last_v
00281             if dv > 180:
00282                 dv -= 360
00283             if dv < -180:
00284                 dv += 360
00285             ret = dv / (tnow - last_t)
00286     last_delta[key] = (var, tnow, ret)
00287     return ret
00288 
00289 def roll_estimate(RAW_IMU,GPS_RAW_INT=None,ATTITUDE=None,SENSOR_OFFSETS=None, ofs=None, mul=None,smooth=0.7):
00290     '''estimate roll from accelerometer'''
00291     rx = RAW_IMU.xacc * 9.81 / 1000.0
00292     ry = RAW_IMU.yacc * 9.81 / 1000.0
00293     rz = RAW_IMU.zacc * 9.81 / 1000.0
00294     if ATTITUDE is not None and GPS_RAW_INT is not None:
00295         ry -= ATTITUDE.yawspeed * GPS_RAW_INT.vel*0.01
00296         rz += ATTITUDE.pitchspeed * GPS_RAW_INT.vel*0.01
00297     if SENSOR_OFFSETS is not None and ofs is not None:
00298         rx += SENSOR_OFFSETS.accel_cal_x
00299         ry += SENSOR_OFFSETS.accel_cal_y
00300         rz += SENSOR_OFFSETS.accel_cal_z
00301         rx -= ofs[0]
00302         ry -= ofs[1]
00303         rz -= ofs[2]
00304         if mul is not None:
00305             rx *= mul[0]
00306             ry *= mul[1]
00307             rz *= mul[2]
00308     return lowpass(degrees(-asin(ry/sqrt(rx**2+ry**2+rz**2))),'_roll',smooth)
00309 
00310 def pitch_estimate(RAW_IMU, GPS_RAW_INT=None,ATTITUDE=None, SENSOR_OFFSETS=None, ofs=None, mul=None, smooth=0.7):
00311     '''estimate pitch from accelerometer'''
00312     rx = RAW_IMU.xacc * 9.81 / 1000.0
00313     ry = RAW_IMU.yacc * 9.81 / 1000.0
00314     rz = RAW_IMU.zacc * 9.81 / 1000.0
00315     if ATTITUDE is not None and GPS_RAW_INT is not None:
00316         ry -= ATTITUDE.yawspeed * GPS_RAW_INT.vel*0.01
00317         rz += ATTITUDE.pitchspeed * GPS_RAW_INT.vel*0.01
00318     if SENSOR_OFFSETS is not None and ofs is not None:
00319         rx += SENSOR_OFFSETS.accel_cal_x
00320         ry += SENSOR_OFFSETS.accel_cal_y
00321         rz += SENSOR_OFFSETS.accel_cal_z
00322         rx -= ofs[0]
00323         ry -= ofs[1]
00324         rz -= ofs[2]
00325         if mul is not None:
00326             rx *= mul[0]
00327             ry *= mul[1]
00328             rz *= mul[2]
00329     return lowpass(degrees(asin(rx/sqrt(rx**2+ry**2+rz**2))),'_pitch',smooth)
00330 
00331 def rotation(ATTITUDE):
00332     '''return the current DCM rotation matrix'''
00333     r = Matrix3()
00334     r.from_euler(ATTITUDE.roll, ATTITUDE.pitch, ATTITUDE.yaw)
00335     return r
00336 
00337 def mag_rotation(RAW_IMU, inclination, declination):
00338     '''return an attitude rotation matrix that is consistent with the current mag
00339        vector'''
00340     m_body = Vector3(RAW_IMU.xmag, RAW_IMU.ymag, RAW_IMU.zmag)
00341     m_earth = Vector3(m_body.length(), 0, 0)
00342 
00343     r = Matrix3()
00344     r.from_euler(0, -radians(inclination), radians(declination))
00345     m_earth = r * m_earth
00346 
00347     r.from_two_vectors(m_earth, m_body)
00348     return r
00349 
00350 def mag_yaw(RAW_IMU, inclination, declination):
00351     '''estimate yaw from mag'''
00352     m = mag_rotation(RAW_IMU, inclination, declination)
00353     (r, p, y) = m.to_euler()
00354     y = degrees(y)
00355     if y < 0:
00356         y += 360
00357     return y
00358 
00359 def mag_pitch(RAW_IMU, inclination, declination):
00360     '''estimate pithc from mag'''
00361     m = mag_rotation(RAW_IMU, inclination, declination)
00362     (r, p, y) = m.to_euler()
00363     return degrees(p)
00364 
00365 def mag_roll(RAW_IMU, inclination, declination):
00366     '''estimate roll from mag'''
00367     m = mag_rotation(RAW_IMU, inclination, declination)
00368     (r, p, y) = m.to_euler()
00369     return degrees(r)
00370 
00371 def expected_mag(RAW_IMU, ATTITUDE, inclination, declination):
00372     '''return expected mag vector'''
00373     m_body = Vector3(RAW_IMU.xmag, RAW_IMU.ymag, RAW_IMU.zmag)
00374     field_strength = m_body.length()
00375 
00376     m = rotation(ATTITUDE)
00377 
00378     r = Matrix3()
00379     r.from_euler(0, -radians(inclination), radians(declination))
00380     m_earth = r * Vector3(field_strength, 0, 0)
00381 
00382     return m.transposed() * m_earth
00383 
00384 def mag_discrepancy(RAW_IMU, ATTITUDE, inclination, declination=None):
00385     '''give the magnitude of the discrepancy between observed and expected magnetic field'''
00386     if declination is None:
00387         import mavutil
00388         declination = degrees(mavutil.mavfile_global.param('COMPASS_DEC', 0))
00389     expected = expected_mag(RAW_IMU, ATTITUDE, inclination, declination)
00390     mag = Vector3(RAW_IMU.xmag, RAW_IMU.ymag, RAW_IMU.zmag)
00391     return degrees(expected.angle(mag))
00392 
00393 
00394 def mag_inclination(RAW_IMU, ATTITUDE, declination=None):
00395     '''give the magnitude of the discrepancy between observed and expected magnetic field'''
00396     if declination is None:
00397         import mavutil
00398         declination = degrees(mavutil.mavfile_global.param('COMPASS_DEC', 0))
00399     r = rotation(ATTITUDE)
00400     mag1 = Vector3(RAW_IMU.xmag, RAW_IMU.ymag, RAW_IMU.zmag)
00401     mag1 = r * mag1
00402     mag2 = Vector3(cos(radians(declination)), sin(radians(declination)), 0)
00403     inclination = degrees(mag1.angle(mag2))
00404     if RAW_IMU.zmag < 0:
00405         inclination = -inclination
00406     return inclination
00407 
00408 def expected_magx(RAW_IMU, ATTITUDE, inclination, declination):
00409     '''estimate  from mag'''
00410     v = expected_mag(RAW_IMU, ATTITUDE, inclination, declination)
00411     return v.x
00412 
00413 def expected_magy(RAW_IMU, ATTITUDE, inclination, declination):
00414     '''estimate  from mag'''
00415     v = expected_mag(RAW_IMU, ATTITUDE, inclination, declination)
00416     return v.y
00417 
00418 def expected_magz(RAW_IMU, ATTITUDE, inclination, declination):
00419     '''estimate  from mag'''
00420     v = expected_mag(RAW_IMU, ATTITUDE, inclination, declination)
00421     return v.z
00422 
00423 def gravity(RAW_IMU, SENSOR_OFFSETS=None, ofs=None, mul=None, smooth=0.7):
00424     '''estimate pitch from accelerometer'''
00425     if hasattr(RAW_IMU, 'xacc'):
00426         rx = RAW_IMU.xacc * 9.81 / 1000.0
00427         ry = RAW_IMU.yacc * 9.81 / 1000.0
00428         rz = RAW_IMU.zacc * 9.81 / 1000.0
00429     else:
00430         rx = RAW_IMU.AccX
00431         ry = RAW_IMU.AccY
00432         rz = RAW_IMU.AccZ
00433     if SENSOR_OFFSETS is not None and ofs is not None:
00434         rx += SENSOR_OFFSETS.accel_cal_x
00435         ry += SENSOR_OFFSETS.accel_cal_y
00436         rz += SENSOR_OFFSETS.accel_cal_z
00437         rx -= ofs[0]
00438         ry -= ofs[1]
00439         rz -= ofs[2]
00440         if mul is not None:
00441             rx *= mul[0]
00442             ry *= mul[1]
00443             rz *= mul[2]
00444     return sqrt(rx**2+ry**2+rz**2)
00445 
00446 
00447 
00448 def pitch_sim(SIMSTATE, GPS_RAW):
00449     '''estimate pitch from SIMSTATE accels'''
00450     xacc = SIMSTATE.xacc - lowpass(delta(GPS_RAW.v,"v")*6.6, "v", 0.9)
00451     zacc = SIMSTATE.zacc
00452     zacc += SIMSTATE.ygyro * GPS_RAW.v;
00453     if xacc/zacc >= 1:
00454         return 0
00455     if xacc/zacc <= -1:
00456         return -0
00457     return degrees(-asin(xacc/zacc))
00458 
00459 def distance_two(GPS_RAW1, GPS_RAW2, horizontal=True):
00460     '''distance between two points'''
00461     if hasattr(GPS_RAW1, 'Lat'):
00462         lat1 = radians(GPS_RAW1.Lat)
00463         lat2 = radians(GPS_RAW2.Lat)
00464         lon1 = radians(GPS_RAW1.Lng)
00465         lon2 = radians(GPS_RAW2.Lng)
00466         alt1 = GPS_RAW1.Alt
00467         alt2 = GPS_RAW2.Alt
00468     elif hasattr(GPS_RAW1, 'cog'):
00469         lat1 = radians(GPS_RAW1.lat)*1.0e-7
00470         lat2 = radians(GPS_RAW2.lat)*1.0e-7
00471         lon1 = radians(GPS_RAW1.lon)*1.0e-7
00472         lon2 = radians(GPS_RAW2.lon)*1.0e-7
00473         alt1 = GPS_RAW1.alt*0.001
00474         alt2 = GPS_RAW2.alt*0.001
00475     else:
00476         lat1 = radians(GPS_RAW1.lat)
00477         lat2 = radians(GPS_RAW2.lat)
00478         lon1 = radians(GPS_RAW1.lon)
00479         lon2 = radians(GPS_RAW2.lon)
00480         alt1 = GPS_RAW1.alt*0.001
00481         alt2 = GPS_RAW2.alt*0.001
00482     dLat = lat2 - lat1
00483     dLon = lon2 - lon1
00484 
00485     a = sin(0.5*dLat)**2 + sin(0.5*dLon)**2 * cos(lat1) * cos(lat2)
00486     c = 2.0 * atan2(sqrt(a), sqrt(1.0-a))
00487     ground_dist = 6371 * 1000 * c
00488     if horizontal:
00489         return ground_dist
00490     return sqrt(ground_dist**2 + (alt2-alt1)**2)
00491 
00492 
00493 first_fix = None
00494 
00495 def distance_home(GPS_RAW):
00496     '''distance from first fix point'''
00497     global first_fix
00498     if (hasattr(GPS_RAW, 'fix_type') and GPS_RAW.fix_type < 2) or \
00499        (hasattr(GPS_RAW, 'Status')   and GPS_RAW.Status   < 2):
00500         return 0
00501 
00502     if first_fix == None:
00503         first_fix = GPS_RAW
00504         return 0
00505     return distance_two(GPS_RAW, first_fix)
00506 
00507 def sawtooth(ATTITUDE, amplitude=2.0, period=5.0):
00508     '''sawtooth pattern based on uptime'''
00509     mins = (ATTITUDE.usec * 1.0e-6)/60
00510     p = fmod(mins, period*2)
00511     if p < period:
00512         return amplitude * (p/period)
00513     return amplitude * (period - (p-period))/period
00514 
00515 def rate_of_turn(speed, bank):
00516     '''return expected rate of turn in degrees/s for given speed in m/s and
00517        bank angle in degrees'''
00518     if abs(speed) < 2 or abs(bank) > 80:
00519         return 0
00520     ret = degrees(9.81*tan(radians(bank))/speed)
00521     return ret
00522 
00523 def wingloading(bank):
00524     '''return expected wing loading factor for a bank angle in radians'''
00525     return 1.0/cos(bank)
00526 
00527 def airspeed(VFR_HUD, ratio=None, used_ratio=None, offset=None):
00528     '''recompute airspeed with a different ARSPD_RATIO'''
00529     import mavutil
00530     mav = mavutil.mavfile_global
00531     if ratio is None:
00532         ratio = 1.9936 # APM default
00533     if used_ratio is None:
00534         if 'ARSPD_RATIO' in mav.params:
00535             used_ratio = mav.params['ARSPD_RATIO']
00536         else:
00537             print("no ARSPD_RATIO in mav.params")
00538             used_ratio = ratio
00539     if hasattr(VFR_HUD,'airspeed'):
00540         airspeed = VFR_HUD.airspeed
00541     else:
00542         airspeed = VFR_HUD.Airspeed
00543     airspeed_pressure = (airspeed**2) / used_ratio
00544     if offset is not None:
00545         airspeed_pressure += offset
00546         if airspeed_pressure < 0:
00547             airspeed_pressure = 0
00548     airspeed = sqrt(airspeed_pressure * ratio)
00549     return airspeed
00550 
00551 def EAS2TAS(ARSP,GPS,BARO,ground_temp=25):
00552     '''EAS2TAS from ARSP.Temp'''
00553     tempK = ground_temp + 273.15 - 0.0065 * GPS.Alt
00554     return sqrt(1.225 / (BARO.Press / (287.26 * tempK)))
00555 
00556 
00557 def airspeed_ratio(VFR_HUD):
00558     '''recompute airspeed with a different ARSPD_RATIO'''
00559     import mavutil
00560     mav = mavutil.mavfile_global
00561     airspeed_pressure = (VFR_HUD.airspeed**2) / ratio
00562     airspeed = sqrt(airspeed_pressure * ratio)
00563     return airspeed
00564 
00565 def airspeed_voltage(VFR_HUD, ratio=None):
00566     '''back-calculate the voltage the airspeed sensor must have seen'''
00567     import mavutil
00568     mav = mavutil.mavfile_global
00569     if ratio is None:
00570         ratio = 1.9936 # APM default
00571     if 'ARSPD_RATIO' in mav.params:
00572         used_ratio = mav.params['ARSPD_RATIO']
00573     else:
00574         used_ratio = ratio
00575     if 'ARSPD_OFFSET' in mav.params:
00576         offset = mav.params['ARSPD_OFFSET']
00577     else:
00578         return -1
00579     airspeed_pressure = (pow(VFR_HUD.airspeed,2)) / used_ratio
00580     raw = airspeed_pressure + offset
00581     SCALING_OLD_CALIBRATION = 204.8
00582     voltage = 5.0 * raw / 4096
00583     return voltage
00584 
00585 
00586 def earth_rates(ATTITUDE):
00587     '''return angular velocities in earth frame'''
00588     from math import sin, cos, tan, fabs
00589 
00590     p     = ATTITUDE.rollspeed
00591     q     = ATTITUDE.pitchspeed
00592     r     = ATTITUDE.yawspeed
00593     phi   = ATTITUDE.roll
00594     theta = ATTITUDE.pitch
00595     psi   = ATTITUDE.yaw
00596 
00597     phiDot   = p + tan(theta)*(q*sin(phi) + r*cos(phi))
00598     thetaDot = q*cos(phi) - r*sin(phi)
00599     if fabs(cos(theta)) < 1.0e-20:
00600         theta += 1.0e-10
00601     psiDot   = (q*sin(phi) + r*cos(phi))/cos(theta)
00602     return (phiDot, thetaDot, psiDot)
00603 
00604 def roll_rate(ATTITUDE):
00605     '''return roll rate in earth frame'''
00606     (phiDot, thetaDot, psiDot) = earth_rates(ATTITUDE)
00607     return phiDot
00608 
00609 def pitch_rate(ATTITUDE):
00610     '''return pitch rate in earth frame'''
00611     (phiDot, thetaDot, psiDot) = earth_rates(ATTITUDE)
00612     return thetaDot
00613 
00614 def yaw_rate(ATTITUDE):
00615     '''return yaw rate in earth frame'''
00616     (phiDot, thetaDot, psiDot) = earth_rates(ATTITUDE)
00617     return psiDot
00618 
00619 
00620 def gps_velocity(GLOBAL_POSITION_INT):
00621     '''return GPS velocity vector'''
00622     return Vector3(GLOBAL_POSITION_INT.vx, GLOBAL_POSITION_INT.vy, GLOBAL_POSITION_INT.vz) * 0.01
00623 
00624 
00625 def gps_velocity_old(GPS_RAW_INT):
00626     '''return GPS velocity vector'''
00627     return Vector3(GPS_RAW_INT.vel*0.01*cos(radians(GPS_RAW_INT.cog*0.01)),
00628                    GPS_RAW_INT.vel*0.01*sin(radians(GPS_RAW_INT.cog*0.01)), 0)
00629 
00630 def gps_velocity_body(GPS_RAW_INT, ATTITUDE):
00631     '''return GPS velocity vector in body frame'''
00632     r = rotation(ATTITUDE)
00633     return r.transposed() * Vector3(GPS_RAW_INT.vel*0.01*cos(radians(GPS_RAW_INT.cog*0.01)),
00634                                     GPS_RAW_INT.vel*0.01*sin(radians(GPS_RAW_INT.cog*0.01)),
00635                                     -tan(ATTITUDE.pitch)*GPS_RAW_INT.vel*0.01)
00636 
00637 def earth_accel(RAW_IMU,ATTITUDE):
00638     '''return earth frame acceleration vector'''
00639     r = rotation(ATTITUDE)
00640     accel = Vector3(RAW_IMU.xacc, RAW_IMU.yacc, RAW_IMU.zacc) * 9.81 * 0.001
00641     return r * accel
00642 
00643 def earth_gyro(RAW_IMU,ATTITUDE):
00644     '''return earth frame gyro vector'''
00645     r = rotation(ATTITUDE)
00646     accel = Vector3(degrees(RAW_IMU.xgyro), degrees(RAW_IMU.ygyro), degrees(RAW_IMU.zgyro)) * 0.001
00647     return r * accel
00648 
00649 def airspeed_energy_error(NAV_CONTROLLER_OUTPUT, VFR_HUD):
00650     '''return airspeed energy error matching APM internals
00651     This is positive when we are going too slow
00652     '''
00653     aspeed_cm = VFR_HUD.airspeed*100
00654     target_airspeed = NAV_CONTROLLER_OUTPUT.aspd_error + aspeed_cm
00655     airspeed_energy_error = ((target_airspeed*target_airspeed) - (aspeed_cm*aspeed_cm))*0.00005
00656     return airspeed_energy_error
00657 
00658 
00659 def energy_error(NAV_CONTROLLER_OUTPUT, VFR_HUD):
00660     '''return energy error matching APM internals
00661     This is positive when we are too low or going too slow
00662     '''
00663     aspeed_energy_error = airspeed_energy_error(NAV_CONTROLLER_OUTPUT, VFR_HUD)
00664     alt_error = NAV_CONTROLLER_OUTPUT.alt_error*100
00665     energy_error = aspeed_energy_error + alt_error*0.098
00666     return energy_error
00667 
00668 def rover_turn_circle(SERVO_OUTPUT_RAW):
00669     '''return turning circle (diameter) in meters for steering_angle in degrees
00670     '''
00671 
00672     # this matches Toms slash
00673     max_wheel_turn = 35
00674     wheelbase      = 0.335
00675     wheeltrack     = 0.296
00676 
00677     steering_angle = max_wheel_turn * (SERVO_OUTPUT_RAW.servo1_raw - 1500) / 400.0
00678     theta = radians(steering_angle)
00679     return (wheeltrack/2) + (wheelbase/sin(theta))
00680 
00681 def rover_yaw_rate(VFR_HUD, SERVO_OUTPUT_RAW):
00682     '''return yaw rate in degrees/second given steering_angle and speed'''
00683     max_wheel_turn=35
00684     speed = VFR_HUD.groundspeed
00685     # assume 1100 to 1900 PWM on steering
00686     steering_angle = max_wheel_turn * (SERVO_OUTPUT_RAW.servo1_raw - 1500) / 400.0
00687     if abs(steering_angle) < 1.0e-6 or abs(speed) < 1.0e-6:
00688         return 0
00689     d = rover_turn_circle(SERVO_OUTPUT_RAW)
00690     c = pi * d
00691     t = c / speed
00692     rate = 360.0 / t
00693     return rate
00694 
00695 def rover_lat_accel(VFR_HUD, SERVO_OUTPUT_RAW):
00696     '''return lateral acceleration in m/s/s'''
00697     speed = VFR_HUD.groundspeed
00698     yaw_rate = rover_yaw_rate(VFR_HUD, SERVO_OUTPUT_RAW)
00699     accel = radians(yaw_rate) * speed
00700     return accel
00701 
00702 
00703 def demix1(servo1, servo2, gain=0.5):
00704     '''de-mix a mixed servo output'''
00705     s1 = servo1 - 1500
00706     s2 = servo2 - 1500
00707     out1 = (s1+s2)*gain
00708     out2 = (s1-s2)*gain
00709     return out1+1500
00710 
00711 def demix2(servo1, servo2, gain=0.5):
00712     '''de-mix a mixed servo output'''
00713     s1 = servo1 - 1500
00714     s2 = servo2 - 1500
00715     out1 = (s1+s2)*gain
00716     out2 = (s1-s2)*gain
00717     return out2+1500
00718 
00719 def mixer(servo1, servo2, mixtype=1, gain=0.5):
00720     '''mix two servos'''
00721     s1 = servo1 - 1500
00722     s2 = servo2 - 1500
00723     v1 = (s1-s2)*gain
00724     v2 = (s1+s2)*gain
00725     if mixtype == 2:
00726         v2 = -v2
00727     elif mixtype == 3:
00728         v1 = -v1
00729     elif mixtype == 4:
00730         v1 = -v1
00731         v2 = -v2
00732     if v1 > 600:
00733         v1 = 600
00734     elif v1 < -600:
00735         v1 = -600
00736     if v2 > 600:
00737         v2 = 600
00738     elif v2 < -600:
00739         v2 = -600
00740     return (1500+v1,1500+v2)
00741 
00742 def mix1(servo1, servo2, mixtype=1, gain=0.5):
00743     '''de-mix a mixed servo output'''
00744     (v1,v2) = mixer(servo1, servo2, mixtype=mixtype, gain=gain)
00745     return v1
00746 
00747 def mix2(servo1, servo2, mixtype=1, gain=0.5):
00748     '''de-mix a mixed servo output'''
00749     (v1,v2) = mixer(servo1, servo2, mixtype=mixtype, gain=gain)
00750     return v2
00751 
00752 def wrap_180(angle):
00753     if angle > 180:
00754         angle -= 360.0
00755     if angle < -180:
00756         angle += 360.0
00757     return angle
00758 
00759 
00760 def wrap_360(angle):
00761     if angle > 360:
00762         angle -= 360.0
00763     if angle < 0:
00764         angle += 360.0
00765     return angle
00766 
00767 class DCM_State(object):
00768     '''DCM state object'''
00769     def __init__(self, roll, pitch, yaw):
00770         self.dcm = Matrix3()
00771         self.dcm2 = Matrix3()
00772         self.dcm.from_euler(radians(roll), radians(pitch), radians(yaw))
00773         self.dcm2.from_euler(radians(roll), radians(pitch), radians(yaw))
00774         self.mag = Vector3()
00775         self.gyro = Vector3()
00776         self.accel = Vector3()
00777         self.gps = None
00778         self.rate = 50.0
00779         self.kp = 0.2
00780         self.kp_yaw = 0.3
00781         self.omega_P = Vector3()
00782         self.omega_P_yaw = Vector3()
00783         self.omega_I = Vector3() # (-0.00199045287445, -0.00653007719666, -0.00714212376624)
00784         self.omega_I_sum = Vector3()
00785         self.omega_I_sum_time = 0
00786         self.omega = Vector3()
00787         self.ra_sum = Vector3()
00788         self.last_delta_angle = Vector3()
00789         self.last_velocity = Vector3()
00790         (self.roll, self.pitch, self.yaw) = self.dcm.to_euler()
00791         (self.roll2, self.pitch2, self.yaw2) = self.dcm2.to_euler()
00792 
00793     def update(self, gyro, accel, mag, GPS):
00794         if self.gyro != gyro or self.accel != accel:
00795             delta_angle = (gyro+self.omega_I) / self.rate
00796             self.dcm.rotate(delta_angle)
00797             correction = self.last_delta_angle % delta_angle
00798             #print (delta_angle - self.last_delta_angle) * 58.0
00799             corrected_delta = delta_angle + 0.0833333 * correction
00800             self.dcm2.rotate(corrected_delta)
00801             self.last_delta_angle = delta_angle
00802 
00803             self.dcm.normalize()
00804             self.dcm2.normalize()
00805 
00806             self.gyro = gyro
00807             self.accel = accel
00808             (self.roll, self.pitch, self.yaw) = self.dcm.to_euler()
00809             (self.roll2, self.pitch2, self.yaw2) = self.dcm2.to_euler()
00810 
00811 dcm_state = None
00812 
00813 def DCM_update(IMU, ATT, MAG, GPS):
00814     '''implement full DCM system'''
00815     global dcm_state
00816     if dcm_state is None:
00817         dcm_state = DCM_State(ATT.Roll, ATT.Pitch, ATT.Yaw)
00818 
00819     mag   = Vector3(MAG.MagX, MAG.MagY, MAG.MagZ)
00820     gyro  = Vector3(IMU.GyrX, IMU.GyrY, IMU.GyrZ)
00821     accel = Vector3(IMU.AccX, IMU.AccY, IMU.AccZ)
00822     accel2 = Vector3(IMU.AccX, IMU.AccY, IMU.AccZ)
00823     dcm_state.update(gyro, accel, mag, GPS)
00824     return dcm_state
00825 
00826 class PX4_State(object):
00827     '''PX4 DCM state object'''
00828     def __init__(self, roll, pitch, yaw, timestamp):
00829         self.dcm = Matrix3()
00830         self.dcm.from_euler(radians(roll), radians(pitch), radians(yaw))
00831         self.gyro = Vector3()
00832         self.accel = Vector3()
00833         self.timestamp = timestamp
00834         (self.roll, self.pitch, self.yaw) = self.dcm.to_euler()
00835 
00836     def update(self, gyro, accel, timestamp):
00837         if self.gyro != gyro or self.accel != accel:
00838             delta_angle = gyro * (timestamp - self.timestamp)
00839             self.timestamp = timestamp
00840             self.dcm.rotate(delta_angle)
00841             self.dcm.normalize()
00842             self.gyro = gyro
00843             self.accel = accel
00844             (self.roll, self.pitch, self.yaw) = self.dcm.to_euler()
00845 
00846 px4_state = None
00847 
00848 def PX4_update(IMU, ATT):
00849     '''implement full DCM using PX4 native SD log data'''
00850     global px4_state
00851     if px4_state is None:
00852         px4_state = PX4_State(degrees(ATT.Roll), degrees(ATT.Pitch), degrees(ATT.Yaw), IMU._timestamp)
00853 
00854     gyro  = Vector3(IMU.GyroX, IMU.GyroY, IMU.GyroZ)
00855     accel = Vector3(IMU.AccX, IMU.AccY, IMU.AccZ)
00856     px4_state.update(gyro, accel, IMU._timestamp)
00857     return px4_state
00858 
00859 _downsample_N = 0
00860 
00861 def downsample(N):
00862     '''conditional that is true on every Nth sample'''
00863     global _downsample_N
00864     _downsample_N = (_downsample_N + 1) % N
00865     return _downsample_N == 0
00866 
00867 def armed(HEARTBEAT):
00868     '''return 1 if armed, 0 if not'''
00869     from . import mavutil
00870     if HEARTBEAT.type == mavutil.mavlink.MAV_TYPE_GCS:
00871         self = mavutil.mavfile_global
00872         if self.motors_armed():
00873             return 1
00874         return 0
00875     if HEARTBEAT.base_mode & mavutil.mavlink.MAV_MODE_FLAG_SAFETY_ARMED:
00876         return 1
00877     return 0
00878 
00879 def rotation_df(ATT):
00880     '''return the current DCM rotation matrix'''
00881     r = Matrix3()
00882     r.from_euler(radians(ATT.Roll), radians(ATT.Pitch), radians(ATT.Yaw))
00883     return r
00884 
00885 def rotation2(AHRS2):
00886     '''return the current DCM rotation matrix'''
00887     r = Matrix3()
00888     r.from_euler(AHRS2.roll, AHRS2.pitch, AHRS2.yaw)
00889     return r
00890 
00891 def earth_accel2(RAW_IMU,ATTITUDE):
00892     '''return earth frame acceleration vector from AHRS2'''
00893     r = rotation2(ATTITUDE)
00894     accel = Vector3(RAW_IMU.xacc, RAW_IMU.yacc, RAW_IMU.zacc) * 9.81 * 0.001
00895     return r * accel
00896 
00897 def earth_accel_df(IMU,ATT):
00898     '''return earth frame acceleration vector from df log'''
00899     r = rotation_df(ATT)
00900     accel = Vector3(IMU.AccX, IMU.AccY, IMU.AccZ)
00901     return r * accel
00902 
00903 def earth_accel2_df(IMU,IMU2,ATT):
00904     '''return earth frame acceleration vector from df log'''
00905     r = rotation_df(ATT)
00906     accel1 = Vector3(IMU.AccX, IMU.AccY, IMU.AccZ)
00907     accel2 = Vector3(IMU2.AccX, IMU2.AccY, IMU2.AccZ)
00908     accel = 0.5 * (accel1 + accel2)
00909     return r * accel
00910 
00911 def gps_velocity_df(GPS):
00912     '''return GPS velocity vector'''
00913     vx = GPS.Spd * cos(radians(GPS.GCrs))
00914     vy = GPS.Spd * sin(radians(GPS.GCrs))
00915     return Vector3(vx, vy, GPS.VZ)
00916 
00917 def distance_gps2(GPS, GPS2):
00918     '''distance between two points'''
00919     if GPS.TimeMS != GPS2.TimeMS:
00920         # reject messages not time aligned
00921         return None
00922     return distance_two(GPS, GPS2)
00923 
00924 
00925 radius_of_earth = 6378100.0 # in meters
00926 
00927 def wrap_valid_longitude(lon):
00928   ''' wrap a longitude value around to always have a value in the range
00929       [-180, +180) i.e 0 => 0, 1 => 1, -1 => -1, 181 => -179, -181 => 179
00930   '''
00931   return (((lon + 180.0) % 360.0) - 180.0)
00932 
00933 def gps_newpos(lat, lon, bearing, distance):
00934   '''extrapolate latitude/longitude given a heading and distance
00935   thanks to http://www.movable-type.co.uk/scripts/latlong.html
00936   '''
00937   import math
00938   lat1 = math.radians(lat)
00939   lon1 = math.radians(lon)
00940   brng = math.radians(bearing)
00941   dr = distance/radius_of_earth
00942 
00943   lat2 = math.asin(math.sin(lat1)*math.cos(dr) +
00944                    math.cos(lat1)*math.sin(dr)*math.cos(brng))
00945   lon2 = lon1 + math.atan2(math.sin(brng)*math.sin(dr)*math.cos(lat1),
00946                            math.cos(dr)-math.sin(lat1)*math.sin(lat2))
00947   return (math.degrees(lat2), wrap_valid_longitude(math.degrees(lon2)))
00948 
00949 def gps_offset(lat, lon, east, north):
00950   '''return new lat/lon after moving east/north
00951   by the given number of meters'''
00952   import math
00953   bearing = math.degrees(math.atan2(east, north))
00954   distance = math.sqrt(east**2 + north**2)
00955   return gps_newpos(lat, lon, bearing, distance)
00956 
00957 ekf_home = None
00958 
00959 def ekf1_pos(EKF1):
00960   '''calculate EKF position when EKF disabled'''
00961   global ekf_home
00962   from . import mavutil
00963   self = mavutil.mavfile_global
00964   if ekf_home is None:
00965       if not 'GPS' in self.messages or self.messages['GPS'].Status != 3:
00966           return None
00967       ekf_home = self.messages['GPS']
00968       (ekf_home.Lat, ekf_home.Lng) = gps_offset(ekf_home.Lat, ekf_home.Lng, -EKF1.PE, -EKF1.PN)
00969   (lat,lon) = gps_offset(ekf_home.Lat, ekf_home.Lng, EKF1.PE, EKF1.PN)
00970   return (lat, lon)
00971 
00972 def quat_to_euler(q):
00973   '''
00974   Get Euler angles from a quaternion
00975   :param q: quaternion [w, x, y , z]
00976   :returns: euler angles [roll, pitch, yaw]
00977   '''
00978   quat = Quaternion(q)
00979   return quat.euler
00980 
00981 def euler_to_quat(e):
00982   '''
00983   Get quaternion from euler angles
00984   :param e: euler angles [roll, pitch, yaw]
00985   :returns: quaternion [w, x, y , z]
00986   '''
00987   quat = Quaternion(e)
00988   return quat.q
00989 
00990 def rotate_quat(attitude, roll, pitch, yaw):
00991   '''
00992   Returns rotated quaternion
00993   :param attitude: quaternion [w, x, y , z]
00994   :param roll: rotation in rad
00995   :param pitch: rotation in rad
00996   :param yaw: rotation in rad
00997   :returns: quaternion [w, x, y , z]
00998   '''
00999   quat = Quaternion(attitude)
01000   rotation = Quaternion([roll, pitch, yaw])
01001   res = rotation * quat
01002 
01003   return res.q


mavlink
Author(s): Lorenz Meier
autogenerated on Wed Sep 9 2015 18:06:17