mavextra.py 51 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131113211331134113511361137113811391140114111421143114411451146114711481149115011511152115311541155115611571158115911601161116211631164116511661167116811691170117111721173117411751176117711781179118011811182118311841185118611871188118911901191119211931194119511961197119811991200120112021203120412051206120712081209121012111212121312141215121612171218121912201221122212231224122512261227122812291230123112321233123412351236123712381239124012411242124312441245124612471248124912501251125212531254125512561257125812591260126112621263126412651266126712681269127012711272127312741275127612771278127912801281128212831284128512861287128812891290129112921293129412951296129712981299130013011302
  1. #!/usr/bin/env python
  2. '''
  3. useful extra functions for use by mavlink clients
  4. Copyright Andrew Tridgell 2011
  5. Released under GNU GPL version 3 or later
  6. '''
  7. from __future__ import print_function
  8. from __future__ import absolute_import
  9. from builtins import object
  10. from math import *
  11. try:
  12. # in case numpy isn't installed
  13. from .quaternion import Quaternion
  14. except:
  15. pass
  16. try:
  17. # rotmat doesn't work on Python3.2 yet
  18. from .rotmat import Vector3, Matrix3
  19. except Exception:
  20. pass
  21. def kmh(mps):
  22. '''convert m/s to Km/h'''
  23. return mps*3.6
  24. def altitude(SCALED_PRESSURE, ground_pressure=None, ground_temp=None):
  25. '''calculate barometric altitude'''
  26. from . import mavutil
  27. self = mavutil.mavfile_global
  28. if ground_pressure is None:
  29. if self.param('GND_ABS_PRESS', None) is None:
  30. return 0
  31. ground_pressure = self.param('GND_ABS_PRESS', 1)
  32. if ground_temp is None:
  33. ground_temp = self.param('GND_TEMP', 0)
  34. scaling = ground_pressure / (SCALED_PRESSURE.press_abs*100.0)
  35. temp = ground_temp + 273.15
  36. return log(scaling) * temp * 29271.267 * 0.001
  37. def altitude2(SCALED_PRESSURE, ground_pressure=None, ground_temp=None):
  38. '''calculate barometric altitude'''
  39. from . import mavutil
  40. self = mavutil.mavfile_global
  41. if ground_pressure is None:
  42. if self.param('GND_ABS_PRESS', None) is None:
  43. return 0
  44. ground_pressure = self.param('GND_ABS_PRESS', 1)
  45. if ground_temp is None:
  46. ground_temp = self.param('GND_TEMP', 0)
  47. scaling = SCALED_PRESSURE.press_abs*100.0 / ground_pressure
  48. temp = ground_temp + 273.15
  49. return 153.8462 * temp * (1.0 - exp(0.190259 * log(scaling)))
  50. def mag_heading(RAW_IMU, ATTITUDE, declination=None, SENSOR_OFFSETS=None, ofs=None):
  51. '''calculate heading from raw magnetometer'''
  52. if declination is None:
  53. from . import mavutil
  54. declination = degrees(mavutil.mavfile_global.param('COMPASS_DEC', 0))
  55. mag_x = RAW_IMU.xmag
  56. mag_y = RAW_IMU.ymag
  57. mag_z = RAW_IMU.zmag
  58. if SENSOR_OFFSETS is not None and ofs is not None:
  59. mag_x += ofs[0] - SENSOR_OFFSETS.mag_ofs_x
  60. mag_y += ofs[1] - SENSOR_OFFSETS.mag_ofs_y
  61. mag_z += ofs[2] - SENSOR_OFFSETS.mag_ofs_z
  62. # go via a DCM matrix to match the APM calculation
  63. dcm_matrix = rotation(ATTITUDE)
  64. cos_pitch_sq = 1.0-(dcm_matrix.c.x*dcm_matrix.c.x)
  65. headY = mag_y * dcm_matrix.c.z - mag_z * dcm_matrix.c.y
  66. headX = mag_x * cos_pitch_sq - dcm_matrix.c.x * (mag_y * dcm_matrix.c.y + mag_z * dcm_matrix.c.z)
  67. heading = degrees(atan2(-headY,headX)) + declination
  68. if heading < 0:
  69. heading += 360
  70. return heading
  71. def mag_heading_motors(RAW_IMU, ATTITUDE, declination, SENSOR_OFFSETS, ofs, SERVO_OUTPUT_RAW, motor_ofs):
  72. '''calculate heading from raw magnetometer'''
  73. ofs = get_motor_offsets(SERVO_OUTPUT_RAW, ofs, motor_ofs)
  74. if declination is None:
  75. from . import mavutil
  76. declination = degrees(mavutil.mavfile_global.param('COMPASS_DEC', 0))
  77. mag_x = RAW_IMU.xmag
  78. mag_y = RAW_IMU.ymag
  79. mag_z = RAW_IMU.zmag
  80. if SENSOR_OFFSETS is not None and ofs is not None:
  81. mag_x += ofs[0] - SENSOR_OFFSETS.mag_ofs_x
  82. mag_y += ofs[1] - SENSOR_OFFSETS.mag_ofs_y
  83. mag_z += ofs[2] - SENSOR_OFFSETS.mag_ofs_z
  84. headX = mag_x*cos(ATTITUDE.pitch) + mag_y*sin(ATTITUDE.roll)*sin(ATTITUDE.pitch) + mag_z*cos(ATTITUDE.roll)*sin(ATTITUDE.pitch)
  85. headY = mag_y*cos(ATTITUDE.roll) - mag_z*sin(ATTITUDE.roll)
  86. heading = degrees(atan2(-headY,headX)) + declination
  87. if heading < 0:
  88. heading += 360
  89. return heading
  90. def mag_field(RAW_IMU, SENSOR_OFFSETS=None, ofs=None):
  91. '''calculate magnetic field strength from raw magnetometer'''
  92. mag_x = RAW_IMU.xmag
  93. mag_y = RAW_IMU.ymag
  94. mag_z = RAW_IMU.zmag
  95. if SENSOR_OFFSETS is not None and ofs is not None:
  96. mag_x += ofs[0] - SENSOR_OFFSETS.mag_ofs_x
  97. mag_y += ofs[1] - SENSOR_OFFSETS.mag_ofs_y
  98. mag_z += ofs[2] - SENSOR_OFFSETS.mag_ofs_z
  99. return sqrt(mag_x**2 + mag_y**2 + mag_z**2)
  100. def mag_field_df(MAG, ofs=None):
  101. '''calculate magnetic field strength from raw magnetometer (dataflash version)'''
  102. mag = Vector3(MAG.MagX, MAG.MagY, MAG.MagZ)
  103. offsets = Vector3(MAG.OfsX, MAG.OfsY, MAG.OfsZ)
  104. if ofs is not None:
  105. mag = (mag - offsets) + Vector3(ofs[0], ofs[1], ofs[2])
  106. return mag.length()
  107. def get_motor_offsets(SERVO_OUTPUT_RAW, ofs, motor_ofs):
  108. '''calculate magnetic field strength from raw magnetometer'''
  109. from . import mavutil
  110. self = mavutil.mavfile_global
  111. m = SERVO_OUTPUT_RAW
  112. motor_pwm = m.servo1_raw + m.servo2_raw + m.servo3_raw + m.servo4_raw
  113. motor_pwm *= 0.25
  114. rc3_min = self.param('RC3_MIN', 1100)
  115. rc3_max = self.param('RC3_MAX', 1900)
  116. motor = (motor_pwm - rc3_min) / (rc3_max - rc3_min)
  117. if motor > 1.0:
  118. motor = 1.0
  119. if motor < 0.0:
  120. motor = 0.0
  121. motor_offsets0 = motor_ofs[0] * motor
  122. motor_offsets1 = motor_ofs[1] * motor
  123. motor_offsets2 = motor_ofs[2] * motor
  124. ofs = (ofs[0] + motor_offsets0, ofs[1] + motor_offsets1, ofs[2] + motor_offsets2)
  125. return ofs
  126. def mag_field_motors(RAW_IMU, SENSOR_OFFSETS, ofs, SERVO_OUTPUT_RAW, motor_ofs):
  127. '''calculate magnetic field strength from raw magnetometer'''
  128. mag_x = RAW_IMU.xmag
  129. mag_y = RAW_IMU.ymag
  130. mag_z = RAW_IMU.zmag
  131. ofs = get_motor_offsets(SERVO_OUTPUT_RAW, ofs, motor_ofs)
  132. if SENSOR_OFFSETS is not None and ofs is not None:
  133. mag_x += ofs[0] - SENSOR_OFFSETS.mag_ofs_x
  134. mag_y += ofs[1] - SENSOR_OFFSETS.mag_ofs_y
  135. mag_z += ofs[2] - SENSOR_OFFSETS.mag_ofs_z
  136. return sqrt(mag_x**2 + mag_y**2 + mag_z**2)
  137. def angle_diff(angle1, angle2):
  138. '''show the difference between two angles in degrees'''
  139. ret = angle1 - angle2
  140. if ret > 180:
  141. ret -= 360;
  142. if ret < -180:
  143. ret += 360
  144. return ret
  145. average_data = {}
  146. def average(var, key, N):
  147. '''average over N points'''
  148. global average_data
  149. if not key in average_data:
  150. average_data[key] = [var]*N
  151. return var
  152. average_data[key].pop(0)
  153. average_data[key].append(var)
  154. return sum(average_data[key])/N
  155. derivative_data = {}
  156. def second_derivative_5(var, key):
  157. '''5 point 2nd derivative'''
  158. global derivative_data
  159. from . import mavutil
  160. tnow = mavutil.mavfile_global.timestamp
  161. if not key in derivative_data:
  162. derivative_data[key] = (tnow, [var]*5)
  163. return 0
  164. (last_time, data) = derivative_data[key]
  165. data.pop(0)
  166. data.append(var)
  167. derivative_data[key] = (tnow, data)
  168. h = (tnow - last_time)
  169. # N=5 2nd derivative from
  170. # http://www.holoborodko.com/pavel/numerical-methods/numerical-derivative/smooth-low-noise-differentiators/
  171. ret = ((data[4] + data[0]) - 2*data[2]) / (4*h**2)
  172. return ret
  173. def second_derivative_9(var, key):
  174. '''9 point 2nd derivative'''
  175. global derivative_data
  176. from . import mavutil
  177. tnow = mavutil.mavfile_global.timestamp
  178. if not key in derivative_data:
  179. derivative_data[key] = (tnow, [var]*9)
  180. return 0
  181. (last_time, data) = derivative_data[key]
  182. data.pop(0)
  183. data.append(var)
  184. derivative_data[key] = (tnow, data)
  185. h = (tnow - last_time)
  186. # N=5 2nd derivative from
  187. # http://www.holoborodko.com/pavel/numerical-methods/numerical-derivative/smooth-low-noise-differentiators/
  188. f = data
  189. 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)
  190. return ret
  191. lowpass_data = {}
  192. def lowpass(var, key, factor):
  193. '''a simple lowpass filter'''
  194. global lowpass_data
  195. if not key in lowpass_data:
  196. lowpass_data[key] = var
  197. else:
  198. lowpass_data[key] = factor*lowpass_data[key] + (1.0 - factor)*var
  199. return lowpass_data[key]
  200. last_diff = {}
  201. def diff(var, key):
  202. '''calculate differences between values'''
  203. global last_diff
  204. ret = 0
  205. if not key in last_diff:
  206. last_diff[key] = var
  207. return 0
  208. ret = var - last_diff[key]
  209. last_diff[key] = var
  210. return ret
  211. last_delta = {}
  212. def delta(var, key, tusec=None):
  213. '''calculate slope'''
  214. global last_delta
  215. if tusec is not None:
  216. tnow = tusec * 1.0e-6
  217. else:
  218. from . import mavutil
  219. tnow = mavutil.mavfile_global.timestamp
  220. ret = 0
  221. if key in last_delta:
  222. (last_v, last_t, last_ret) = last_delta[key]
  223. if last_t == tnow:
  224. return last_ret
  225. if tnow == last_t:
  226. ret = 0
  227. else:
  228. ret = (var - last_v) / (tnow - last_t)
  229. last_delta[key] = (var, tnow, ret)
  230. return ret
  231. def delta_angle(var, key, tusec=None):
  232. '''calculate slope of an angle'''
  233. global last_delta
  234. if tusec is not None:
  235. tnow = tusec * 1.0e-6
  236. else:
  237. from . import mavutil
  238. tnow = mavutil.mavfile_global.timestamp
  239. dv = 0
  240. ret = 0
  241. if key in last_delta:
  242. (last_v, last_t, last_ret) = last_delta[key]
  243. if last_t == tnow:
  244. return last_ret
  245. if tnow == last_t:
  246. ret = 0
  247. else:
  248. dv = var - last_v
  249. if dv > 180:
  250. dv -= 360
  251. if dv < -180:
  252. dv += 360
  253. ret = dv / (tnow - last_t)
  254. last_delta[key] = (var, tnow, ret)
  255. return ret
  256. def roll_estimate(RAW_IMU,GPS_RAW_INT=None,ATTITUDE=None,SENSOR_OFFSETS=None, ofs=None, mul=None,smooth=0.7):
  257. '''estimate roll from accelerometer'''
  258. rx = RAW_IMU.xacc * 9.81 / 1000.0
  259. ry = RAW_IMU.yacc * 9.81 / 1000.0
  260. rz = RAW_IMU.zacc * 9.81 / 1000.0
  261. if ATTITUDE is not None and GPS_RAW_INT is not None:
  262. ry -= ATTITUDE.yawspeed * GPS_RAW_INT.vel*0.01
  263. rz += ATTITUDE.pitchspeed * GPS_RAW_INT.vel*0.01
  264. if SENSOR_OFFSETS is not None and ofs is not None:
  265. rx += SENSOR_OFFSETS.accel_cal_x
  266. ry += SENSOR_OFFSETS.accel_cal_y
  267. rz += SENSOR_OFFSETS.accel_cal_z
  268. rx -= ofs[0]
  269. ry -= ofs[1]
  270. rz -= ofs[2]
  271. if mul is not None:
  272. rx *= mul[0]
  273. ry *= mul[1]
  274. rz *= mul[2]
  275. return lowpass(degrees(-asin(ry/sqrt(rx**2+ry**2+rz**2))),'_roll',smooth)
  276. def pitch_estimate(RAW_IMU, GPS_RAW_INT=None,ATTITUDE=None, SENSOR_OFFSETS=None, ofs=None, mul=None, smooth=0.7):
  277. '''estimate pitch from accelerometer'''
  278. rx = RAW_IMU.xacc * 9.81 / 1000.0
  279. ry = RAW_IMU.yacc * 9.81 / 1000.0
  280. rz = RAW_IMU.zacc * 9.81 / 1000.0
  281. if ATTITUDE is not None and GPS_RAW_INT is not None:
  282. ry -= ATTITUDE.yawspeed * GPS_RAW_INT.vel*0.01
  283. rz += ATTITUDE.pitchspeed * GPS_RAW_INT.vel*0.01
  284. if SENSOR_OFFSETS is not None and ofs is not None:
  285. rx += SENSOR_OFFSETS.accel_cal_x
  286. ry += SENSOR_OFFSETS.accel_cal_y
  287. rz += SENSOR_OFFSETS.accel_cal_z
  288. rx -= ofs[0]
  289. ry -= ofs[1]
  290. rz -= ofs[2]
  291. if mul is not None:
  292. rx *= mul[0]
  293. ry *= mul[1]
  294. rz *= mul[2]
  295. return lowpass(degrees(asin(rx/sqrt(rx**2+ry**2+rz**2))),'_pitch',smooth)
  296. def rotation(ATTITUDE):
  297. '''return the current DCM rotation matrix'''
  298. r = Matrix3()
  299. r.from_euler(ATTITUDE.roll, ATTITUDE.pitch, ATTITUDE.yaw)
  300. return r
  301. def mag_rotation(RAW_IMU, inclination, declination):
  302. '''return an attitude rotation matrix that is consistent with the current mag
  303. vector'''
  304. m_body = Vector3(RAW_IMU.xmag, RAW_IMU.ymag, RAW_IMU.zmag)
  305. m_earth = Vector3(m_body.length(), 0, 0)
  306. r = Matrix3()
  307. r.from_euler(0, -radians(inclination), radians(declination))
  308. m_earth = r * m_earth
  309. r.from_two_vectors(m_earth, m_body)
  310. return r
  311. def mag_yaw(RAW_IMU, inclination, declination):
  312. '''estimate yaw from mag'''
  313. m = mag_rotation(RAW_IMU, inclination, declination)
  314. (r, p, y) = m.to_euler()
  315. y = degrees(y)
  316. if y < 0:
  317. y += 360
  318. return y
  319. def mag_pitch(RAW_IMU, inclination, declination):
  320. '''estimate pithc from mag'''
  321. m = mag_rotation(RAW_IMU, inclination, declination)
  322. (r, p, y) = m.to_euler()
  323. return degrees(p)
  324. def mag_roll(RAW_IMU, inclination, declination):
  325. '''estimate roll from mag'''
  326. m = mag_rotation(RAW_IMU, inclination, declination)
  327. (r, p, y) = m.to_euler()
  328. return degrees(r)
  329. def gravity(RAW_IMU, SENSOR_OFFSETS=None, ofs=None, mul=None, smooth=0.7):
  330. '''estimate pitch from accelerometer'''
  331. if hasattr(RAW_IMU, 'xacc'):
  332. rx = RAW_IMU.xacc * 9.81 / 1000.0
  333. ry = RAW_IMU.yacc * 9.81 / 1000.0
  334. rz = RAW_IMU.zacc * 9.81 / 1000.0
  335. else:
  336. rx = RAW_IMU.AccX
  337. ry = RAW_IMU.AccY
  338. rz = RAW_IMU.AccZ
  339. if SENSOR_OFFSETS is not None and ofs is not None:
  340. rx += SENSOR_OFFSETS.accel_cal_x
  341. ry += SENSOR_OFFSETS.accel_cal_y
  342. rz += SENSOR_OFFSETS.accel_cal_z
  343. rx -= ofs[0]
  344. ry -= ofs[1]
  345. rz -= ofs[2]
  346. if mul is not None:
  347. rx *= mul[0]
  348. ry *= mul[1]
  349. rz *= mul[2]
  350. return sqrt(rx**2+ry**2+rz**2)
  351. def pitch_sim(SIMSTATE, GPS_RAW):
  352. '''estimate pitch from SIMSTATE accels'''
  353. xacc = SIMSTATE.xacc - lowpass(delta(GPS_RAW.v,"v")*6.6, "v", 0.9)
  354. zacc = SIMSTATE.zacc
  355. zacc += SIMSTATE.ygyro * GPS_RAW.v;
  356. if xacc/zacc >= 1:
  357. return 0
  358. if xacc/zacc <= -1:
  359. return -0
  360. return degrees(-asin(xacc/zacc))
  361. def distance_two(GPS_RAW1, GPS_RAW2, horizontal=True):
  362. '''distance between two points'''
  363. if hasattr(GPS_RAW1, 'Lat'):
  364. lat1 = radians(GPS_RAW1.Lat)
  365. lat2 = radians(GPS_RAW2.Lat)
  366. lon1 = radians(GPS_RAW1.Lng)
  367. lon2 = radians(GPS_RAW2.Lng)
  368. alt1 = GPS_RAW1.Alt
  369. alt2 = GPS_RAW2.Alt
  370. elif hasattr(GPS_RAW1, 'cog'):
  371. lat1 = radians(GPS_RAW1.lat)*1.0e-7
  372. lat2 = radians(GPS_RAW2.lat)*1.0e-7
  373. lon1 = radians(GPS_RAW1.lon)*1.0e-7
  374. lon2 = radians(GPS_RAW2.lon)*1.0e-7
  375. alt1 = GPS_RAW1.alt*0.001
  376. alt2 = GPS_RAW2.alt*0.001
  377. else:
  378. lat1 = radians(GPS_RAW1.lat)
  379. lat2 = radians(GPS_RAW2.lat)
  380. lon1 = radians(GPS_RAW1.lon)
  381. lon2 = radians(GPS_RAW2.lon)
  382. alt1 = GPS_RAW1.alt*0.001
  383. alt2 = GPS_RAW2.alt*0.001
  384. dLat = lat2 - lat1
  385. dLon = lon2 - lon1
  386. a = sin(0.5*dLat)**2 + sin(0.5*dLon)**2 * cos(lat1) * cos(lat2)
  387. c = 2.0 * atan2(sqrt(a), sqrt(1.0-a))
  388. ground_dist = 6371 * 1000 * c
  389. if horizontal:
  390. return ground_dist
  391. return sqrt(ground_dist**2 + (alt2-alt1)**2)
  392. first_fix = None
  393. def distance_home(GPS_RAW):
  394. '''distance from first fix point'''
  395. global first_fix
  396. if (hasattr(GPS_RAW, 'fix_type') and GPS_RAW.fix_type < 2) or \
  397. (hasattr(GPS_RAW, 'Status') and GPS_RAW.Status < 2):
  398. return 0
  399. if first_fix is None:
  400. first_fix = GPS_RAW
  401. return 0
  402. return distance_two(GPS_RAW, first_fix)
  403. def sawtooth(ATTITUDE, amplitude=2.0, period=5.0):
  404. '''sawtooth pattern based on uptime'''
  405. mins = (ATTITUDE.usec * 1.0e-6)/60
  406. p = fmod(mins, period*2)
  407. if p < period:
  408. return amplitude * (p/period)
  409. return amplitude * (period - (p-period))/period
  410. def rate_of_turn(speed, bank):
  411. '''return expected rate of turn in degrees/s for given speed in m/s and
  412. bank angle in degrees'''
  413. if abs(speed) < 2 or abs(bank) > 80:
  414. return 0
  415. ret = degrees(9.81*tan(radians(bank))/speed)
  416. return ret
  417. def wingloading(bank):
  418. '''return expected wing loading factor for a bank angle in radians'''
  419. return 1.0/cos(bank)
  420. def airspeed(VFR_HUD, ratio=None, used_ratio=None, offset=None):
  421. '''recompute airspeed with a different ARSPD_RATIO'''
  422. from . import mavutil
  423. mav = mavutil.mavfile_global
  424. if ratio is None:
  425. ratio = 1.9936 # APM default
  426. if used_ratio is None:
  427. if 'ARSPD_RATIO' in mav.params:
  428. used_ratio = mav.params['ARSPD_RATIO']
  429. else:
  430. print("no ARSPD_RATIO in mav.params")
  431. used_ratio = ratio
  432. if hasattr(VFR_HUD,'airspeed'):
  433. airspeed = VFR_HUD.airspeed
  434. else:
  435. airspeed = VFR_HUD.Airspeed
  436. airspeed_pressure = (airspeed**2) / used_ratio
  437. if offset is not None:
  438. airspeed_pressure += offset
  439. if airspeed_pressure < 0:
  440. airspeed_pressure = 0
  441. airspeed = sqrt(airspeed_pressure * ratio)
  442. return airspeed
  443. def EAS2TAS(ARSP,GPS,BARO,ground_temp=25):
  444. '''EAS2TAS from ARSP.Temp'''
  445. tempK = ground_temp + 273.15 - 0.0065 * GPS.Alt
  446. return sqrt(1.225 / (BARO.Press / (287.26 * tempK)))
  447. def airspeed_ratio(VFR_HUD):
  448. '''recompute airspeed with a different ARSPD_RATIO'''
  449. from . import mavutil
  450. mav = mavutil.mavfile_global
  451. airspeed_pressure = (VFR_HUD.airspeed**2) / ratio
  452. airspeed = sqrt(airspeed_pressure * ratio)
  453. return airspeed
  454. def airspeed_voltage(VFR_HUD, ratio=None):
  455. '''back-calculate the voltage the airspeed sensor must have seen'''
  456. from . import mavutil
  457. mav = mavutil.mavfile_global
  458. if ratio is None:
  459. ratio = 1.9936 # APM default
  460. if 'ARSPD_RATIO' in mav.params:
  461. used_ratio = mav.params['ARSPD_RATIO']
  462. else:
  463. used_ratio = ratio
  464. if 'ARSPD_OFFSET' in mav.params:
  465. offset = mav.params['ARSPD_OFFSET']
  466. else:
  467. return -1
  468. airspeed_pressure = (pow(VFR_HUD.airspeed,2)) / used_ratio
  469. raw = airspeed_pressure + offset
  470. SCALING_OLD_CALIBRATION = 204.8
  471. voltage = 5.0 * raw / 4096
  472. return voltage
  473. def earth_rates(ATTITUDE):
  474. '''return angular velocities in earth frame'''
  475. from math import sin, cos, tan, fabs
  476. p = ATTITUDE.rollspeed
  477. q = ATTITUDE.pitchspeed
  478. r = ATTITUDE.yawspeed
  479. phi = ATTITUDE.roll
  480. theta = ATTITUDE.pitch
  481. psi = ATTITUDE.yaw
  482. phiDot = p + tan(theta)*(q*sin(phi) + r*cos(phi))
  483. thetaDot = q*cos(phi) - r*sin(phi)
  484. if fabs(cos(theta)) < 1.0e-20:
  485. theta += 1.0e-10
  486. psiDot = (q*sin(phi) + r*cos(phi))/cos(theta)
  487. return (phiDot, thetaDot, psiDot)
  488. def roll_rate(ATTITUDE):
  489. '''return roll rate in earth frame'''
  490. (phiDot, thetaDot, psiDot) = earth_rates(ATTITUDE)
  491. return phiDot
  492. def pitch_rate(ATTITUDE):
  493. '''return pitch rate in earth frame'''
  494. (phiDot, thetaDot, psiDot) = earth_rates(ATTITUDE)
  495. return thetaDot
  496. def yaw_rate(ATTITUDE):
  497. '''return yaw rate in earth frame'''
  498. (phiDot, thetaDot, psiDot) = earth_rates(ATTITUDE)
  499. return psiDot
  500. def gps_velocity(GLOBAL_POSITION_INT):
  501. '''return GPS velocity vector'''
  502. return Vector3(GLOBAL_POSITION_INT.vx, GLOBAL_POSITION_INT.vy, GLOBAL_POSITION_INT.vz) * 0.01
  503. def gps_velocity_old(GPS_RAW_INT):
  504. '''return GPS velocity vector'''
  505. return Vector3(GPS_RAW_INT.vel*0.01*cos(radians(GPS_RAW_INT.cog*0.01)),
  506. GPS_RAW_INT.vel*0.01*sin(radians(GPS_RAW_INT.cog*0.01)), 0)
  507. def gps_velocity_body(GPS_RAW_INT, ATTITUDE):
  508. '''return GPS velocity vector in body frame'''
  509. r = rotation(ATTITUDE)
  510. return r.transposed() * Vector3(GPS_RAW_INT.vel*0.01*cos(radians(GPS_RAW_INT.cog*0.01)),
  511. GPS_RAW_INT.vel*0.01*sin(radians(GPS_RAW_INT.cog*0.01)),
  512. -tan(ATTITUDE.pitch)*GPS_RAW_INT.vel*0.01)
  513. def earth_accel(RAW_IMU,ATTITUDE):
  514. '''return earth frame acceleration vector'''
  515. r = rotation(ATTITUDE)
  516. accel = Vector3(RAW_IMU.xacc, RAW_IMU.yacc, RAW_IMU.zacc) * 9.81 * 0.001
  517. return r * accel
  518. def earth_gyro(RAW_IMU,ATTITUDE):
  519. '''return earth frame gyro vector'''
  520. r = rotation(ATTITUDE)
  521. accel = Vector3(degrees(RAW_IMU.xgyro), degrees(RAW_IMU.ygyro), degrees(RAW_IMU.zgyro)) * 0.001
  522. return r * accel
  523. def airspeed_energy_error(NAV_CONTROLLER_OUTPUT, VFR_HUD):
  524. '''return airspeed energy error matching APM internals
  525. This is positive when we are going too slow
  526. '''
  527. aspeed_cm = VFR_HUD.airspeed*100
  528. target_airspeed = NAV_CONTROLLER_OUTPUT.aspd_error + aspeed_cm
  529. airspeed_energy_error = ((target_airspeed*target_airspeed) - (aspeed_cm*aspeed_cm))*0.00005
  530. return airspeed_energy_error
  531. def energy_error(NAV_CONTROLLER_OUTPUT, VFR_HUD):
  532. '''return energy error matching APM internals
  533. This is positive when we are too low or going too slow
  534. '''
  535. aspeed_energy_error = airspeed_energy_error(NAV_CONTROLLER_OUTPUT, VFR_HUD)
  536. alt_error = NAV_CONTROLLER_OUTPUT.alt_error*100
  537. energy_error = aspeed_energy_error + alt_error*0.098
  538. return energy_error
  539. def rover_turn_circle(SERVO_OUTPUT_RAW):
  540. '''return turning circle (diameter) in meters for steering_angle in degrees
  541. '''
  542. # this matches Toms slash
  543. max_wheel_turn = 35
  544. wheelbase = 0.335
  545. wheeltrack = 0.296
  546. steering_angle = max_wheel_turn * (SERVO_OUTPUT_RAW.servo1_raw - 1500) / 400.0
  547. theta = radians(steering_angle)
  548. return (wheeltrack/2) + (wheelbase/sin(theta))
  549. def rover_yaw_rate(VFR_HUD, SERVO_OUTPUT_RAW):
  550. '''return yaw rate in degrees/second given steering_angle and speed'''
  551. max_wheel_turn=35
  552. speed = VFR_HUD.groundspeed
  553. # assume 1100 to 1900 PWM on steering
  554. steering_angle = max_wheel_turn * (SERVO_OUTPUT_RAW.servo1_raw - 1500) / 400.0
  555. if abs(steering_angle) < 1.0e-6 or abs(speed) < 1.0e-6:
  556. return 0
  557. d = rover_turn_circle(SERVO_OUTPUT_RAW)
  558. c = pi * d
  559. t = c / speed
  560. rate = 360.0 / t
  561. return rate
  562. def rover_lat_accel(VFR_HUD, SERVO_OUTPUT_RAW):
  563. '''return lateral acceleration in m/s/s'''
  564. speed = VFR_HUD.groundspeed
  565. yaw_rate = rover_yaw_rate(VFR_HUD, SERVO_OUTPUT_RAW)
  566. accel = radians(yaw_rate) * speed
  567. return accel
  568. def demix1(servo1, servo2, gain=0.5):
  569. '''de-mix a mixed servo output'''
  570. s1 = servo1 - 1500
  571. s2 = servo2 - 1500
  572. out1 = (s1+s2)*gain
  573. out2 = (s1-s2)*gain
  574. return out1+1500
  575. def demix2(servo1, servo2, gain=0.5):
  576. '''de-mix a mixed servo output'''
  577. s1 = servo1 - 1500
  578. s2 = servo2 - 1500
  579. out1 = (s1+s2)*gain
  580. out2 = (s1-s2)*gain
  581. return out2+1500
  582. def mixer(servo1, servo2, mixtype=1, gain=0.5):
  583. '''mix two servos'''
  584. s1 = servo1 - 1500
  585. s2 = servo2 - 1500
  586. v1 = (s1-s2)*gain
  587. v2 = (s1+s2)*gain
  588. if mixtype == 2:
  589. v2 = -v2
  590. elif mixtype == 3:
  591. v1 = -v1
  592. elif mixtype == 4:
  593. v1 = -v1
  594. v2 = -v2
  595. if v1 > 600:
  596. v1 = 600
  597. elif v1 < -600:
  598. v1 = -600
  599. if v2 > 600:
  600. v2 = 600
  601. elif v2 < -600:
  602. v2 = -600
  603. return (1500+v1,1500+v2)
  604. def mix1(servo1, servo2, mixtype=1, gain=0.5):
  605. '''de-mix a mixed servo output'''
  606. (v1,v2) = mixer(servo1, servo2, mixtype=mixtype, gain=gain)
  607. return v1
  608. def mix2(servo1, servo2, mixtype=1, gain=0.5):
  609. '''de-mix a mixed servo output'''
  610. (v1,v2) = mixer(servo1, servo2, mixtype=mixtype, gain=gain)
  611. return v2
  612. def wrap_180(angle):
  613. if angle > 180:
  614. angle -= 360.0
  615. if angle < -180:
  616. angle += 360.0
  617. return angle
  618. def wrap_360(angle):
  619. if angle > 360:
  620. angle -= 360.0
  621. if angle < 0:
  622. angle += 360.0
  623. return angle
  624. class DCM_State(object):
  625. '''DCM state object'''
  626. def __init__(self, roll, pitch, yaw):
  627. self.dcm = Matrix3()
  628. self.dcm2 = Matrix3()
  629. self.dcm.from_euler(radians(roll), radians(pitch), radians(yaw))
  630. self.dcm2.from_euler(radians(roll), radians(pitch), radians(yaw))
  631. self.mag = Vector3()
  632. self.gyro = Vector3()
  633. self.accel = Vector3()
  634. self.gps = None
  635. self.rate = 50.0
  636. self.kp = 0.2
  637. self.kp_yaw = 0.3
  638. self.omega_P = Vector3()
  639. self.omega_P_yaw = Vector3()
  640. self.omega_I = Vector3() # (-0.00199045287445, -0.00653007719666, -0.00714212376624)
  641. self.omega_I_sum = Vector3()
  642. self.omega_I_sum_time = 0
  643. self.omega = Vector3()
  644. self.ra_sum = Vector3()
  645. self.last_delta_angle = Vector3()
  646. self.last_velocity = Vector3()
  647. (self.roll, self.pitch, self.yaw) = self.dcm.to_euler()
  648. (self.roll2, self.pitch2, self.yaw2) = self.dcm2.to_euler()
  649. def update(self, gyro, accel, mag, GPS):
  650. if self.gyro != gyro or self.accel != accel:
  651. delta_angle = old_div((gyro+self.omega_I), self.rate)
  652. self.dcm.rotate(delta_angle)
  653. correction = self.last_delta_angle % delta_angle
  654. #print (delta_angle - self.last_delta_angle) * 58.0
  655. corrected_delta = delta_angle + 0.0833333 * correction
  656. self.dcm2.rotate(corrected_delta)
  657. self.last_delta_angle = delta_angle
  658. self.dcm.normalize()
  659. self.dcm2.normalize()
  660. self.gyro = gyro
  661. self.accel = accel
  662. (self.roll, self.pitch, self.yaw) = self.dcm.to_euler()
  663. (self.roll2, self.pitch2, self.yaw2) = self.dcm2.to_euler()
  664. dcm_state = None
  665. def DCM_update(IMU, ATT, MAG, GPS):
  666. '''implement full DCM system'''
  667. global dcm_state
  668. if dcm_state is None:
  669. dcm_state = DCM_State(ATT.Roll, ATT.Pitch, ATT.Yaw)
  670. mag = Vector3(MAG.MagX, MAG.MagY, MAG.MagZ)
  671. gyro = Vector3(IMU.GyrX, IMU.GyrY, IMU.GyrZ)
  672. accel = Vector3(IMU.AccX, IMU.AccY, IMU.AccZ)
  673. accel2 = Vector3(IMU.AccX, IMU.AccY, IMU.AccZ)
  674. dcm_state.update(gyro, accel, mag, GPS)
  675. return dcm_state
  676. class PX4_State(object):
  677. '''PX4 DCM state object'''
  678. def __init__(self, roll, pitch, yaw, timestamp):
  679. self.dcm = Matrix3()
  680. self.dcm.from_euler(radians(roll), radians(pitch), radians(yaw))
  681. self.gyro = Vector3()
  682. self.accel = Vector3()
  683. self.timestamp = timestamp
  684. (self.roll, self.pitch, self.yaw) = self.dcm.to_euler()
  685. def update(self, gyro, accel, timestamp):
  686. if self.gyro != gyro or self.accel != accel:
  687. delta_angle = gyro * (timestamp - self.timestamp)
  688. self.timestamp = timestamp
  689. self.dcm.rotate(delta_angle)
  690. self.dcm.normalize()
  691. self.gyro = gyro
  692. self.accel = accel
  693. (self.roll, self.pitch, self.yaw) = self.dcm.to_euler()
  694. px4_state = None
  695. def PX4_update(IMU, ATT):
  696. '''implement full DCM using PX4 native SD log data'''
  697. global px4_state
  698. if px4_state is None:
  699. px4_state = PX4_State(degrees(ATT.Roll), degrees(ATT.Pitch), degrees(ATT.Yaw), IMU._timestamp)
  700. gyro = Vector3(IMU.GyroX, IMU.GyroY, IMU.GyroZ)
  701. accel = Vector3(IMU.AccX, IMU.AccY, IMU.AccZ)
  702. px4_state.update(gyro, accel, IMU._timestamp)
  703. return px4_state
  704. _downsample_N = 0
  705. def downsample(N):
  706. '''conditional that is true on every Nth sample'''
  707. global _downsample_N
  708. _downsample_N = (_downsample_N + 1) % N
  709. return _downsample_N == 0
  710. def armed(HEARTBEAT):
  711. '''return 1 if armed, 0 if not'''
  712. from . import mavutil
  713. if HEARTBEAT.type == mavutil.mavlink.MAV_TYPE_GCS:
  714. self = mavutil.mavfile_global
  715. if self.motors_armed():
  716. return 1
  717. return 0
  718. if HEARTBEAT.base_mode & mavutil.mavlink.MAV_MODE_FLAG_SAFETY_ARMED:
  719. return 1
  720. return 0
  721. def rotation_df(ATT):
  722. '''return the current DCM rotation matrix'''
  723. r = Matrix3()
  724. r.from_euler(radians(ATT.Roll), radians(ATT.Pitch), radians(ATT.Yaw))
  725. return r
  726. def rotation2(AHRS2):
  727. '''return the current DCM rotation matrix'''
  728. r = Matrix3()
  729. r.from_euler(AHRS2.roll, AHRS2.pitch, AHRS2.yaw)
  730. return r
  731. def earth_accel2(RAW_IMU,ATTITUDE):
  732. '''return earth frame acceleration vector from AHRS2'''
  733. r = rotation2(ATTITUDE)
  734. accel = Vector3(RAW_IMU.xacc, RAW_IMU.yacc, RAW_IMU.zacc) * 9.81 * 0.001
  735. return r * accel
  736. def earth_accel_df(IMU,ATT):
  737. '''return earth frame acceleration vector from df log'''
  738. r = rotation_df(ATT)
  739. accel = Vector3(IMU.AccX, IMU.AccY, IMU.AccZ)
  740. return r * accel
  741. def earth_accel2_df(IMU,IMU2,ATT):
  742. '''return earth frame acceleration vector from df log'''
  743. r = rotation_df(ATT)
  744. accel1 = Vector3(IMU.AccX, IMU.AccY, IMU.AccZ)
  745. accel2 = Vector3(IMU2.AccX, IMU2.AccY, IMU2.AccZ)
  746. accel = 0.5 * (accel1 + accel2)
  747. return r * accel
  748. def gps_velocity_df(GPS):
  749. '''return GPS velocity vector'''
  750. vx = GPS.Spd * cos(radians(GPS.GCrs))
  751. vy = GPS.Spd * sin(radians(GPS.GCrs))
  752. return Vector3(vx, vy, GPS.VZ)
  753. def distance_gps2(GPS, GPS2):
  754. '''distance between two points'''
  755. if GPS.TimeMS != GPS2.TimeMS:
  756. # reject messages not time aligned
  757. return None
  758. return distance_two(GPS, GPS2)
  759. radius_of_earth = 6378100.0 # in meters
  760. def wrap_valid_longitude(lon):
  761. ''' wrap a longitude value around to always have a value in the range
  762. [-180, +180) i.e 0 => 0, 1 => 1, -1 => -1, 181 => -179, -181 => 179
  763. '''
  764. return (((lon + 180.0) % 360.0) - 180.0)
  765. def gps_newpos(lat, lon, bearing, distance):
  766. '''extrapolate latitude/longitude given a heading and distance
  767. thanks to http://www.movable-type.co.uk/scripts/latlong.html
  768. '''
  769. import math
  770. lat1 = math.radians(lat)
  771. lon1 = math.radians(lon)
  772. brng = math.radians(bearing)
  773. dr = distance/radius_of_earth
  774. lat2 = math.asin(math.sin(lat1)*math.cos(dr) +
  775. math.cos(lat1)*math.sin(dr)*math.cos(brng))
  776. lon2 = lon1 + math.atan2(math.sin(brng)*math.sin(dr)*math.cos(lat1),
  777. math.cos(dr)-math.sin(lat1)*math.sin(lat2))
  778. return (math.degrees(lat2), wrap_valid_longitude(math.degrees(lon2)))
  779. def gps_offset(lat, lon, east, north):
  780. '''return new lat/lon after moving east/north
  781. by the given number of meters'''
  782. import math
  783. bearing = math.degrees(math.atan2(east, north))
  784. distance = math.sqrt(east**2 + north**2)
  785. return gps_newpos(lat, lon, bearing, distance)
  786. ekf_home = None
  787. def ekf1_pos(EKF1):
  788. '''calculate EKF position when EKF disabled'''
  789. global ekf_home
  790. from . import mavutil
  791. self = mavutil.mavfile_global
  792. if ekf_home is None:
  793. if not 'GPS' in self.messages or self.messages['GPS'].Status != 3:
  794. return None
  795. ekf_home = self.messages['GPS']
  796. (ekf_home.Lat, ekf_home.Lng) = gps_offset(ekf_home.Lat, ekf_home.Lng, -EKF1.PE, -EKF1.PN)
  797. (lat,lon) = gps_offset(ekf_home.Lat, ekf_home.Lng, EKF1.PE, EKF1.PN)
  798. return (lat, lon)
  799. def quat_to_euler(q):
  800. '''
  801. Get Euler angles from a quaternion
  802. :param q: quaternion [w, x, y , z]
  803. :returns: euler angles [roll, pitch, yaw]
  804. '''
  805. quat = Quaternion(q)
  806. return quat.euler
  807. def euler_to_quat(e):
  808. '''
  809. Get quaternion from euler angles
  810. :param e: euler angles [roll, pitch, yaw]
  811. :returns: quaternion [w, x, y , z]
  812. '''
  813. quat = Quaternion(e)
  814. return quat.q
  815. def rotate_quat(attitude, roll, pitch, yaw):
  816. '''
  817. Returns rotated quaternion
  818. :param attitude: quaternion [w, x, y , z]
  819. :param roll: rotation in rad
  820. :param pitch: rotation in rad
  821. :param yaw: rotation in rad
  822. :returns: quaternion [w, x, y , z]
  823. '''
  824. quat = Quaternion(attitude)
  825. rotation = Quaternion([roll, pitch, yaw])
  826. res = rotation * quat
  827. return res.q
  828. def qroll(MSG):
  829. '''return quaternion roll in degrees'''
  830. q = Quaternion([MSG.Q1,MSG.Q2,MSG.Q3,MSG.Q4])
  831. return degrees(q.euler[0])
  832. def qpitch(MSG):
  833. '''return quaternion pitch in degrees'''
  834. q = Quaternion([MSG.Q1,MSG.Q2,MSG.Q3,MSG.Q4])
  835. return degrees(q.euler[1])
  836. def qyaw(MSG):
  837. '''return quaternion yaw in degrees'''
  838. q = Quaternion([MSG.Q1,MSG.Q2,MSG.Q3,MSG.Q4])
  839. return degrees(q.euler[2])
  840. def euler_rotated(MSG, roll, pitch, yaw):
  841. '''return eulers in radians from quaternion for view at given attitude in euler radians'''
  842. rot_view = Matrix3()
  843. rot_view.from_euler(roll, pitch, yaw)
  844. q = Quaternion([MSG.Q1,MSG.Q2,MSG.Q3,MSG.Q4])
  845. dcm = (rot_view * q.dcm.transposed()).transposed()
  846. return dcm.to_euler()
  847. def euler_p90(MSG):
  848. '''return eulers in radians from quaternion for view at pitch 90'''
  849. return euler_rotated(MSG, 0, radians(90), 0);
  850. def qroll_p90(MSG):
  851. '''return quaternion roll in degrees for view at pitch 90'''
  852. return degrees(euler_p90(MSG)[0])
  853. def qpitch_p90(MSG):
  854. '''return quaternion roll in degrees for view at pitch 90'''
  855. return degrees(euler_p90(MSG)[1])
  856. def qyaw_p90(MSG):
  857. '''return quaternion roll in degrees for view at pitch 90'''
  858. return degrees(euler_p90(MSG)[2])
  859. def rotation_df(ATT):
  860. '''return the current DCM rotation matrix'''
  861. r = Matrix3()
  862. r.from_euler(radians(ATT.Roll), radians(ATT.Pitch), radians(ATT.Yaw))
  863. return r
  864. def rotation2(AHRS2):
  865. '''return the current DCM rotation matrix'''
  866. r = Matrix3()
  867. r.from_euler(AHRS2.roll, AHRS2.pitch, AHRS2.yaw)
  868. return r
  869. def earth_accel2(RAW_IMU,ATTITUDE):
  870. '''return earth frame acceleration vector from AHRS2'''
  871. r = rotation2(ATTITUDE)
  872. accel = Vector3(RAW_IMU.xacc, RAW_IMU.yacc, RAW_IMU.zacc) * 9.81 * 0.001
  873. return r * accel
  874. def earth_accel_df(IMU,ATT):
  875. '''return earth frame acceleration vector from df log'''
  876. r = rotation_df(ATT)
  877. accel = Vector3(IMU.AccX, IMU.AccY, IMU.AccZ)
  878. return r * accel
  879. def earth_accel2_df(IMU,IMU2,ATT):
  880. '''return earth frame acceleration vector from df log'''
  881. r = rotation_df(ATT)
  882. accel1 = Vector3(IMU.AccX, IMU.AccY, IMU.AccZ)
  883. accel2 = Vector3(IMU2.AccX, IMU2.AccY, IMU2.AccZ)
  884. accel = 0.5 * (accel1 + accel2)
  885. return r * accel
  886. def gps_velocity_df(GPS):
  887. '''return GPS velocity vector'''
  888. vx = GPS.Spd * cos(radians(GPS.GCrs))
  889. vy = GPS.Spd * sin(radians(GPS.GCrs))
  890. return Vector3(vx, vy, GPS.VZ)
  891. def armed(HEARTBEAT):
  892. '''return 1 if armed, 0 if not'''
  893. from pymavlink import mavutil
  894. if HEARTBEAT.type == mavutil.mavlink.MAV_TYPE_GCS:
  895. self = mavutil.mavfile_global
  896. if self.motors_armed():
  897. return 1
  898. return 0
  899. if HEARTBEAT.base_mode & mavutil.mavlink.MAV_MODE_FLAG_SAFETY_ARMED:
  900. return 1
  901. return 0
  902. def mode(HEARTBEAT):
  903. '''return flight mode number'''
  904. from pymavlink import mavutil
  905. if HEARTBEAT.type == mavutil.mavlink.MAV_TYPE_GCS:
  906. return None
  907. return HEARTBEAT.custom_mode
  908. '''
  909. magnetic field tables for estimating earths mag field
  910. '''
  911. # set to the sampling in degrees for the table below
  912. SAMPLING_RES = 10.0
  913. SAMPLING_MIN_LAT = -60.0
  914. SAMPLING_MAX_LAT = 60.0
  915. SAMPLING_MIN_LON = -180.0
  916. SAMPLING_MAX_LON = 180.0
  917. # table data containing magnetic declination angle in degrees
  918. declination_table = [
  919. [47.225,46.016,44.6,43.214,41.929,40.625,38.996,36.648,33.246,28.649,22.973,16.599,10.096,4.0412,-1.2113,-5.7129,-9.9239,-14.505,-19.992,-26.538,-33.881,-41.531,-48.995,-55.908,-62.043,-67.26,-71.433,-74.32,-75.32,-72.759,-61.089,-22.66,24.673,41.679,46.715,47.77,47.225],
  920. [30.663,30.935,30.729,30.365,30.083,29.989,29.903,29.306,27.493,23.864,18.229,11.012,3.2503,-3.7771,-9.1638,-12.793,-15.299,-17.753,-21.275,-26.491,-33.098,-40.129,-46.619,-51.911,-55.576,-57.256,-56.482,-52.464,-44.092,-30.765,-14.236,1.4682,13.543,21.705,26.727,29.465,30.663],
  921. [22.141,22.67,22.786,22.665,22.457,22.365,22.478,22.512,21.659,18.814,13.22,5.1441,-3.8724,-11.749,-17.208,-20.303,-21.777,-22.354,-23.04,-25.422,-30.143,-35.947,-41.114,-44.536,-45.603,-43.943,-39.28,-31.541,-21.622,-11.631,-3.1023,3.9413,9.8774,14.757,18.445,20.858,22.141],
  922. [16.701,17.175,17.415,17.473,17.283,16.943,16.689,16.566,15.935,13.436,7.8847,-0.52637,-9.7982,-17.399,-22.182,-24.63,-25.544,-24.89,-22.583,-20.489,-21.371,-25.128,-29.294,-31.76,-31.569,-28.686,-23.466,-16.487,-9.2421,-3.5196,0.52944,4.0043,7.5112,10.847,13.654,15.633,16.701],
  923. [13.062,13.307,13.488,13.647,13.552,13.138,12.644,12.281,11.511,8.9083,3.288,-4.9363,-13.534,-20.108,-23.761,-24.943,-24.267,-21.633,-16.975,-11.895,-9.3052,-10.608,-14.22,-17.235,-17.896,-16.21,-12.734,-7.944,-3.1917,-0.09448,1.5925,3.3685,5.7977,8.374,10.643,12.277,13.062],
  924. [10.819,10.774,10.744,10.873,10.857,10.513,10.051,9.6504,8.6623,5.7203,-0.00103,-7.7113,-15.239,-20.543,-22.747,-22.021,-19.117,-14.884,-10.06,-5.4668,-2.2918,-1.8711,-4.2049,-7.1881,-8.7089,-8.4387,-6.7419,-3.8048,-0.7327,0.90936,1.399,2.3853,4.3796,6.6682,8.7425,10.241,10.819],
  925. [9.6261,9.4267,9.2035,9.2862,9.3524,9.1115,8.7204,8.235,6.8708,3.4733,-2.2704,-9.2885,-15.646,-19.575,-20.227,-17.864,-13.663,-9.1469,-5.2757,-2.071,0.49345,1.5251,0.29098,-2.0644,-3.6913,-4.1179,-3.5596,-1.9862,-0.1684,0.55548,0.42539,1.019,2.8249,5.1073,7.319,8.9998,9.6261],
  926. [8.9369,8.9745,8.8157,9.0087,9.2615,9.1408,8.6708,7.7842,5.7199,1.6936,-4.0873,-10.373,-15.479,-17.961,-17.333,-14.207,-9.8358,-5.6345,-2.4989,-0.22009,1.7216,2.8156,2.1698,0.36849,-1.0742,-1.6949,-1.7318,-1.1504,-0.42435,-0.50061,-1.1161,-0.88856,0.69851,3.0638,5.6417,7.8392,8.9369],
  927. [8.0661,8.9128,9.3097,9.8875,10.445,10.466,9.7864,8.2288,5.1818,0.28672,-5.7524,-11.438,-15.264,-16.348,-14.841,-11.596,-7.5597,-3.7288,-0.91243,0.96946,2.51,3.5079,3.1926,1.8339,0.62026,-0.01417,-0.36046,-0.53631,-0.84781,-1.8165,-3.0616,-3.3677,-2.1514,0.22612,3.1996,6.0876,8.0661],
  928. [6.6045,8.7101,10.209,11.491,12.418,12.553,11.622,9.3409,5.2254,-0.73322,-7.3408,-12.717,-15.505,-15.494,-13.422,-10.206,-6.4719,-2.8539,-0.05159,1.8185,3.2182,4.1923,4.2452,3.4363,2.5284,1.8671,1.1902,0.25353,-1.1684,-3.2141,-5.2908,-6.2436,-5.4483,-3.1334,0.11904,3.6145,6.6045],
  929. [4.8686,8.2538,11.062,13.264,14.651,14.898,13.714,10.725,5.4958,-1.7139,-9.1709,-14.568,-16.765,-16.116,-13.666,-10.317,-6.5773,-2.906,0.14042,2.3482,3.9956,5.2703,5.9678,5.9805,5.5419,4.7751,3.4951,1.4836,-1.3442,-4.7282,-7.762,-9.283,-8.7476,-6.4234,-2.9491,1.0086,4.8686],
  930. [3.5965,7.9367,11.797,14.893,16.888,17.409,16.035,12.22,5.5033,-3.468,-12.144,-17.817,-19.749,-18.751,-15.97,-12.268,-8.1724,-4.1017,-0.46224,2.551,5.0589,7.2268,8.9817,10.082,10.298,9.416,7.21,3.5705,-1.2522,-6.3856,-10.448,-12.313,-11.73,-9.1743,-5.367,-0.9513,3.5965],
  931. [3.0633,8.0696,12.667,16.527,19.239,20.252,18.783,13.765,4.4393,-7.6723,-18.2,-24.093,-25.554,-23.984,-20.61,-16.25,-11.425,-6.5023,-1.759,2.6571,6.7294,10.458,13.708,16.148,17.3,16.587,13.441,7.6143,-0.14961,-7.7957,-13.103,-15.143,-14.253,-11.262,-6.9868,-2.0631,3.0633]
  932. ]
  933. # table data containing magnetic inclination angle in degrees
  934. inclination_table = [
  935. [-77.62,-75.621,-73.703,-71.805,-69.84,-67.703,-65.317,-62.69,-59.968,-57.429,-55.437,-54.313,-54.191,-54.921,-56.118,-57.329,-58.214,-58.643,-58.712,-58.692,-58.934,-59.74,-61.257,-63.461,-66.211,-69.329,-72.657,-76.065,-79.441,-82.661,-85.506,-87.208,-86.36,-84.237,-81.951,-79.73,-77.62],
  936. [-71.644,-69.722,-67.862,-66.038,-64.191,-62.202,-59.91,-57.194,-54.113,-51.035,-48.639,-47.697,-48.625,-51.137,-54.39,-57.488,-59.821,-61.085,-61.237,-60.574,-59.768,-59.618,-60.616,-62.761,-65.711,-69.044,-72.416,-75.556,-78.175,-79.936,-80.593,-80.201,-79.054,-77.45,-75.591,-73.62,-71.644],
  937. [-64.379,-62.435,-60.505,-58.564,-56.621,-54.665,-52.574,-50.107,-47.083,-43.756,-41.093,-40.479,-42.721,-47.229,-52.537,-57.471,-61.513,-64.379,-65.669,-65.164,-63.395,-61.672,-61.269,-62.55,-65.012,-67.881,-70.533,-72.526,-73.547,-73.61,-73.075,-72.251,-71.191,-69.844,-68.201,-66.334,-64.379],
  938. [-54.946,-52.868,-50.792,-48.616,-46.372,-44.193,-42.1,-39.8,-36.829,-33.264,-30.385,-30.266,-34.046,-40.628,-47.854,-54.358,-59.856,-64.283,-67.119,-67.68,-65.968,-63.1,-60.894,-60.535,-61.761,-63.584,-65.189,-66.021,-65.775,-64.769,-63.698,-62.826,-61.898,-60.654,-59.023,-57.056,-54.946],
  939. [-42.121,-39.754,-37.516,-35.153,-32.626,-30.14,-27.828,-25.343,-22.028,-18.017,-15.062,-15.744,-21.265,-30.112,-39.56,-47.788,-54.306,-59.187,-62.247,-63.04,-61.444,-58.163,-54.854,-53.154,-53.207,-54.092,-55.004,-55.267,-54.381,-52.801,-51.562,-50.874,-50.1,-48.81,-46.97,-44.643,-42.121],
  940. [-25.138,-22.301,-19.912,-17.531,-14.951,-12.37,-9.9146,-7.1192,-3.3525,0.86465,3.4285,1.8632,-4.8485,-15.374,-26.858,-36.666,-43.599,-47.78,-49.783,-49.893,-48.024,-44.445,-40.638,-38.414,-38.009,-38.508,-39.247,-39.498,-38.5,-36.768,-35.692,-35.432,-34.911,-33.532,-31.323,-28.369,-25.138],
  941. [-4.9962,-1.7126,0.71401,2.8847,5.219,7.5873,9.91,12.689,16.306,19.897,21.553,19.47,12.842,2.3904,-9.4406,-19.56,-26.119,-29.178,-29.919,-29.286,-27.194,-23.471,-19.459,-17.133,-16.698,-17.132,-17.899,-18.371,-17.66,-16.255,-15.708,-16.114,-16.082,-14.846,-12.422,-8.9145,-4.9962],
  942. [14.869,18.185,20.462,22.293,24.256,26.334,28.442,30.896,33.762,36.172,36.784,34.538,28.924,20.356,10.616,2.2154,-3.0793,-5.0649,-4.8917,-3.7875,-1.7639,1.5757,5.1722,7.2324,7.5774,7.2059,6.5718,6.0595,6.3467,7.0334,6.8289,5.7043,4.9959,5.5796,7.5845,10.93,14.869],
  943. [31.164,34.006,36.041,37.647,39.383,41.332,43.382,45.569,47.716,49.104,48.9,46.613,42.181,36.116,29.611,24.084,20.599,19.485,20.056,21.274,22.956,25.416,28.017,29.529,29.786,29.536,29.184,28.895,28.929,28.95,28.145,26.531,25.104,24.717,25.695,28.042,31.164],
  944. [43.422,45.479,47.235,48.815,50.558,52.55,54.665,56.761,58.528,59.374,58.753,56.548,53.102,49.074,45.208,42.092,40.16,39.643,40.248,41.324,42.606,44.197,45.811,46.815,47.078,47.021,46.948,46.916,46.893,46.555,45.437,43.596,41.72,40.533,40.438,41.516,43.422],
  945. [53.102,54.356,55.814,57.449,59.331,61.427,63.597,65.639,67.216,67.832,67.107,65.133,62.449,59.699,57.346,55.602,54.591,54.397,54.884,55.703,56.613,57.588,58.539,59.25,59.652,59.904,60.137,60.33,60.32,59.812,58.553,56.66,54.639,53.044,52.229,52.294,53.102],
  946. [61.877,62.601,63.785,65.363,67.255,69.332,71.425,73.313,74.675,75.099,74.352,72.651,70.529,68.494,66.843,65.687,65.049,64.919,65.198,65.705,66.286,66.893,67.525,68.165,68.802,69.44,70.041,70.469,70.5,69.901,68.591,66.775,64.856,63.228,62.144,61.699,61.877],
  947. [70.565,71.043,71.969,73.282,74.89,76.669,78.458,80.035,81.082,81.248,80.439,78.963,77.256,75.651,74.334,73.378,72.792,72.544,72.57,72.785,73.123,73.565,74.13,74.845,75.713,76.683,77.618,78.289,78.419,77.836,76.61,75.025,73.414,72.04,71.067,70.568,70.565]
  948. ]
  949. # table data containing magnetic intensity in Gauss
  950. intensity_table = [
  951. [0.62195,0.60352,0.58407,0.56378,0.54235,0.5192,0.49375,0.46596,0.43661,0.40734,0.38017,0.35689,0.33841,0.32458,0.31447,0.30707,0.302,0.29983,0.30197,0.31023,0.32606,0.35005,0.38167,0.41941,0.4611,0.50431,0.54648,0.58515,0.61805,0.64341,0.66031,0.66875,0.6695,0.66384,0.65315,0.6388,0.62195],
  952. [0.58699,0.56471,0.54222,0.51977,0.49699,0.47285,0.44606,0.4159,0.38299,0.3495,0.31875,0.29401,0.2771,0.26745,0.26251,0.25941,0.25657,0.25431,0.25469,0.26104,0.27676,0.30379,0.34157,0.38741,0.43751,0.48812,0.53602,0.57843,0.61292,0.63771,0.65218,0.65693,0.65331,0.64296,0.62744,0.6083,0.58699],
  953. [0.54115,0.51716,0.49337,0.47003,0.44701,0.42359,0.39839,0.37018,0.33882,0.30605,0.27573,0.25265,0.23995,0.23673,0.23869,0.24146,0.24284,0.24258,0.24188,0.24416,0.25504,0.27952,0.31847,0.36815,0.42238,0.47534,0.52306,0.56286,0.59276,0.61199,0.62133,0.62218,0.61584,0.60338,0.58585,0.56455,0.54115],
  954. [0.48901,0.46546,0.44226,0.41941,0.39712,0.37544,0.35375,0.33083,0.30548,0.27808,0.25206,0.23294,0.22466,0.22623,0.23284,0.24043,0.24771,0.25392,0.25756,0.2592,0.26416,0.28046,0.31301,0.35947,0.41201,0.4626,0.5061,0.53933,0.56053,0.57088,0.5738,0.57145,0.56393,0.55115,0.53361,0.51231,0.48901],
  955. [0.43275,0.41204,0.39186,0.37191,0.35253,0.33441,0.31775,0.3017,0.28442,0.26511,0.24603,0.23176,0.22605,0.22892,0.2372,0.24818,0.2613,0.27524,0.28613,0.2912,0.29315,0.29999,0.32028,0.35581,0.39969,0.44294,0.47952,0.50496,0.51672,0.51792,0.51496,0.51028,0.50215,0.48957,0.47314,0.45367,0.43275],
  956. [0.37936,0.36387,0.34916,0.33493,0.32156,0.30968,0.29963,0.29094,0.28194,0.27119,0.25923,0.24862,0.24246,0.2429,0.25003,0.26227,0.27786,0.29465,0.30882,0.3168,0.31873,0.3201,0.32969,0.35219,0.38333,0.41554,0.44325,0.46129,0.46614,0.4614,0.45461,0.44801,0.43895,0.4265,0.41178,0.39569,0.37936],
  957. [0.34151,0.33271,0.3248,0.31786,0.31251,0.30889,0.30674,0.30563,0.30411,0.30005,0.29252,0.28275,0.27347,0.26836,0.27051,0.27963,0.29265,0.30666,0.31919,0.32782,0.33164,0.33341,0.33926,0.35308,0.37271,0.39367,0.41222,0.42402,0.42574,0.41956,0.41085,0.40143,0.39009,0.37701,0.36387,0.35184,0.34151],
  958. [0.32861,0.32598,0.32444,0.32451,0.32723,0.33225,0.33844,0.34476,0.34925,0.34892,0.34232,0.33071,0.31718,0.30603,0.30142,0.30408,0.3115,0.32118,0.33137,0.34024,0.34686,0.35275,0.36068,0.37146,0.38401,0.39715,0.40907,0.41682,0.418,0.41256,0.40201,0.38791,0.37189,0.35616,0.34293,0.33373,0.32861],
  959. [0.34027,0.34127,0.34464,0.3507,0.36038,0.37294,0.3865,0.39917,0.40815,0.4099,0.40274,0.38831,0.37072,0.3552,0.34582,0.34316,0.34566,0.35218,0.36135,0.37089,0.37971,0.38903,0.39965,0.41036,0.42049,0.43072,0.44044,0.44743,0.44945,0.44455,0.43158,0.41195,0.38966,0.369,0.35302,0.34348,0.34027],
  960. [0.37253,0.3743,0.38082,0.39172,0.4068,0.42456,0.44274,0.45904,0.47046,0.47349,0.4662,0.45016,0.43012,0.41204,0.39986,0.39392,0.39314,0.39717,0.40505,0.41434,0.42357,0.43356,0.44488,0.45654,0.46802,0.47977,0.49115,0.5,0.50357,0.49896,0.48426,0.46097,0.43398,0.40879,0.38917,0.37703,0.37253],
  961. [0.42232,0.42361,0.43153,0.44511,0.46277,0.48222,0.50102,0.51697,0.52763,0.53021,0.5231,0.50749,0.48759,0.46872,0.4545,0.44574,0.44202,0.44314,0.44829,0.45556,0.46359,0.47278,0.48398,0.49721,0.51197,0.52753,0.54226,0.5536,0.55855,0.55434,0.53968,0.51634,0.489,0.46299,0.44215,0.4284,0.42232],
  962. [0.48297,0.48409,0.49144,0.50386,0.51947,0.53592,0.55104,0.56298,0.57002,0.57048,0.5635,0.54997,0.53268,0.51524,0.50048,0.48973,0.48333,0.48125,0.48294,0.48735,0.49374,0.50234,0.51385,0.52856,0.54583,0.56407,0.58089,0.59345,0.59903,0.5957,0.58321,0.56356,0.54058,0.51853,0.50058,0.4885,0.48297],
  963. [0.53888,0.53954,0.54416,0.55185,0.5613,0.57099,0.5795,0.58558,0.58818,0.58651,0.58029,0.57006,0.55723,0.54365,0.53109,0.52078,0.51346,0.50946,0.50872,0.51103,0.51624,0.52445,0.53585,0.55027,0.56682,0.58384,0.59914,0.61041,0.61575,0.61419,0.60607,0.59307,0.5778,0.563,0.55086,0.54264,0.53888]
  964. ]
  965. '''
  966. calculate magnetic field intensity and orientation
  967. returns array [declination_deg, inclination_deg, intensity] or None
  968. '''
  969. def get_mag_field_ef(latitude_deg, longitude_deg):
  970. # round down to nearest sampling resolution
  971. min_lat = int(floor(latitude_deg / SAMPLING_RES) * SAMPLING_RES)
  972. min_lon = int(floor(longitude_deg / SAMPLING_RES) * SAMPLING_RES)
  973. # limit to table bounds
  974. if latitude_deg <= SAMPLING_MIN_LAT:
  975. return None
  976. if latitude_deg >= SAMPLING_MAX_LAT:
  977. return None
  978. if longitude_deg <= SAMPLING_MIN_LON:
  979. return None
  980. if longitude_deg >= SAMPLING_MAX_LON:
  981. return None
  982. # find index of nearest low sampling point
  983. min_lat_index = int(floor(-(SAMPLING_MIN_LAT) + min_lat) / SAMPLING_RES)
  984. min_lon_index = int(floor(-(SAMPLING_MIN_LON) + min_lon) / SAMPLING_RES)
  985. # calculate intensity
  986. data_sw = intensity_table[min_lat_index][min_lon_index]
  987. data_se = intensity_table[min_lat_index][min_lon_index + 1]
  988. data_ne = intensity_table[min_lat_index + 1][min_lon_index + 1]
  989. data_nw = intensity_table[min_lat_index + 1][min_lon_index]
  990. # perform bilinear interpolation on the four grid corners
  991. data_min = ((longitude_deg - min_lon) / SAMPLING_RES) * (data_se - data_sw) + data_sw
  992. data_max = ((longitude_deg - min_lon) / SAMPLING_RES) * (data_ne - data_nw) + data_nw
  993. intensity_gauss = ((latitude_deg - min_lat) / SAMPLING_RES) * (data_max - data_min) + data_min
  994. # calculate declination
  995. data_sw = declination_table[min_lat_index][min_lon_index]
  996. data_se = declination_table[min_lat_index][min_lon_index + 1]
  997. data_ne = declination_table[min_lat_index + 1][min_lon_index + 1]
  998. data_nw = declination_table[min_lat_index + 1][min_lon_index]
  999. # perform bilinear interpolation on the four grid corners
  1000. data_min = ((longitude_deg - min_lon) / SAMPLING_RES) * (data_se - data_sw) + data_sw
  1001. data_max = ((longitude_deg - min_lon) / SAMPLING_RES) * (data_ne - data_nw) + data_nw
  1002. declination_deg = ((latitude_deg - min_lat) / SAMPLING_RES) * (data_max - data_min) + data_min
  1003. # calculate inclination
  1004. data_sw = inclination_table[min_lat_index][min_lon_index]
  1005. data_se = inclination_table[min_lat_index][min_lon_index + 1]
  1006. data_ne = inclination_table[min_lat_index + 1][min_lon_index + 1]
  1007. data_nw = inclination_table[min_lat_index + 1][min_lon_index]
  1008. # perform bilinear interpolation on the four grid corners
  1009. data_min = ((longitude_deg - min_lon) / SAMPLING_RES) * (data_se - data_sw) + data_sw
  1010. data_max = ((longitude_deg - min_lon) / SAMPLING_RES) * (data_ne - data_nw) + data_nw
  1011. inclination_deg = ((latitude_deg - min_lat) / SAMPLING_RES) * (data_max - data_min) + data_min
  1012. return [declination_deg, inclination_deg, intensity_gauss]
  1013. earth_field = None
  1014. def expected_earth_field(GPS):
  1015. '''return expected magnetic field for a location'''
  1016. global earth_field
  1017. if earth_field is not None:
  1018. return earth_field
  1019. if hasattr(GPS,'fix_type'):
  1020. gps_status = GPS.fix_type
  1021. lat = GPS.lat*1.0e-7
  1022. lon = GPS.lon*1.0e-7
  1023. else:
  1024. gps_status = GPS.Status
  1025. lat = GPS.Lat
  1026. lon = GPS.Lng
  1027. if gps_status < 3:
  1028. return Vector3(0,0,0)
  1029. field_var = get_mag_field_ef(lat, lon)
  1030. mag_ef = Vector3(field_var[2]*1000.0, 0.0, 0.0)
  1031. R = Matrix3()
  1032. R.from_euler(0.0, -radians(field_var[1]), radians(field_var[0]))
  1033. mag_ef = R * mag_ef
  1034. earth_field = mag_ef
  1035. return earth_field
  1036. def expected_mag(GPS,ATT,roll_adjust=0,pitch_adjust=0,yaw_adjust=0):
  1037. '''return expected magnetic field for a location and attitude'''
  1038. global earth_field
  1039. expected_earth_field(GPS)
  1040. if earth_field is None:
  1041. return Vector3(0,0,0)
  1042. if hasattr(ATT,'roll'):
  1043. roll = degrees(ATT.roll)+roll_adjust
  1044. pitch = degrees(ATT.pitch)+pitch_adjust
  1045. yaw = degrees(ATT.yaw)+yaw_adjust
  1046. else:
  1047. roll = ATT.Roll+roll_adjust
  1048. pitch = ATT.Pitch+pitch_adjust
  1049. yaw = ATT.Yaw+yaw_adjust
  1050. rot = Matrix3()
  1051. rot.from_euler(radians(roll), radians(pitch), radians(yaw))
  1052. field = rot.transposed() * earth_field
  1053. return field
  1054. def earth_field_error(GPS,NKF2):
  1055. '''return vector error in earth field estimate'''
  1056. global earth_field
  1057. expected_earth_field(GPS)
  1058. if earth_field is None:
  1059. return Vector3(0,0,0)
  1060. ef = Vector3(NKF2.MN,NKF2.ME,NKF2.MD)
  1061. ret = ef - earth_field
  1062. return ret
  1063. def distance_home_df(GPS,ORGN):
  1064. '''distance from home origin'''
  1065. return distance_two(GPS_RAW, first_fix)
  1066. def airspeed_estimate(GLOBAL_POSITION_INT,WIND):
  1067. '''estimate airspeed'''
  1068. wind = WIND
  1069. gpi = GLOBAL_POSITION_INT
  1070. from pymavlink.rotmat import Vector3
  1071. import math
  1072. wind3d = Vector3(wind.speed*math.cos(math.radians(wind.direction)),
  1073. wind.speed*math.sin(math.radians(wind.direction)), 0)
  1074. ground = Vector3(gpi.vx*0.01, gpi.vy*0.01, 0)
  1075. airspeed = (ground + wind3d).length()
  1076. return airspeed
  1077. def distance_from(GPS_RAW1, lat, lon):
  1078. '''distance from a given location'''
  1079. if hasattr(GPS_RAW1, 'Lat'):
  1080. lat1 = radians(GPS_RAW1.Lat)
  1081. lon1 = radians(GPS_RAW1.Lng)
  1082. elif hasattr(GPS_RAW1, 'cog'):
  1083. lat1 = radians(GPS_RAW1.lat)*1.0e-7
  1084. lon1 = radians(GPS_RAW1.lon)*1.0e-7
  1085. else:
  1086. lat1 = radians(GPS_RAW1.lat)
  1087. lon1 = radians(GPS_RAW1.lon)
  1088. lat2 = radians(lat)
  1089. lon2 = radians(lon)
  1090. dLat = lat2 - lat1
  1091. dLon = lon2 - lon1
  1092. a = sin(0.5*dLat)**2 + sin(0.5*dLon)**2 * cos(lat1) * cos(lat2)
  1093. c = 2.0 * atan2(sqrt(a), sqrt(1.0-a))
  1094. ground_dist = 6371 * 1000 * c
  1095. return ground_dist
  1096. def distance_lat_lon(lat1, lon1, lat2, lon2):
  1097. '''distance between two points'''
  1098. dLat = radians(lat2) - radians(lat1)
  1099. dLon = radians(lon2) - radians(lon1)
  1100. a = sin(0.5*dLat)**2 + sin(0.5*dLon)**2 * cos(lat1) * cos(lat2)
  1101. c = 2.0 * atan2(sqrt(a), sqrt(1.0-a))
  1102. ground_dist = 6371 * 1000 * c
  1103. return ground_dist
  1104. def constrain(v, minv, maxv):
  1105. if v < minv:
  1106. v = minv
  1107. if v > maxv:
  1108. v = maxv
  1109. return v