mavutil.py 91 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003100410051006100710081009101010111012101310141015101610171018101910201021102210231024102510261027102810291030103110321033103410351036103710381039104010411042104310441045104610471048104910501051105210531054105510561057105810591060106110621063106410651066106710681069107010711072107310741075107610771078107910801081108210831084108510861087108810891090109110921093109410951096109710981099110011011102110311041105110611071108110911101111111211131114111511161117111811191120112111221123112411251126112711281129113011311132113311341135113611371138113911401141114211431144114511461147114811491150115111521153115411551156115711581159116011611162116311641165116611671168116911701171117211731174117511761177117811791180118111821183118411851186118711881189119011911192119311941195119611971198119912001201120212031204120512061207120812091210121112121213121412151216121712181219122012211222122312241225122612271228122912301231123212331234123512361237123812391240124112421243124412451246124712481249125012511252125312541255125612571258125912601261126212631264126512661267126812691270127112721273127412751276127712781279128012811282128312841285128612871288128912901291129212931294129512961297129812991300130113021303130413051306130713081309131013111312131313141315131613171318131913201321132213231324132513261327132813291330133113321333133413351336133713381339134013411342134313441345134613471348134913501351135213531354135513561357135813591360136113621363136413651366136713681369137013711372137313741375137613771378137913801381138213831384138513861387138813891390139113921393139413951396139713981399140014011402140314041405140614071408140914101411141214131414141514161417141814191420142114221423142414251426142714281429143014311432143314341435143614371438143914401441144214431444144514461447144814491450145114521453145414551456145714581459146014611462146314641465146614671468146914701471147214731474147514761477147814791480148114821483148414851486148714881489149014911492149314941495149614971498149915001501150215031504150515061507150815091510151115121513151415151516151715181519152015211522152315241525152615271528152915301531153215331534153515361537153815391540154115421543154415451546154715481549155015511552155315541555155615571558155915601561156215631564156515661567156815691570157115721573157415751576157715781579158015811582158315841585158615871588158915901591159215931594159515961597159815991600160116021603160416051606160716081609161016111612161316141615161616171618161916201621162216231624162516261627162816291630163116321633163416351636163716381639164016411642164316441645164616471648164916501651165216531654165516561657165816591660166116621663166416651666166716681669167016711672167316741675167616771678167916801681168216831684168516861687168816891690169116921693169416951696169716981699170017011702170317041705170617071708170917101711171217131714171517161717171817191720172117221723172417251726172717281729173017311732173317341735173617371738173917401741174217431744174517461747174817491750175117521753175417551756175717581759176017611762176317641765176617671768176917701771177217731774177517761777177817791780178117821783178417851786178717881789179017911792179317941795179617971798179918001801180218031804180518061807180818091810181118121813181418151816181718181819182018211822182318241825182618271828182918301831183218331834183518361837183818391840184118421843184418451846184718481849185018511852185318541855185618571858185918601861186218631864186518661867186818691870187118721873187418751876187718781879188018811882188318841885188618871888188918901891189218931894189518961897189818991900190119021903190419051906190719081909191019111912191319141915191619171918191919201921192219231924192519261927192819291930193119321933193419351936193719381939194019411942194319441945194619471948194919501951195219531954195519561957195819591960196119621963196419651966196719681969197019711972197319741975197619771978197919801981198219831984198519861987198819891990199119921993199419951996199719981999200020012002200320042005200620072008200920102011201220132014201520162017201820192020202120222023202420252026202720282029203020312032203320342035203620372038203920402041204220432044204520462047204820492050205120522053205420552056205720582059206020612062206320642065206620672068206920702071207220732074207520762077207820792080208120822083208420852086208720882089209020912092209320942095209620972098209921002101210221032104210521062107210821092110211121122113211421152116211721182119212021212122212321242125212621272128212921302131213221332134213521362137213821392140214121422143214421452146214721482149215021512152215321542155215621572158215921602161216221632164216521662167216821692170217121722173217421752176217721782179218021812182218321842185218621872188218921902191219221932194219521962197219821992200220122022203220422052206220722082209221022112212221322142215221622172218221922202221222222232224222522262227222822292230223122322233223422352236223722382239224022412242224322442245224622472248224922502251225222532254225522562257225822592260226122622263226422652266226722682269227022712272227322742275227622772278227922802281228222832284228522862287228822892290229122922293229422952296229722982299230023012302230323042305230623072308230923102311231223132314231523162317231823192320232123222323232423252326232723282329233023312332233323342335233623372338233923402341234223432344234523462347234823492350235123522353235423552356235723582359236023612362236323642365236623672368236923702371237223732374237523762377237823792380238123822383238423852386238723882389239023912392239323942395239623972398239924002401240224032404240524062407240824092410241124122413241424152416241724182419242024212422
  1. #!/usr/bin/env python
  2. '''
  3. mavlink python utility functions
  4. Copyright Andrew Tridgell 2011
  5. Released under GNU GPL version 3 or later
  6. '''
  7. from __future__ import print_function
  8. from builtins import object
  9. import socket, math, struct, time, os, fnmatch, array, sys, errno
  10. import select
  11. from pymavlink import mavexpression
  12. # adding these extra imports allows pymavlink to be used directly with pyinstaller
  13. # without having complex spec files. To allow for installs that don't have ardupilotmega
  14. # at all we avoid throwing an exception if it isn't installed
  15. try:
  16. import json
  17. from pymavlink.dialects.v10 import ardupilotmega
  18. except Exception:
  19. pass
  20. # maximum packet length for a single receive call - use the UDP limit
  21. UDP_MAX_PACKET_LEN = 65535
  22. # Store the MAVLink library for the currently-selected dialect
  23. # (set by set_dialect())
  24. mavlink = None
  25. # Store the mavlink file currently being operated on
  26. # (set by mavlink_connection())
  27. mavfile_global = None
  28. # If the caller hasn't specified a particular native/legacy version, use this
  29. default_native = False
  30. # link_id used for signing
  31. global_link_id = 0
  32. # Use a globally-set MAVLink dialect if one has been specified as an environment variable.
  33. if not 'MAVLINK_DIALECT' in os.environ:
  34. os.environ['MAVLINK_DIALECT'] = 'ardupilotmega'
  35. def mavlink10():
  36. '''return True if using MAVLink 1.0 or later'''
  37. return not 'MAVLINK09' in os.environ
  38. def mavlink20():
  39. '''return True if using MAVLink 2.0'''
  40. return 'MAVLINK20' in os.environ
  41. def evaluate_expression(expression, vars):
  42. '''evaluation an expression'''
  43. return mavexpression.evaluate_expression(expression, vars)
  44. def evaluate_condition(condition, vars):
  45. '''evaluation a conditional (boolean) statement'''
  46. if condition is None:
  47. return True
  48. v = evaluate_expression(condition, vars)
  49. if v is None:
  50. return False
  51. return v
  52. def u_ord(c):
  53. return ord(c) if sys.version_info.major < 3 else c
  54. class location(object):
  55. '''represent a GPS coordinate'''
  56. def __init__(self, lat, lng, alt=0, heading=0):
  57. self.lat = lat
  58. self.lng = lng
  59. self.alt = alt
  60. self.heading = heading
  61. def __str__(self):
  62. return "lat=%.6f,lon=%.6f,alt=%.1f" % (self.lat, self.lng, self.alt)
  63. def set_dialect(dialect):
  64. '''set the MAVLink dialect to work with.
  65. For example, set_dialect("ardupilotmega")
  66. '''
  67. global mavlink, current_dialect
  68. from .generator import mavparse
  69. if 'MAVLINK20' in os.environ:
  70. wire_protocol = mavparse.PROTOCOL_2_0
  71. modname = "pymavlink.dialects.v20." + dialect
  72. elif mavlink is None or mavlink.WIRE_PROTOCOL_VERSION == "1.0" or not 'MAVLINK09' in os.environ:
  73. wire_protocol = mavparse.PROTOCOL_1_0
  74. modname = "pymavlink.dialects.v10." + dialect
  75. else:
  76. wire_protocol = mavparse.PROTOCOL_0_9
  77. modname = "pymavlink.dialects.v09." + dialect
  78. try:
  79. mod = __import__(modname)
  80. except Exception:
  81. # auto-generate the dialect module
  82. from .generator.mavgen import mavgen_python_dialect
  83. mavgen_python_dialect(dialect, wire_protocol)
  84. mod = __import__(modname)
  85. components = modname.split('.')
  86. for comp in components[1:]:
  87. mod = getattr(mod, comp)
  88. current_dialect = dialect
  89. mavlink = mod
  90. # Set the default dialect. This is done here as it needs to be after the function declaration
  91. set_dialect(os.environ['MAVLINK_DIALECT'])
  92. class mavfile_state(object):
  93. '''state for a particular system id'''
  94. def __init__(self):
  95. self.messages = { 'MAV' : self }
  96. self.flightmode = "UNKNOWN"
  97. self.vehicle_type = "UNKNOWN"
  98. self.mav_type = mavlink.MAV_TYPE_FIXED_WING
  99. self.base_mode = 0
  100. self.armed = False # canonical arm state for the vehicle as a whole
  101. if float(mavlink.WIRE_PROTOCOL_VERSION) >= 1:
  102. self.messages['HOME'] = mavlink.MAVLink_gps_raw_int_message(0,0,0,0,0,0,0,0,0,0)
  103. mavlink.MAVLink_waypoint_message = mavlink.MAVLink_mission_item_message
  104. else:
  105. self.messages['HOME'] = mavlink.MAVLink_gps_raw_message(0,0,0,0,0,0,0,0,0)
  106. class param_state(object):
  107. '''state for a particular system id/component id pair'''
  108. def __init__(self):
  109. self.params = {}
  110. class mavfile(object):
  111. '''a generic mavlink port'''
  112. def __init__(self, fd, address, source_system=255, source_component=0, notimestamps=False, input=True, use_native=default_native):
  113. global mavfile_global
  114. if input:
  115. mavfile_global = self
  116. self.fd = fd
  117. self.sysid = 0
  118. self.param_sysid = (0,0)
  119. self.address = address
  120. self.timestamp = 0
  121. self.last_seq = {}
  122. self.mav_loss = 0
  123. self.mav_count = 0
  124. self.param_fetch_start = 0
  125. # state for each sysid
  126. self.sysid_state = {}
  127. self.sysid_state[self.sysid] = mavfile_state()
  128. # param state for each sysid/compid tuple
  129. self.param_state = {}
  130. self.param_state[self.param_sysid] = param_state()
  131. # status of param fetch, indexed by sysid,compid tuple
  132. self.source_system = source_system
  133. self.source_component = source_component
  134. self.first_byte = True
  135. self.robust_parsing = True
  136. self.mav = mavlink.MAVLink(self, srcSystem=self.source_system, srcComponent=self.source_component, use_native=use_native)
  137. self.mav.robust_parsing = self.robust_parsing
  138. self.logfile = None
  139. self.logfile_raw = None
  140. self.start_time = time.time()
  141. self.message_hooks = []
  142. self.idle_hooks = []
  143. self.uptime = 0.0
  144. self.notimestamps = notimestamps
  145. self._timestamp = None
  146. self.WIRE_PROTOCOL_VERSION = mavlink.WIRE_PROTOCOL_VERSION
  147. self.stop_on_EOF = False
  148. self.portdead = False
  149. @property
  150. def target_system(self):
  151. return self.sysid
  152. @property
  153. def target_component(self):
  154. return self.param_sysid[1]
  155. @target_system.setter
  156. def target_system(self, value):
  157. self.sysid = value
  158. if not self.sysid in self.sysid_state:
  159. self.sysid_state[self.sysid] = mavfile_state()
  160. if self.sysid != self.param_sysid[0]:
  161. self.param_sysid = (self.sysid, self.param_sysid[1])
  162. if not self.param_sysid in self.param_state:
  163. self.param_state[self.param_sysid] = param_state()
  164. @target_component.setter
  165. def target_component(self, value):
  166. if value != self.param_sysid[1]:
  167. self.param_sysid = (self.param_sysid[0], value)
  168. if not self.param_sysid in self.param_state:
  169. self.param_state[self.param_sysid] = param_state()
  170. @property
  171. def params(self):
  172. if self.param_sysid[1] == 0:
  173. eff_tuple = (self.sysid, 1)
  174. if eff_tuple in self.param_state:
  175. return getattr(self.param_state[eff_tuple],'params')
  176. return getattr(self.param_state[self.param_sysid],'params')
  177. @property
  178. def messages(self):
  179. return getattr(self.sysid_state[self.sysid],'messages')
  180. @property
  181. def flightmode(self):
  182. return getattr(self.sysid_state[self.sysid],'flightmode')
  183. @flightmode.setter
  184. def flightmode(self, value):
  185. setattr(self.sysid_state[self.sysid],'flightmode',value)
  186. @property
  187. def vehicle_type(self):
  188. return getattr(self.sysid_state[self.sysid],'vehicle_type')
  189. @vehicle_type.setter
  190. def vehicle_type(self, value):
  191. setattr(self.sysid_state[self.sysid],'vehicle_type',value)
  192. @property
  193. def mav_type(self):
  194. return getattr(self.sysid_state[self.sysid],'mav_type')
  195. @mav_type.setter
  196. def mav_type(self, value):
  197. setattr(self.sysid_state[self.sysid],'mav_type',value)
  198. @property
  199. def base_mode(self):
  200. return getattr(self.sysid_state[self.sysid],'base_mode')
  201. @base_mode.setter
  202. def base_mode(self, value):
  203. setattr(self.sysid_state[self.sysid],'base_mode',value)
  204. def auto_mavlink_version(self, buf):
  205. '''auto-switch mavlink protocol version'''
  206. global mavlink
  207. if len(buf) == 0:
  208. return
  209. try:
  210. magic = ord(buf[0])
  211. except:
  212. magic = buf[0]
  213. if not magic in [ 85, 254, 253 ]:
  214. return
  215. self.first_byte = False
  216. if self.WIRE_PROTOCOL_VERSION == "0.9" and magic == 254:
  217. self.WIRE_PROTOCOL_VERSION = "1.0"
  218. set_dialect(current_dialect)
  219. elif self.WIRE_PROTOCOL_VERSION == "1.0" and magic == 85:
  220. self.WIRE_PROTOCOL_VERSION = "0.9"
  221. os.environ['MAVLINK09'] = '1'
  222. set_dialect(current_dialect)
  223. elif self.WIRE_PROTOCOL_VERSION != "2.0" and magic == 253:
  224. self.WIRE_PROTOCOL_VERSION = "2.0"
  225. os.environ['MAVLINK20'] = '1'
  226. set_dialect(current_dialect)
  227. else:
  228. return
  229. # switch protocol
  230. (callback, callback_args, callback_kwargs) = (self.mav.callback,
  231. self.mav.callback_args,
  232. self.mav.callback_kwargs)
  233. self.mav = mavlink.MAVLink(self, srcSystem=self.source_system, srcComponent=self.source_component)
  234. self.mav.robust_parsing = self.robust_parsing
  235. self.WIRE_PROTOCOL_VERSION = mavlink.WIRE_PROTOCOL_VERSION
  236. (self.mav.callback, self.mav.callback_args, self.mav.callback_kwargs) = (callback,
  237. callback_args,
  238. callback_kwargs)
  239. def recv(self, n=None):
  240. '''default recv method'''
  241. raise RuntimeError('no recv() method supplied')
  242. def close(self, n=None):
  243. '''default close method'''
  244. raise RuntimeError('no close() method supplied')
  245. def write(self, buf):
  246. '''default write method'''
  247. raise RuntimeError('no write() method supplied')
  248. def select(self, timeout):
  249. '''wait for up to timeout seconds for more data'''
  250. if self.fd is None:
  251. time.sleep(min(timeout,0.5))
  252. return True
  253. try:
  254. (rin, win, xin) = select.select([self.fd], [], [], timeout)
  255. except select.error:
  256. return False
  257. return len(rin) == 1
  258. def pre_message(self):
  259. '''default pre message call'''
  260. return
  261. def set_rtscts(self, enable):
  262. '''enable/disable RTS/CTS if applicable'''
  263. return
  264. def probably_vehicle_heartbeat(self, msg):
  265. if msg.get_srcComponent() == mavlink.MAV_COMP_ID_GIMBAL:
  266. return False
  267. if msg.type in (mavlink.MAV_TYPE_GCS,
  268. mavlink.MAV_TYPE_GIMBAL,
  269. mavlink.MAV_TYPE_ADSB,
  270. mavlink.MAV_TYPE_ONBOARD_CONTROLLER):
  271. return False
  272. return True
  273. def post_message(self, msg):
  274. '''default post message call'''
  275. if '_posted' in msg.__dict__:
  276. return
  277. msg._posted = True
  278. msg._timestamp = time.time()
  279. type = msg.get_type()
  280. if 'usec' in msg.__dict__:
  281. self.uptime = msg.usec * 1.0e-6
  282. if 'time_boot_ms' in msg.__dict__:
  283. self.uptime = msg.time_boot_ms * 1.0e-3
  284. if self._timestamp is not None:
  285. if self.notimestamps:
  286. msg._timestamp = self.uptime
  287. else:
  288. msg._timestamp = self._timestamp
  289. src_system = msg.get_srcSystem()
  290. src_component = msg.get_srcComponent()
  291. src_tuple = (src_system, src_component)
  292. radio_tuple = (ord('3'), ord('D'))
  293. if not src_system in self.sysid_state:
  294. # we've seen a new system
  295. self.sysid_state[src_system] = mavfile_state()
  296. self.sysid_state[src_system].messages[type] = msg
  297. if src_tuple == radio_tuple:
  298. # as a special case radio msgs are added for all sysids
  299. for s in self.sysid_state.keys():
  300. self.sysid_state[s].messages[type] = msg
  301. if not (src_tuple == radio_tuple or msg.get_type() == 'BAD_DATA'):
  302. if not src_tuple in self.last_seq:
  303. last_seq = -1
  304. else:
  305. last_seq = self.last_seq[src_tuple]
  306. seq = (last_seq+1) % 256
  307. seq2 = msg.get_seq()
  308. if seq != seq2 and last_seq != -1:
  309. diff = (seq2 - seq) % 256
  310. self.mav_loss += diff
  311. #print("lost %u seq=%u seq2=%u last_seq=%u src_tupe=%s %s" % (diff, seq, seq2, last_seq, str(src_tuple), msg.get_type()))
  312. self.last_seq[src_tuple] = seq2
  313. self.mav_count += 1
  314. self.timestamp = msg._timestamp
  315. if type == 'HEARTBEAT' and self.probably_vehicle_heartbeat(msg):
  316. if self.sysid == 0:
  317. # lock onto id tuple of first vehicle heartbeat
  318. self.sysid = src_system
  319. if float(mavlink.WIRE_PROTOCOL_VERSION) >= 1:
  320. self.flightmode = mode_string_v10(msg)
  321. self.mav_type = msg.type
  322. self.base_mode = msg.base_mode
  323. self.sysid_state[self.sysid].armed = (msg.base_mode & mavlink.MAV_MODE_FLAG_SAFETY_ARMED)
  324. elif type == 'PARAM_VALUE':
  325. if not src_tuple in self.param_state:
  326. self.param_state[src_tuple] = param_state()
  327. self.param_state[src_tuple].params[msg.param_id] = msg.param_value
  328. elif type == 'SYS_STATUS' and mavlink.WIRE_PROTOCOL_VERSION == '0.9':
  329. self.flightmode = mode_string_v09(msg)
  330. elif type == 'GPS_RAW':
  331. if self.sysid_state[src_system].messages['HOME'].fix_type < 2:
  332. self.sysid_state[src_system].messages['HOME'] = msg
  333. elif type == 'GPS_RAW_INT':
  334. if self.sysid_state[src_system].messages['HOME'].fix_type < 3:
  335. self.sysid_state[src_system].messages['HOME'] = msg
  336. for hook in self.message_hooks:
  337. hook(self, msg)
  338. if (msg.get_signed() and
  339. self.mav.signing.link_id == 0 and
  340. msg.get_link_id() != 0 and
  341. self.target_system == msg.get_srcSystem() and
  342. self.target_component == msg.get_srcComponent()):
  343. # change to link_id from incoming packet
  344. self.mav.signing.link_id = msg.get_link_id()
  345. def packet_loss(self):
  346. '''packet loss as a percentage'''
  347. if self.mav_count == 0:
  348. return 0
  349. return (100.0*self.mav_loss)/(self.mav_count+self.mav_loss)
  350. def recv_msg(self):
  351. '''message receive routine'''
  352. self.pre_message()
  353. while True:
  354. n = self.mav.bytes_needed()
  355. s = self.recv(n)
  356. numnew = len(s)
  357. if numnew != 0:
  358. if self.logfile_raw:
  359. self.logfile_raw.write(str(s))
  360. if self.first_byte:
  361. self.auto_mavlink_version(s)
  362. # We always call parse_char even if the new string is empty, because the existing message buf might already have some valid packet
  363. # we can extract
  364. msg = self.mav.parse_char(s)
  365. if msg:
  366. if self.logfile and msg.get_type() != 'BAD_DATA' :
  367. usec = int(time.time() * 1.0e6) & ~3
  368. self.logfile.write(str(struct.pack('>Q', usec) + msg.get_msgbuf()))
  369. self.post_message(msg)
  370. return msg
  371. else:
  372. # if we failed to parse any messages _and_ no new bytes arrived, return immediately so the client has the option to
  373. # timeout
  374. if numnew == 0:
  375. return None
  376. def recv_match(self, condition=None, type=None, blocking=False, timeout=None):
  377. '''recv the next MAVLink message that matches the given condition
  378. type can be a string or a list of strings'''
  379. if type is not None and not isinstance(type, list) and not isinstance(type, set):
  380. type = [type]
  381. start_time = time.time()
  382. while True:
  383. if timeout is not None:
  384. now = time.time()
  385. if now < start_time:
  386. start_time = now # If an external process rolls back system time, we should not spin forever.
  387. if start_time + timeout < time.time():
  388. return None
  389. m = self.recv_msg()
  390. if m is None:
  391. if blocking:
  392. for hook in self.idle_hooks:
  393. hook(self)
  394. if timeout is None:
  395. self.select(0.05)
  396. else:
  397. self.select(timeout/2)
  398. continue
  399. return None
  400. if type is not None and not m.get_type() in type:
  401. continue
  402. if not evaluate_condition(condition, self.messages):
  403. continue
  404. return m
  405. def check_condition(self, condition):
  406. '''check if a condition is true'''
  407. return evaluate_condition(condition, self.messages)
  408. def mavlink10(self):
  409. '''return True if using MAVLink 1.0 or later'''
  410. return float(self.WIRE_PROTOCOL_VERSION) >= 1
  411. def mavlink20(self):
  412. '''return True if using MAVLink 2.0 or later'''
  413. return float(self.WIRE_PROTOCOL_VERSION) >= 2
  414. def setup_logfile(self, logfile, mode='w'):
  415. '''start logging to the given logfile, with timestamps'''
  416. self.logfile = open(logfile, mode=mode)
  417. def setup_logfile_raw(self, logfile, mode='w'):
  418. '''start logging raw bytes to the given logfile, without timestamps'''
  419. self.logfile_raw = open(logfile, mode=mode)
  420. def wait_heartbeat(self, blocking=True, timeout=None):
  421. '''wait for a heartbeat so we know the target system IDs'''
  422. return self.recv_match(type='HEARTBEAT', blocking=blocking, timeout=timeout)
  423. def param_fetch_all(self):
  424. '''initiate fetch of all parameters'''
  425. if time.time() - self.param_fetch_start < 2.0:
  426. # don't fetch too often
  427. return
  428. self.param_fetch_start = time.time()
  429. self.mav.param_request_list_send(self.target_system, self.target_component)
  430. def param_fetch_one(self, name):
  431. '''initiate fetch of one parameter'''
  432. try:
  433. idx = int(name)
  434. self.mav.param_request_read_send(self.target_system, self.target_component, b"", idx)
  435. except Exception:
  436. if sys.version_info.major >= 3 and not isinstance(name, bytes):
  437. name = bytes(name,'ascii')
  438. self.mav.param_request_read_send(self.target_system, self.target_component, name, -1)
  439. def time_since(self, mtype):
  440. '''return the time since the last message of type mtype was received'''
  441. if not mtype in self.messages:
  442. return time.time() - self.start_time
  443. return time.time() - self.messages[mtype]._timestamp
  444. def param_set_send(self, parm_name, parm_value, parm_type=None):
  445. '''wrapper for parameter set'''
  446. if self.mavlink10():
  447. if parm_type is None:
  448. parm_type = mavlink.MAVLINK_TYPE_FLOAT
  449. self.mav.param_set_send(self.target_system, self.target_component,
  450. parm_name.encode('utf8'), parm_value, parm_type)
  451. else:
  452. self.mav.param_set_send(self.target_system, self.target_component,
  453. parm_name.encode('utf8'), parm_value)
  454. def waypoint_request_list_send(self):
  455. '''wrapper for waypoint_request_list_send'''
  456. if self.mavlink10():
  457. self.mav.mission_request_list_send(self.target_system, self.target_component)
  458. else:
  459. self.mav.waypoint_request_list_send(self.target_system, self.target_component)
  460. def waypoint_clear_all_send(self):
  461. '''wrapper for waypoint_clear_all_send'''
  462. if self.mavlink10():
  463. self.mav.mission_clear_all_send(self.target_system, self.target_component)
  464. else:
  465. self.mav.waypoint_clear_all_send(self.target_system, self.target_component)
  466. def waypoint_request_send(self, seq):
  467. '''wrapper for waypoint_request_send'''
  468. if self.mavlink10():
  469. self.mav.mission_request_send(self.target_system, self.target_component, seq)
  470. else:
  471. self.mav.waypoint_request_send(self.target_system, self.target_component, seq)
  472. def waypoint_set_current_send(self, seq):
  473. '''wrapper for waypoint_set_current_send'''
  474. if self.mavlink10():
  475. self.mav.mission_set_current_send(self.target_system, self.target_component, seq)
  476. else:
  477. self.mav.waypoint_set_current_send(self.target_system, self.target_component, seq)
  478. def waypoint_current(self):
  479. '''return current waypoint'''
  480. if self.mavlink10():
  481. m = self.recv_match(type='MISSION_CURRENT', blocking=True)
  482. else:
  483. m = self.recv_match(type='WAYPOINT_CURRENT', blocking=True)
  484. return m.seq
  485. def waypoint_count_send(self, seq):
  486. '''wrapper for waypoint_count_send'''
  487. if self.mavlink10():
  488. self.mav.mission_count_send(self.target_system, self.target_component, seq)
  489. else:
  490. self.mav.waypoint_count_send(self.target_system, self.target_component, seq)
  491. def set_mode_flag(self, flag, enable):
  492. '''
  493. Enables/ disables MAV_MODE_FLAG
  494. @param flag The mode flag,
  495. see MAV_MODE_FLAG enum
  496. @param enable Enable the flag, (True/False)
  497. '''
  498. if self.mavlink10():
  499. mode = self.base_mode
  500. if enable:
  501. mode = mode | flag
  502. elif not enable:
  503. mode = mode & ~flag
  504. self.mav.command_long_send(self.target_system, self.target_component,
  505. mavlink.MAV_CMD_DO_SET_MODE, 0,
  506. mode,
  507. 0, 0, 0, 0, 0, 0)
  508. else:
  509. print("Set mode flag not supported")
  510. def set_mode_auto(self):
  511. '''enter auto mode'''
  512. if self.mavlink10():
  513. self.mav.command_long_send(self.target_system, self.target_component,
  514. mavlink.MAV_CMD_MISSION_START, 0, 0, 0, 0, 0, 0, 0, 0)
  515. else:
  516. MAV_ACTION_SET_AUTO = 13
  517. self.mav.action_send(self.target_system, self.target_component, MAV_ACTION_SET_AUTO)
  518. def mode_mapping(self):
  519. '''return dictionary mapping mode names to numbers, or None if unknown'''
  520. mav_type = self.field('HEARTBEAT', 'type', self.mav_type)
  521. mav_autopilot = self.field('HEARTBEAT', 'autopilot', None)
  522. if mav_autopilot == mavlink.MAV_AUTOPILOT_PX4:
  523. return px4_map
  524. if mav_type is None:
  525. return None
  526. map = None
  527. if mav_type in [mavlink.MAV_TYPE_QUADROTOR,
  528. mavlink.MAV_TYPE_HELICOPTER,
  529. mavlink.MAV_TYPE_HEXAROTOR,
  530. mavlink.MAV_TYPE_OCTOROTOR,
  531. mavlink.MAV_TYPE_DODECAROTOR,
  532. mavlink.MAV_TYPE_COAXIAL,
  533. mavlink.MAV_TYPE_TRICOPTER]:
  534. map = mode_mapping_acm
  535. if mav_type == mavlink.MAV_TYPE_FIXED_WING:
  536. map = mode_mapping_apm
  537. if mav_type == mavlink.MAV_TYPE_GROUND_ROVER:
  538. map = mode_mapping_rover
  539. if mav_type == mavlink.MAV_TYPE_SURFACE_BOAT:
  540. map = mode_mapping_rover # for the time being
  541. if mav_type == mavlink.MAV_TYPE_ANTENNA_TRACKER:
  542. map = mode_mapping_tracker
  543. if mav_type == mavlink.MAV_TYPE_SUBMARINE:
  544. map = mode_mapping_sub
  545. if map is None:
  546. return None
  547. inv_map = dict((a, b) for (b, a) in map.items())
  548. return inv_map
  549. def set_mode_apm(self, mode, custom_mode = 0, custom_sub_mode = 0):
  550. '''enter arbitrary mode'''
  551. if isinstance(mode, str):
  552. mode_map = self.mode_mapping()
  553. if mode_map is None or mode not in mode_map:
  554. print("Unknown mode '%s'" % mode)
  555. return
  556. mode = mode_map[mode]
  557. # set mode by integer mode number for ArduPilot
  558. self.mav.set_mode_send(self.target_system,
  559. mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED,
  560. mode)
  561. def set_mode_px4(self, mode, custom_mode, custom_sub_mode):
  562. '''enter arbitrary mode'''
  563. if isinstance(mode, str):
  564. mode_map = self.mode_mapping()
  565. if mode_map is None or mode not in mode_map:
  566. print("Unknown mode '%s'" % mode)
  567. return
  568. # PX4 uses two fields to define modes
  569. mode, custom_mode, custom_sub_mode = px4_map[mode]
  570. self.mav.command_long_send(self.target_system, self.target_component,
  571. mavlink.MAV_CMD_DO_SET_MODE, 0, mode, custom_mode, custom_sub_mode, 0, 0, 0, 0)
  572. def set_mode(self, mode, custom_mode = 0, custom_sub_mode = 0):
  573. '''set arbitrary flight mode'''
  574. mav_autopilot = self.field('HEARTBEAT', 'autopilot', None)
  575. if mav_autopilot == mavlink.MAV_AUTOPILOT_PX4:
  576. self.set_mode_px4(mode, custom_mode, custom_sub_mode)
  577. else:
  578. self.set_mode_apm(mode)
  579. def set_mode_rtl(self):
  580. '''enter RTL mode'''
  581. if self.mavlink10():
  582. self.mav.command_long_send(self.target_system, self.target_component,
  583. mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0, 0, 0, 0, 0, 0)
  584. else:
  585. MAV_ACTION_RETURN = 3
  586. self.mav.action_send(self.target_system, self.target_component, MAV_ACTION_RETURN)
  587. def set_mode_manual(self):
  588. '''enter MANUAL mode'''
  589. if self.mavlink10():
  590. self.mav.command_long_send(self.target_system, self.target_component,
  591. mavlink.MAV_CMD_DO_SET_MODE, 0,
  592. mavlink.MAV_MODE_MANUAL_ARMED,
  593. 0, 0, 0, 0, 0, 0)
  594. else:
  595. MAV_ACTION_SET_MANUAL = 12
  596. self.mav.action_send(self.target_system, self.target_component, MAV_ACTION_SET_MANUAL)
  597. def set_mode_fbwa(self):
  598. '''enter FBWA mode'''
  599. if self.mavlink10():
  600. self.mav.command_long_send(self.target_system, self.target_component,
  601. mavlink.MAV_CMD_DO_SET_MODE, 0,
  602. mavlink.MAV_MODE_STABILIZE_ARMED,
  603. 0, 0, 0, 0, 0, 0)
  604. else:
  605. print("Forcing FBWA not supported")
  606. def set_mode_loiter(self):
  607. '''enter LOITER mode'''
  608. if self.mavlink10():
  609. self.mav.command_long_send(self.target_system, self.target_component,
  610. mavlink.MAV_CMD_NAV_LOITER_UNLIM, 0, 0, 0, 0, 0, 0, 0, 0)
  611. else:
  612. MAV_ACTION_LOITER = 27
  613. self.mav.action_send(self.target_system, self.target_component, MAV_ACTION_LOITER)
  614. def set_servo(self, channel, pwm):
  615. '''set a servo value'''
  616. self.mav.command_long_send(self.target_system, self.target_component,
  617. mavlink.MAV_CMD_DO_SET_SERVO, 0,
  618. channel, pwm,
  619. 0, 0, 0, 0, 0)
  620. def set_relay(self, relay_pin=0, state=True):
  621. '''Set relay_pin to value of state'''
  622. if self.mavlink10():
  623. self.mav.command_long_send(
  624. self.target_system, # target_system
  625. self.target_component, # target_component
  626. mavlink.MAV_CMD_DO_SET_RELAY, # command
  627. 0, # Confirmation
  628. relay_pin, # Relay Number
  629. int(state), # state (1 to indicate arm)
  630. 0, # param3 (all other params meaningless)
  631. 0, # param4
  632. 0, # param5
  633. 0, # param6
  634. 0) # param7
  635. else:
  636. print("Setting relays not supported.")
  637. def calibrate_level(self):
  638. '''calibrate accels (1D version)'''
  639. self.mav.command_long_send(self.target_system, self.target_component,
  640. mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, 0,
  641. 1, 1, 0, 0, 0, 0, 0)
  642. def calibrate_pressure(self):
  643. '''calibrate pressure'''
  644. if self.mavlink10():
  645. self.mav.command_long_send(self.target_system, self.target_component,
  646. mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, 0,
  647. 0, 0, 1, 0, 0, 0, 0)
  648. else:
  649. MAV_ACTION_CALIBRATE_PRESSURE = 20
  650. self.mav.action_send(self.target_system, self.target_component, MAV_ACTION_CALIBRATE_PRESSURE)
  651. def reboot_autopilot(self, hold_in_bootloader=False):
  652. '''reboot the autopilot'''
  653. if self.mavlink10():
  654. if hold_in_bootloader:
  655. param1 = 3
  656. else:
  657. param1 = 1
  658. self.mav.command_long_send(self.target_system, self.target_component,
  659. mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 0,
  660. param1, 0, 0, 0, 0, 0, 0)
  661. # send an old style reboot immediately afterwards in case it is an older firmware
  662. # that doesn't understand the new convention
  663. self.mav.command_long_send(self.target_system, self.target_component,
  664. mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 0,
  665. 1, 0, 0, 0, 0, 0, 0)
  666. def wait_gps_fix(self):
  667. self.recv_match(type='VFR_HUD', blocking=True)
  668. if self.mavlink10():
  669. self.recv_match(type='GPS_RAW_INT', blocking=True,
  670. condition='GPS_RAW_INT.fix_type>=3 and GPS_RAW_INT.lat != 0')
  671. else:
  672. self.recv_match(type='GPS_RAW', blocking=True,
  673. condition='GPS_RAW.fix_type>=2 and GPS_RAW.lat != 0')
  674. def location(self, relative_alt=False):
  675. '''return current location'''
  676. self.wait_gps_fix()
  677. # wait for another VFR_HUD, to ensure we have correct altitude
  678. self.recv_match(type='VFR_HUD', blocking=True)
  679. self.recv_match(type='GLOBAL_POSITION_INT', blocking=True)
  680. if relative_alt:
  681. alt = self.messages['GLOBAL_POSITION_INT'].relative_alt*0.001
  682. else:
  683. alt = self.messages['VFR_HUD'].alt
  684. return location(self.messages['GPS_RAW_INT'].lat*1.0e-7,
  685. self.messages['GPS_RAW_INT'].lon*1.0e-7,
  686. alt,
  687. self.messages['VFR_HUD'].heading)
  688. def arducopter_arm(self):
  689. '''arm motors (arducopter only)'''
  690. if self.mavlink10():
  691. self.mav.command_long_send(
  692. self.target_system, # target_system
  693. self.target_component,
  694. mavlink.MAV_CMD_COMPONENT_ARM_DISARM, # command
  695. 0, # confirmation
  696. 1, # param1 (1 to indicate arm)
  697. 0, # param2 (all other params meaningless)
  698. 0, # param3
  699. 0, # param4
  700. 0, # param5
  701. 0, # param6
  702. 0) # param7
  703. def arducopter_disarm(self):
  704. '''calibrate pressure'''
  705. if self.mavlink10():
  706. self.mav.command_long_send(
  707. self.target_system, # target_system
  708. self.target_component,
  709. mavlink.MAV_CMD_COMPONENT_ARM_DISARM, # command
  710. 0, # confirmation
  711. 0, # param1 (0 to indicate disarm)
  712. 0, # param2 (all other params meaningless)
  713. 0, # param3
  714. 0, # param4
  715. 0, # param5
  716. 0, # param6
  717. 0) # param7
  718. def motors_armed(self):
  719. '''return true if motors armed'''
  720. return self.sysid_state[self.sysid].armed
  721. def motors_armed_wait(self):
  722. '''wait for motors to be armed'''
  723. while True:
  724. m = self.wait_heartbeat()
  725. if self.motors_armed():
  726. return
  727. def motors_disarmed_wait(self):
  728. '''wait for motors to be disarmed'''
  729. while True:
  730. m = self.wait_heartbeat()
  731. if not self.motors_armed():
  732. return
  733. def field(self, type, field, default=None):
  734. '''convenient function for returning an arbitrary MAVLink
  735. field with a default'''
  736. if not type in self.messages:
  737. return default
  738. return getattr(self.messages[type], field, default)
  739. def param(self, name, default=None):
  740. '''convenient function for returning an arbitrary MAVLink
  741. parameter with a default'''
  742. if not name in self.params:
  743. return default
  744. return self.params[name]
  745. def setup_signing(self, secret_key, sign_outgoing=True, allow_unsigned_callback=None, initial_timestamp=None, link_id=None):
  746. '''setup for MAVLink2 signing'''
  747. self.mav.signing.secret_key = secret_key
  748. self.mav.signing.sign_outgoing = sign_outgoing
  749. self.mav.signing.allow_unsigned_callback = allow_unsigned_callback
  750. if link_id is None:
  751. # auto-increment the link_id for each link
  752. global global_link_id
  753. link_id = global_link_id
  754. global_link_id = min(global_link_id + 1, 255)
  755. self.mav.signing.link_id = link_id
  756. if initial_timestamp is None:
  757. # timestamp is time since 1/1/2015
  758. epoch_offset = 1420070400
  759. now = max(time.time(), epoch_offset)
  760. initial_timestamp = now - epoch_offset
  761. initial_timestamp = int(initial_timestamp * 100 * 1000)
  762. # initial_timestamp is in 10usec units
  763. self.mav.signing.timestamp = initial_timestamp
  764. def disable_signing(self):
  765. '''disable MAVLink2 signing'''
  766. self.mav.signing.secret_key = None
  767. self.mav.signing.sign_outgoing = False
  768. self.mav.signing.allow_unsigned_callback = None
  769. self.mav.signing.link_id = 0
  770. self.mav.signing.timestamp = 0
  771. def set_close_on_exec(fd):
  772. '''set the clone on exec flag on a file descriptor. Ignore exceptions'''
  773. try:
  774. import fcntl
  775. flags = fcntl.fcntl(fd, fcntl.F_GETFD)
  776. flags |= fcntl.FD_CLOEXEC
  777. fcntl.fcntl(fd, fcntl.F_SETFD, flags)
  778. except Exception:
  779. pass
  780. class FakeSerial():
  781. def __init__(self):
  782. pass
  783. def read(self, len):
  784. return ""
  785. def write(self, buf):
  786. raise Exception("write always fails")
  787. def inWaiting(self):
  788. return 0
  789. def close(self):
  790. pass
  791. class mavserial(mavfile):
  792. '''a serial mavlink port'''
  793. def __init__(self, device, baud=115200, autoreconnect=False, source_system=255, source_component=0, use_native=default_native, force_connected=False):
  794. import serial
  795. if ',' in device and not os.path.exists(device):
  796. device, baud = device.split(',')
  797. self.baud = baud
  798. self.device = device
  799. self.autoreconnect = autoreconnect
  800. self.force_connected = force_connected
  801. # we rather strangely set the baudrate initially to 1200, then change to the desired
  802. # baudrate. This works around a kernel bug on some Linux kernels where the baudrate
  803. # is not set correctly
  804. try:
  805. self.port = serial.Serial(self.device, 1200, timeout=0,
  806. dsrdtr=False, rtscts=False, xonxoff=False)
  807. except serial.SerialException as e:
  808. if not force_connected:
  809. raise e
  810. self.port = FakeSerial()
  811. try:
  812. fd = self.port.fileno()
  813. set_close_on_exec(fd)
  814. except Exception:
  815. fd = None
  816. self.set_baudrate(self.baud)
  817. mavfile.__init__(self, fd, device, source_system=source_system, source_component=source_component, use_native=use_native)
  818. self.rtscts = False
  819. def set_rtscts(self, enable):
  820. '''enable/disable RTS/CTS if applicable'''
  821. try:
  822. self.port.setRtsCts(enable)
  823. except Exception:
  824. self.port.rtscts = enable
  825. self.rtscts = enable
  826. def set_baudrate(self, baudrate):
  827. '''set baudrate'''
  828. try:
  829. self.port.setBaudrate(baudrate)
  830. except Exception:
  831. # for pySerial 3.0, which doesn't have setBaudrate()
  832. self.port.baudrate = baudrate
  833. def close(self):
  834. self.port.close()
  835. def recv(self,n=None):
  836. if n is None:
  837. n = self.mav.bytes_needed()
  838. if self.fd is None:
  839. waiting = self.port.inWaiting()
  840. if waiting < n:
  841. n = waiting
  842. ret = self.port.read(n)
  843. return ret
  844. def write(self, buf):
  845. try:
  846. return self.port.write(bytes(buf))
  847. except Exception:
  848. if not self.portdead:
  849. print("Device %s is dead" % self.device)
  850. self.portdead = True
  851. if self.autoreconnect:
  852. self.reset()
  853. return -1
  854. def reset(self):
  855. import serial
  856. try:
  857. try:
  858. newport = serial.Serial(self.device, self.baud, timeout=0,
  859. dsrdtr=False, rtscts=False, xonxoff=False)
  860. except serial.SerialException as e:
  861. if not self.force_connected:
  862. raise e
  863. newport = FakeSerial()
  864. return False
  865. self.port.close()
  866. self.port = newport
  867. print("Device %s reopened OK" % self.device)
  868. self.portdead = False
  869. try:
  870. self.fd = self.port.fileno()
  871. except Exception:
  872. self.fd = None
  873. self.set_baudrate(self.baud)
  874. if self.rtscts:
  875. self.set_rtscts(self.rtscts)
  876. return True
  877. except Exception:
  878. return False
  879. class mavudp(mavfile):
  880. '''a UDP mavlink socket'''
  881. def __init__(self, device, input=True, broadcast=False, source_system=255, source_component=0, use_native=default_native):
  882. a = device.split(':')
  883. if len(a) != 2:
  884. print("UDP ports must be specified as host:port")
  885. sys.exit(1)
  886. self.port = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
  887. self.udp_server = input
  888. self.broadcast = False
  889. if input:
  890. self.port.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1)
  891. self.port.bind((a[0], int(a[1])))
  892. else:
  893. self.destination_addr = (a[0], int(a[1]))
  894. if broadcast:
  895. self.port.setsockopt(socket.SOL_SOCKET, socket.SO_BROADCAST, 1)
  896. self.broadcast = True
  897. set_close_on_exec(self.port.fileno())
  898. self.port.setblocking(0)
  899. self.last_address = None
  900. self.resolved_destination_addr = None
  901. mavfile.__init__(self, self.port.fileno(), device, source_system=source_system, source_component=source_component, input=input, use_native=use_native)
  902. def close(self):
  903. self.port.close()
  904. def recv(self,n=None):
  905. try:
  906. data, new_addr = self.port.recvfrom(UDP_MAX_PACKET_LEN)
  907. except socket.error as e:
  908. if e.errno in [ errno.EAGAIN, errno.EWOULDBLOCK, errno.ECONNREFUSED ]:
  909. return ""
  910. raise
  911. if self.udp_server or self.broadcast:
  912. self.last_address = new_addr
  913. return data
  914. def write(self, buf):
  915. try:
  916. if self.udp_server:
  917. if self.last_address:
  918. self.port.sendto(buf, self.last_address)
  919. else:
  920. if self.last_address and self.broadcast:
  921. self.destination_addr = self.last_address
  922. self.broadcast = False
  923. self.port.connect(self.destination_addr)
  924. # turn a (possible) hostname into an IP address to
  925. # avoid resolving the hostname for every packet sent:
  926. if self.destination_addr[0] != self.resolved_destination_addr:
  927. self.resolved_destination_addr = self.destination_addr[0]
  928. self.destination_addr = (socket.gethostbyname(self.destination_addr[0]), self.destination_addr[1])
  929. self.port.sendto(buf, self.destination_addr)
  930. except socket.error:
  931. pass
  932. def recv_msg(self):
  933. '''message receive routine for UDP link'''
  934. self.pre_message()
  935. s = self.recv()
  936. if len(s) > 0:
  937. if self.first_byte:
  938. self.auto_mavlink_version(s)
  939. m = self.mav.parse_char(s)
  940. if m is not None:
  941. self.post_message(m)
  942. return m
  943. class mavmcast(mavfile):
  944. '''a UDP multicast mavlink socket'''
  945. def __init__(self, device, broadcast=False, source_system=255, source_component=0, use_native=default_native):
  946. a = device.split(':')
  947. mcast_ip = "239.255.145.50"
  948. mcast_port = 14550
  949. if len(a) == 1 and len(a[0]) > 0:
  950. mcast_port = int(a[0])
  951. elif len(a) > 1:
  952. mcast_ip = a[0]
  953. mcast_port = int(a[1])
  954. # first the receiving socket. We use separate sending and receiving
  955. # sockets so we can use the port number of the sending socket to detect
  956. # packets from ourselves
  957. self.port = socket.socket(socket.AF_INET, socket.SOCK_DGRAM, socket.IPPROTO_UDP)
  958. self.port.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1)
  959. self.port.bind((mcast_ip, mcast_port))
  960. mreq = struct.pack("4sl", socket.inet_aton(mcast_ip), socket.INADDR_ANY)
  961. self.port.setsockopt(socket.IPPROTO_IP, socket.IP_ADD_MEMBERSHIP, mreq)
  962. self.port.setblocking(0)
  963. set_close_on_exec(self.port.fileno())
  964. # now the sending socket
  965. self.port_out = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
  966. self.port_out.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1)
  967. self.port_out.setblocking(0)
  968. self.port_out.connect((mcast_ip, mcast_port))
  969. set_close_on_exec(self.port_out.fileno())
  970. self.myport = None
  971. mavfile.__init__(self, self.port.fileno(), device,
  972. source_system=source_system, source_component=source_component,
  973. input=False, use_native=use_native)
  974. def close(self):
  975. self.port.close()
  976. self.port_out.close()
  977. def recv(self,n=None):
  978. try:
  979. data, new_addr = self.port.recvfrom(UDP_MAX_PACKET_LEN)
  980. if self.myport is None:
  981. try:
  982. (myaddr,self.myport) = self.port_out.getsockname()
  983. except Exception:
  984. pass
  985. except socket.error as e:
  986. if e.errno in [ errno.EAGAIN, errno.EWOULDBLOCK, errno.ECONNREFUSED ]:
  987. return ""
  988. raise
  989. if self.myport == new_addr[1]:
  990. # data from ourselves, discard
  991. return ''
  992. return data
  993. def write(self, buf):
  994. try:
  995. self.port_out.send(buf)
  996. except socket.error as e:
  997. pass
  998. def recv_msg(self):
  999. '''message receive routine for UDP link'''
  1000. self.pre_message()
  1001. s = self.recv()
  1002. if len(s) > 0:
  1003. if self.first_byte:
  1004. self.auto_mavlink_version(s)
  1005. m = self.mav.parse_char(s)
  1006. if m is not None:
  1007. self.post_message(m)
  1008. return m
  1009. class mavtcp(mavfile):
  1010. '''a TCP mavlink socket'''
  1011. def __init__(self,
  1012. device,
  1013. autoreconnect=False,
  1014. source_system=255,
  1015. source_component=0,
  1016. retries=6,
  1017. use_native=default_native):
  1018. a = device.split(':')
  1019. if len(a) != 2:
  1020. print("TCP ports must be specified as host:port")
  1021. sys.exit(1)
  1022. self.destination_addr = (a[0], int(a[1]))
  1023. self.autoreconnect = autoreconnect
  1024. self.retries = retries
  1025. self.do_connect()
  1026. mavfile.__init__(self, self.port.fileno(), "tcp:" + device, source_system=source_system, source_component=source_component, use_native=use_native)
  1027. def do_connect(self):
  1028. self.port = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
  1029. retries = self.retries
  1030. if retries <= 0:
  1031. # try to connect at least once:
  1032. retries = 1
  1033. while retries >= 0:
  1034. retries -= 1
  1035. try:
  1036. self.port.connect(self.destination_addr)
  1037. break
  1038. except Exception as e:
  1039. if retries == 0:
  1040. if self.port is not None:
  1041. self.port.close()
  1042. self.port = None
  1043. raise e
  1044. print(e, "sleeping")
  1045. time.sleep(1)
  1046. self.port.setblocking(0)
  1047. set_close_on_exec(self.port.fileno())
  1048. self.port.setsockopt(socket.SOL_TCP, socket.TCP_NODELAY, 1)
  1049. def close(self):
  1050. self.port.close()
  1051. def handle_disconnect(self):
  1052. print("Connection reset or closed by peer on TCP socket")
  1053. self.reconnect()
  1054. def handle_eof(self):
  1055. # EOF
  1056. print("EOF on TCP socket")
  1057. self.reconnect()
  1058. def recv(self,n=None):
  1059. if self.port is None:
  1060. self.reconnect()
  1061. if n is None:
  1062. n = self.mav.bytes_needed()
  1063. try:
  1064. data = self.port.recv(n)
  1065. except socket.error as e:
  1066. if e.errno in [ errno.EAGAIN, errno.EWOULDBLOCK ]:
  1067. return ""
  1068. if e.errno in [ errno.ECONNRESET, errno.EPIPE ]:
  1069. self.handle_disconnect()
  1070. raise
  1071. if len(data) == 0:
  1072. self.handle_eof()
  1073. return data
  1074. def write(self, buf):
  1075. if self.port is None:
  1076. try:
  1077. self.reconnect()
  1078. except socket.error as e:
  1079. pass
  1080. try:
  1081. self.port.send(buf)
  1082. except socket.error as e:
  1083. if e.errno in [ errno.ECONNRESET, errno.EPIPE ]:
  1084. self.handle_disconnect()
  1085. pass
  1086. def reconnect(self):
  1087. if self.autoreconnect:
  1088. print("Attempting reconnect")
  1089. if self.port is not None:
  1090. self.port.close()
  1091. self.port = None
  1092. self.do_connect()
  1093. class mavtcpin(mavfile):
  1094. '''a TCP input mavlink socket'''
  1095. def __init__(self, device, source_system=255, source_component=0, retries=3, use_native=default_native):
  1096. a = device.split(':')
  1097. if len(a) != 2:
  1098. print("TCP ports must be specified as host:port")
  1099. sys.exit(1)
  1100. self.listen = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
  1101. self.listen_addr = (a[0], int(a[1]))
  1102. self.listen.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1)
  1103. self.listen.bind(self.listen_addr)
  1104. self.listen.listen(1)
  1105. self.listen.setblocking(0)
  1106. set_close_on_exec(self.listen.fileno())
  1107. self.listen.setsockopt(socket.SOL_TCP, socket.TCP_NODELAY, 1)
  1108. mavfile.__init__(self, self.listen.fileno(), "tcpin:" + device, source_system=source_system, source_component=source_component, use_native=use_native)
  1109. self.port = None
  1110. def close(self):
  1111. self.listen.close()
  1112. def recv(self,n=None):
  1113. if not self.port:
  1114. try:
  1115. (self.port, addr) = self.listen.accept()
  1116. except Exception:
  1117. return ''
  1118. self.port.setsockopt(socket.SOL_TCP, socket.TCP_NODELAY, 1)
  1119. self.port.setblocking(0)
  1120. set_close_on_exec(self.port.fileno())
  1121. self.fd = self.port.fileno()
  1122. if n is None:
  1123. n = self.mav.bytes_needed()
  1124. try:
  1125. data = self.port.recv(n)
  1126. except socket.error as e:
  1127. if e.errno in [ errno.EAGAIN, errno.EWOULDBLOCK ]:
  1128. return ""
  1129. self.port.close()
  1130. self.port = None
  1131. self.fd = self.listen.fileno()
  1132. return ''
  1133. return data
  1134. def write(self, buf):
  1135. if self.port is None:
  1136. return
  1137. try:
  1138. self.port.send(buf)
  1139. except socket.error as e:
  1140. if e.errno in [ errno.EPIPE ]:
  1141. self.port.close()
  1142. self.port = None
  1143. self.fd = self.listen.fileno()
  1144. pass
  1145. class mavlogfile(mavfile):
  1146. '''a MAVLink logfile reader/writer'''
  1147. def __init__(self, filename, planner_format=None,
  1148. write=False, append=False,
  1149. robust_parsing=True, notimestamps=False, source_system=255, source_component=0, use_native=default_native):
  1150. self.filename = filename
  1151. self.writeable = write
  1152. self.robust_parsing = robust_parsing
  1153. self.planner_format = planner_format
  1154. self._two64 = math.pow(2.0, 63)
  1155. mode = 'rb'
  1156. if self.writeable:
  1157. if append:
  1158. mode = 'ab'
  1159. else:
  1160. mode = 'wb'
  1161. self.f = open(filename, mode)
  1162. self.filesize = os.path.getsize(filename)
  1163. self.percent = 0
  1164. mavfile.__init__(self, None, filename, source_system=source_system, source_component=source_component, notimestamps=notimestamps, use_native=use_native)
  1165. if self.notimestamps:
  1166. self._timestamp = 0
  1167. else:
  1168. self._timestamp = time.time()
  1169. self.stop_on_EOF = True
  1170. self._last_message = None
  1171. self._last_timestamp = None
  1172. self._link = 0
  1173. def close(self):
  1174. self.f.close()
  1175. def recv(self,n=None):
  1176. if n is None:
  1177. n = self.mav.bytes_needed()
  1178. return self.f.read(n)
  1179. def write(self, buf):
  1180. self.f.write(buf)
  1181. def scan_timestamp(self, tbuf):
  1182. '''scan forward looking in a tlog for a timestamp in a reasonable range'''
  1183. while True:
  1184. (tusec,) = struct.unpack('>Q', tbuf)
  1185. t = tusec * 1.0e-6
  1186. if abs(t - self._last_timestamp) <= 3*24*60*60:
  1187. break
  1188. c = self.f.read(1)
  1189. if len(c) != 1:
  1190. break
  1191. tbuf = tbuf[1:] + c
  1192. return t
  1193. def pre_message(self):
  1194. '''read timestamp if needed'''
  1195. # read the timestamp
  1196. if self.filesize != 0:
  1197. self.percent = (100.0 * self.f.tell()) / self.filesize
  1198. if self.notimestamps:
  1199. return
  1200. if self.planner_format:
  1201. tbuf = self.f.read(21)
  1202. if len(tbuf) != 21 or tbuf[0] != '-' or tbuf[20] != ':':
  1203. raise RuntimeError('bad planner timestamp %s' % tbuf)
  1204. hnsec = self._two64 + float(tbuf[0:20])
  1205. t = hnsec * 1.0e-7 # convert to seconds
  1206. t -= 719163 * 24 * 60 * 60 # convert to 1970 base
  1207. self._link = 0
  1208. else:
  1209. tbuf = self.f.read(8)
  1210. if len(tbuf) != 8:
  1211. return
  1212. (tusec,) = struct.unpack('>Q', tbuf)
  1213. t = tusec * 1.0e-6
  1214. if (self._last_timestamp is not None and
  1215. self._last_message.get_type() == "BAD_DATA" and
  1216. abs(t - self._last_timestamp) > 3*24*60*60):
  1217. t = self.scan_timestamp(tbuf)
  1218. self._link = tusec & 0x3
  1219. self._timestamp = t
  1220. def post_message(self, msg):
  1221. '''add timestamp to message'''
  1222. # read the timestamp
  1223. super(mavlogfile, self).post_message(msg)
  1224. if self.planner_format:
  1225. self.f.read(1) # trailing newline
  1226. self.timestamp = msg._timestamp
  1227. self._last_message = msg
  1228. if msg.get_type() != "BAD_DATA":
  1229. self._last_timestamp = msg._timestamp
  1230. msg._link = self._link
  1231. class mavmmaplog(mavlogfile):
  1232. '''a MAVLink log file accessed via mmap. Used for fast read-only
  1233. access with low memory overhead where particular message types are wanted'''
  1234. def __init__(self, filename, progress_callback=None):
  1235. import platform, mmap
  1236. mavlogfile.__init__(self, filename)
  1237. self.f.seek(0, 2)
  1238. self.data_len = self.f.tell()
  1239. self.f.seek(0)
  1240. if platform.system() == "Windows":
  1241. self.data_map = mmap.mmap(self.f.fileno(), self.data_len, None, mmap.ACCESS_READ)
  1242. else:
  1243. self.data_map = mmap.mmap(self.f.fileno(), self.data_len, mmap.MAP_PRIVATE, mmap.PROT_READ)
  1244. self._rewind()
  1245. self.init_arrays(progress_callback)
  1246. self._flightmodes = None
  1247. def _rewind(self):
  1248. '''rewind to start of log'''
  1249. self.flightmode = "UNKNOWN"
  1250. self.offset = 0
  1251. self.type_nums = None
  1252. self.f.seek(0)
  1253. def rewind(self):
  1254. '''rewind to start of log'''
  1255. self._rewind()
  1256. def init_arrays(self, progress_callback=None):
  1257. '''initialise arrays for fast recv_match()'''
  1258. # dictionary indexed by msgid, mapping to arrays of file offsets where
  1259. # each instance of a msg type is found
  1260. self.offsets = {}
  1261. # number of msgs of each msg type
  1262. self.counts = {}
  1263. self._count = 0
  1264. # mapping from msg name to msg id
  1265. self.name_to_id = {}
  1266. # mapping from msg id to name
  1267. self.id_to_name = {}
  1268. self.type_nums = None
  1269. ofs = 0
  1270. pct = 0
  1271. MARKER_V1 = 0xFE
  1272. MARKER_V2 = 0xFD
  1273. while ofs+8+6 < self.data_len:
  1274. marker = u_ord(self.data_map[ofs+8])
  1275. mlen = u_ord(self.data_map[ofs+9]) + 8
  1276. if marker == MARKER_V1:
  1277. mtype = u_ord(self.data_map[ofs+13])
  1278. mlen += 8
  1279. elif marker == MARKER_V2:
  1280. mtype = u_ord(self.data_map[ofs+15]) | (u_ord(self.data_map[ofs+16])<<8) | (u_ord(self.data_map[ofs+17])<<16)
  1281. mlen += 12
  1282. incompat_flags = u_ord(self.data_map[ofs+10])
  1283. if incompat_flags & mavlink.MAVLINK_IFLAG_SIGNED:
  1284. mlen += mavlink.MAVLINK_SIGNATURE_BLOCK_LEN
  1285. else:
  1286. # unrecognised marker; probably a malformed log
  1287. ofs += 1
  1288. continue
  1289. if not mtype in self.offsets:
  1290. if not mtype in mavlink.mavlink_map:
  1291. ofs += mlen
  1292. continue
  1293. self.offsets[mtype] = []
  1294. self.counts[mtype] = 0
  1295. msg = mavlink.mavlink_map[mtype]
  1296. self.name_to_id[msg.name] = mtype
  1297. self.id_to_name[mtype] = msg.name
  1298. self.f.seek(ofs)
  1299. m = self.recv_msg()
  1300. self.messages[msg.name] = m
  1301. self.offsets[mtype].append(ofs)
  1302. self.counts[mtype] += 1
  1303. ofs += mlen
  1304. new_pct = (100 * ofs) // self.data_len
  1305. if progress_callback is not None and new_pct != pct:
  1306. progress_callback(new_pct)
  1307. pct = new_pct
  1308. for mtype in self.counts:
  1309. self._count += self.counts[mtype]
  1310. self.offset = 0
  1311. self._rewind()
  1312. def skip_to_type(self, type):
  1313. '''skip fwd to next msg matching given type set'''
  1314. if self.type_nums is None:
  1315. # always add some key msg types so we can track flightmode, params etc
  1316. type = type.copy()
  1317. type.update(set(['HEARTBEAT','PARAM_VALUE']))
  1318. self.indexes = []
  1319. self.type_nums = []
  1320. for t in type:
  1321. if not t in self.name_to_id:
  1322. continue
  1323. self.type_nums.append(self.name_to_id[t])
  1324. self.indexes.append(0)
  1325. smallest_index = -1
  1326. smallest_offset = self.data_len
  1327. for i in range(len(self.type_nums)):
  1328. mtype = self.type_nums[i]
  1329. if self.indexes[i] >= self.counts[mtype]:
  1330. continue
  1331. ofs = self.offsets[mtype][self.indexes[i]]
  1332. if ofs < smallest_offset:
  1333. smallest_offset = ofs
  1334. smallest_index = i
  1335. if smallest_index >= 0:
  1336. self.indexes[smallest_index] += 1
  1337. self.offset = smallest_offset
  1338. self.f.seek(smallest_offset)
  1339. def recv_match(self, condition=None, type=None, blocking=False, timeout=None):
  1340. '''recv the next message that matches the given condition
  1341. type can be a string or a list of strings'''
  1342. if type is not None:
  1343. if isinstance(type, str):
  1344. type = set([type])
  1345. elif isinstance(type, list):
  1346. type = set(type)
  1347. while True:
  1348. if type is not None:
  1349. self.skip_to_type(type)
  1350. m = self.recv_msg()
  1351. if m is None:
  1352. if blocking:
  1353. for hook in self.idle_hooks:
  1354. hook(self)
  1355. if timeout is None:
  1356. self.select(0.05)
  1357. else:
  1358. self.select(timeout/2)
  1359. continue
  1360. return None
  1361. if type is not None and not m.get_type() in type:
  1362. continue
  1363. if not evaluate_condition(condition, self.messages):
  1364. continue
  1365. return m
  1366. def flightmode_list(self):
  1367. '''return an array of tuples for all flightmodes in log. Tuple is (modestring, t0, t1)'''
  1368. tstamp = None
  1369. fmode = None
  1370. if self._flightmodes is None:
  1371. self._rewind()
  1372. self._flightmodes = []
  1373. types = set(['HEARTBEAT'])
  1374. while True:
  1375. m = self.recv_match(type=types)
  1376. if m is None:
  1377. break
  1378. tstamp = m._timestamp
  1379. if self.flightmode == fmode:
  1380. continue
  1381. if len(self._flightmodes) > 0:
  1382. (mode, t0, t1) = self._flightmodes[-1]
  1383. self._flightmodes[-1] = (mode, t0, tstamp)
  1384. self._flightmodes.append((self.flightmode, tstamp, None))
  1385. fmode = self.flightmode
  1386. if tstamp is not None:
  1387. (mode, t0, t1) = self._flightmodes[-1]
  1388. self._flightmodes[-1] = (mode, t0, tstamp)
  1389. self._rewind()
  1390. return self._flightmodes
  1391. class mavchildexec(mavfile):
  1392. '''a MAVLink child processes reader/writer'''
  1393. def __init__(self, filename, source_system=255, source_component=0, use_native=default_native):
  1394. from subprocess import Popen, PIPE
  1395. import fcntl
  1396. self.filename = filename
  1397. self.child = Popen(filename, shell=False, stdout=PIPE, stdin=PIPE, bufsize=0)
  1398. self.fd = self.child.stdout.fileno()
  1399. fl = fcntl.fcntl(self.fd, fcntl.F_GETFL)
  1400. fcntl.fcntl(self.fd, fcntl.F_SETFL, fl | os.O_NONBLOCK)
  1401. fl = fcntl.fcntl(self.child.stdout.fileno(), fcntl.F_GETFL)
  1402. fcntl.fcntl(self.child.stdout.fileno(), fcntl.F_SETFL, fl | os.O_NONBLOCK)
  1403. mavfile.__init__(self, self.fd, filename, source_system=source_system, source_component=source_component, use_native=use_native)
  1404. def close(self):
  1405. self.child.close()
  1406. def recv(self,n=None):
  1407. try:
  1408. x = self.child.stdout.read(1)
  1409. except Exception:
  1410. return ''
  1411. return x
  1412. def write(self, buf):
  1413. self.child.stdin.write(buf)
  1414. def mavlink_connection(device, baud=115200, source_system=255, source_component=0,
  1415. planner_format=None, write=False, append=False,
  1416. robust_parsing=True, notimestamps=False, input=True,
  1417. dialect=None, autoreconnect=False, zero_time_base=False,
  1418. retries=3, use_native=default_native,
  1419. force_connected=False, progress_callback=None):
  1420. '''open a serial, UDP, TCP or file mavlink connection'''
  1421. global mavfile_global
  1422. if force_connected:
  1423. # force_connected implies autoreconnect
  1424. autoreconnect = True
  1425. if dialect is not None:
  1426. set_dialect(dialect)
  1427. if device.startswith('tcp:'):
  1428. return mavtcp(device[4:],
  1429. autoreconnect=autoreconnect,
  1430. source_system=source_system,
  1431. source_component=source_component,
  1432. retries=retries,
  1433. use_native=use_native)
  1434. if device.startswith('tcpin:'):
  1435. return mavtcpin(device[6:], source_system=source_system, source_component=source_component, retries=retries, use_native=use_native)
  1436. if device.startswith('udpin:'):
  1437. return mavudp(device[6:], input=True, source_system=source_system, source_component=source_component, use_native=use_native)
  1438. if device.startswith('udpout:'):
  1439. return mavudp(device[7:], input=False, source_system=source_system, source_component=source_component, use_native=use_native)
  1440. if device.startswith('udpbcast:'):
  1441. return mavudp(device[9:], input=False, source_system=source_system, source_component=source_component, use_native=use_native, broadcast=True)
  1442. # For legacy purposes we accept the following syntax and let the caller to specify direction
  1443. if device.startswith('udp:'):
  1444. return mavudp(device[4:], input=input, source_system=source_system, source_component=source_component, use_native=use_native)
  1445. if device.startswith('mcast:'):
  1446. return mavmcast(device[6:], source_system=source_system, source_component=source_component, use_native=use_native)
  1447. if device.lower().endswith('.bin') or device.lower().endswith('.px4log'):
  1448. # support dataflash logs
  1449. from pymavlink import DFReader
  1450. m = DFReader.DFReader_binary(device, zero_time_base=zero_time_base, progress_callback=progress_callback)
  1451. mavfile_global = m
  1452. return m
  1453. if device.endswith('.log'):
  1454. # support dataflash text logs
  1455. from pymavlink import DFReader
  1456. if DFReader.DFReader_is_text_log(device):
  1457. m = DFReader.DFReader_text(device, zero_time_base=zero_time_base, progress_callback=progress_callback)
  1458. mavfile_global = m
  1459. return m
  1460. # list of suffixes to prevent setting DOS paths as UDP sockets
  1461. logsuffixes = ['mavlink', 'log', 'raw', 'tlog' ]
  1462. suffix = device.split('.')[-1].lower()
  1463. if device.find(':') != -1 and not suffix in logsuffixes:
  1464. return mavudp(device, source_system=source_system, source_component=source_component, input=input, use_native=use_native)
  1465. if os.path.isfile(device):
  1466. if device.endswith(".elf") or device.find("/bin/") != -1:
  1467. print("executing '%s'" % device)
  1468. return mavchildexec(device, source_system=source_system, source_component=source_component, use_native=use_native)
  1469. elif not write and not append and not notimestamps:
  1470. return mavmmaplog(device, progress_callback=progress_callback)
  1471. else:
  1472. return mavlogfile(device, planner_format=planner_format, write=write,
  1473. append=append, robust_parsing=robust_parsing, notimestamps=notimestamps,
  1474. source_system=source_system, source_component=source_component, use_native=use_native)
  1475. return mavserial(device,
  1476. baud=baud,
  1477. source_system=source_system,
  1478. source_component=source_component,
  1479. autoreconnect=autoreconnect,
  1480. use_native=use_native,
  1481. force_connected=force_connected)
  1482. class periodic_event(object):
  1483. '''a class for fixed frequency events'''
  1484. def __init__(self, frequency):
  1485. self.frequency = float(frequency)
  1486. self.last_time = time.time()
  1487. def force(self):
  1488. '''force immediate triggering'''
  1489. self.last_time = 0
  1490. def trigger(self):
  1491. '''return True if we should trigger now'''
  1492. tnow = time.time()
  1493. if tnow < self.last_time:
  1494. print("Warning, time moved backwards. Restarting timer.")
  1495. self.last_time = tnow
  1496. if self.last_time + (1.0/self.frequency) <= tnow:
  1497. self.last_time = tnow
  1498. return True
  1499. return False
  1500. try:
  1501. from curses import ascii
  1502. have_ascii = True
  1503. except:
  1504. have_ascii = False
  1505. def is_printable(c):
  1506. '''see if a character is printable'''
  1507. global have_ascii
  1508. if have_ascii:
  1509. return ascii.isprint(c)
  1510. if isinstance(c, int):
  1511. ic = c
  1512. else:
  1513. ic = ord(c)
  1514. return ic >= 32 and ic <= 126
  1515. def all_printable(buf):
  1516. '''see if a string is all printable'''
  1517. for c in buf:
  1518. if not is_printable(c) and not c in ['\r', '\n', '\t'] and not c in [ord('\r'), ord('\n'), ord('\t')]:
  1519. return False
  1520. return True
  1521. class SerialPort(object):
  1522. '''auto-detected serial port'''
  1523. def __init__(self, device, description=None, hwid=None):
  1524. self.device = device
  1525. self.description = description
  1526. self.hwid = hwid
  1527. def __str__(self):
  1528. ret = self.device
  1529. if self.description is not None:
  1530. ret += " : " + self.description
  1531. if self.hwid is not None:
  1532. ret += " : " + self.hwid
  1533. return ret
  1534. def auto_detect_serial_win32(preferred_list=['*']):
  1535. '''try to auto-detect serial ports on win32'''
  1536. try:
  1537. from serial.tools.list_ports_windows import comports
  1538. list = sorted(comports())
  1539. except:
  1540. return []
  1541. ret = []
  1542. others = []
  1543. for port, description, hwid in list:
  1544. matches = False
  1545. p = SerialPort(port, description=description, hwid=hwid)
  1546. for preferred in preferred_list:
  1547. if fnmatch.fnmatch(description, preferred) or fnmatch.fnmatch(hwid, preferred):
  1548. matches = True
  1549. if matches:
  1550. ret.append(p)
  1551. else:
  1552. others.append(p)
  1553. if len(ret) > 0:
  1554. return ret
  1555. # now the rest
  1556. ret.extend(others)
  1557. return ret
  1558. def auto_detect_serial_unix(preferred_list=['*']):
  1559. '''try to auto-detect serial ports on unix'''
  1560. import glob
  1561. glist = glob.glob('/dev/ttyS*') + glob.glob('/dev/ttyUSB*') + glob.glob('/dev/ttyACM*') + glob.glob('/dev/serial/by-id/*')
  1562. ret = []
  1563. others = []
  1564. # try preferred ones first
  1565. for d in glist:
  1566. matches = False
  1567. for preferred in preferred_list:
  1568. if fnmatch.fnmatch(d, preferred):
  1569. matches = True
  1570. if matches:
  1571. ret.append(SerialPort(d))
  1572. else:
  1573. others.append(SerialPort(d))
  1574. if len(ret) > 0:
  1575. return ret
  1576. ret.extend(others)
  1577. return ret
  1578. def auto_detect_serial(preferred_list=['*']):
  1579. '''try to auto-detect serial port'''
  1580. # see if
  1581. if os.name == 'nt':
  1582. return auto_detect_serial_win32(preferred_list=preferred_list)
  1583. return auto_detect_serial_unix(preferred_list=preferred_list)
  1584. def mode_string_v09(msg):
  1585. '''mode string for 0.9 protocol'''
  1586. mode = msg.mode
  1587. nav_mode = msg.nav_mode
  1588. MAV_MODE_UNINIT = 0
  1589. MAV_MODE_MANUAL = 2
  1590. MAV_MODE_GUIDED = 3
  1591. MAV_MODE_AUTO = 4
  1592. MAV_MODE_TEST1 = 5
  1593. MAV_MODE_TEST2 = 6
  1594. MAV_MODE_TEST3 = 7
  1595. MAV_NAV_GROUNDED = 0
  1596. MAV_NAV_LIFTOFF = 1
  1597. MAV_NAV_HOLD = 2
  1598. MAV_NAV_WAYPOINT = 3
  1599. MAV_NAV_VECTOR = 4
  1600. MAV_NAV_RETURNING = 5
  1601. MAV_NAV_LANDING = 6
  1602. MAV_NAV_LOST = 7
  1603. MAV_NAV_LOITER = 8
  1604. cmode = (mode, nav_mode)
  1605. mapping = {
  1606. (MAV_MODE_UNINIT, MAV_NAV_GROUNDED) : "INITIALISING",
  1607. (MAV_MODE_MANUAL, MAV_NAV_VECTOR) : "MANUAL",
  1608. (MAV_MODE_TEST3, MAV_NAV_VECTOR) : "CIRCLE",
  1609. (MAV_MODE_GUIDED, MAV_NAV_VECTOR) : "GUIDED",
  1610. (MAV_MODE_TEST1, MAV_NAV_VECTOR) : "STABILIZE",
  1611. (MAV_MODE_TEST2, MAV_NAV_LIFTOFF) : "FBWA",
  1612. (MAV_MODE_AUTO, MAV_NAV_WAYPOINT) : "AUTO",
  1613. (MAV_MODE_AUTO, MAV_NAV_RETURNING) : "RTL",
  1614. (MAV_MODE_AUTO, MAV_NAV_LOITER) : "LOITER",
  1615. (MAV_MODE_AUTO, MAV_NAV_LIFTOFF) : "TAKEOFF",
  1616. (MAV_MODE_AUTO, MAV_NAV_LANDING) : "LANDING",
  1617. (MAV_MODE_AUTO, MAV_NAV_HOLD) : "LOITER",
  1618. (MAV_MODE_GUIDED, MAV_NAV_VECTOR) : "GUIDED",
  1619. (MAV_MODE_GUIDED, MAV_NAV_WAYPOINT) : "GUIDED",
  1620. (100, MAV_NAV_VECTOR) : "STABILIZE",
  1621. (101, MAV_NAV_VECTOR) : "ACRO",
  1622. (102, MAV_NAV_VECTOR) : "ALT_HOLD",
  1623. (107, MAV_NAV_VECTOR) : "CIRCLE",
  1624. (109, MAV_NAV_VECTOR) : "LAND",
  1625. }
  1626. if cmode in mapping:
  1627. return mapping[cmode]
  1628. return "Mode(%s,%s)" % cmode
  1629. mode_mapping_apm = {
  1630. 0 : 'MANUAL',
  1631. 1 : 'CIRCLE',
  1632. 2 : 'STABILIZE',
  1633. 3 : 'TRAINING',
  1634. 4 : 'ACRO',
  1635. 5 : 'FBWA',
  1636. 6 : 'FBWB',
  1637. 7 : 'CRUISE',
  1638. 8 : 'AUTOTUNE',
  1639. 10 : 'AUTO',
  1640. 11 : 'RTL',
  1641. 12 : 'LOITER',
  1642. 14 : 'LAND',
  1643. 15 : 'GUIDED',
  1644. 16 : 'INITIALISING',
  1645. 17 : 'QSTABILIZE',
  1646. 18 : 'QHOVER',
  1647. 19 : 'QLOITER',
  1648. 20 : 'QLAND',
  1649. 21 : 'QRTL',
  1650. 22 : 'QAUTOTUNE',
  1651. }
  1652. mode_mapping_acm = {
  1653. 0 : 'STABILIZE',
  1654. 1 : 'ACRO',
  1655. 2 : 'ALT_HOLD',
  1656. 3 : 'AUTO',
  1657. 4 : 'GUIDED',
  1658. 5 : 'LOITER',
  1659. 6 : 'RTL',
  1660. 7 : 'CIRCLE',
  1661. 8 : 'POSITION',
  1662. 9 : 'LAND',
  1663. 10 : 'OF_LOITER',
  1664. 11 : 'DRIFT',
  1665. 13 : 'SPORT',
  1666. 14 : 'FLIP',
  1667. 15 : 'AUTOTUNE',
  1668. 16 : 'POSHOLD',
  1669. 17 : 'BRAKE',
  1670. 18 : 'THROW',
  1671. 19 : 'AVOID_ADSB',
  1672. 20 : 'GUIDED_NOGPS',
  1673. 21 : 'SMART_RTL',
  1674. 22 : 'FLOWHOLD',
  1675. 23 : 'FOLLOW',
  1676. }
  1677. mode_mapping_rover = {
  1678. 0 : 'MANUAL',
  1679. 1 : 'ACRO',
  1680. 2 : 'LEARNING',
  1681. 3 : 'STEERING',
  1682. 4 : 'HOLD',
  1683. 5 : 'LOITER',
  1684. 10 : 'AUTO',
  1685. 11 : 'RTL',
  1686. 12 : 'SMART_RTL',
  1687. 15 : 'GUIDED',
  1688. 16 : 'INITIALISING'
  1689. }
  1690. mode_mapping_tracker = {
  1691. 0 : 'MANUAL',
  1692. 1 : 'STOP',
  1693. 2 : 'SCAN',
  1694. 10 : 'AUTO',
  1695. 16 : 'INITIALISING'
  1696. }
  1697. mode_mapping_sub = {
  1698. 0: 'STABILIZE',
  1699. 1: 'ACRO',
  1700. 2: 'ALT_HOLD',
  1701. 3: 'AUTO',
  1702. 4: 'GUIDED',
  1703. 7: 'CIRCLE',
  1704. 9: 'SURFACE',
  1705. 16: 'POSHOLD',
  1706. 19: 'MANUAL',
  1707. }
  1708. # map from a PX4 "main_state" to a string; see msg/commander_state.msg
  1709. # This allows us to map sdlog STAT.MainState to a simple "mode"
  1710. # string, used in DFReader and possibly other places. These are
  1711. # related but distict from what is found in mavlink messages; see
  1712. # "Custom mode definitions", below.
  1713. mainstate_mapping_px4 = {
  1714. 0 : 'MANUAL',
  1715. 1 : 'ALTCTL',
  1716. 2 : 'POSCTL',
  1717. 3 : 'AUTO_MISSION',
  1718. 4 : 'AUTO_LOITER',
  1719. 5 : 'AUTO_RTL',
  1720. 6 : 'ACRO',
  1721. 7 : 'OFFBOARD',
  1722. 8 : 'STAB',
  1723. 9 : 'RATTITUDE',
  1724. 10 : 'AUTO_TAKEOFF',
  1725. 11 : 'AUTO_LAND',
  1726. 12 : 'AUTO_FOLLOW_TARGET',
  1727. 13 : 'MAX',
  1728. }
  1729. def mode_string_px4(MainState):
  1730. return mainstate_mapping_px4.get(MainState, "Unknown")
  1731. # Custom mode definitions from PX4
  1732. PX4_CUSTOM_MAIN_MODE_MANUAL = 1
  1733. PX4_CUSTOM_MAIN_MODE_ALTCTL = 2
  1734. PX4_CUSTOM_MAIN_MODE_POSCTL = 3
  1735. PX4_CUSTOM_MAIN_MODE_AUTO = 4
  1736. PX4_CUSTOM_MAIN_MODE_ACRO = 5
  1737. PX4_CUSTOM_MAIN_MODE_OFFBOARD = 6
  1738. PX4_CUSTOM_MAIN_MODE_STABILIZED = 7
  1739. PX4_CUSTOM_MAIN_MODE_RATTITUDE = 8
  1740. PX4_CUSTOM_SUB_MODE_OFFBOARD = 0
  1741. PX4_CUSTOM_SUB_MODE_AUTO_READY = 1
  1742. PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF = 2
  1743. PX4_CUSTOM_SUB_MODE_AUTO_LOITER = 3
  1744. PX4_CUSTOM_SUB_MODE_AUTO_MISSION = 4
  1745. PX4_CUSTOM_SUB_MODE_AUTO_RTL = 5
  1746. PX4_CUSTOM_SUB_MODE_AUTO_LAND = 6
  1747. PX4_CUSTOM_SUB_MODE_AUTO_RTGS = 7
  1748. PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_TARGET = 8
  1749. auto_mode_flags = mavlink.MAV_MODE_FLAG_AUTO_ENABLED \
  1750. | mavlink.MAV_MODE_FLAG_STABILIZE_ENABLED \
  1751. | mavlink.MAV_MODE_FLAG_GUIDED_ENABLED
  1752. px4_map = { "MANUAL": (mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | mavlink.MAV_MODE_FLAG_STABILIZE_ENABLED | mavlink.MAV_MODE_FLAG_MANUAL_INPUT_ENABLED, PX4_CUSTOM_MAIN_MODE_MANUAL, 0 ),
  1753. "STABILIZED": (mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | mavlink.MAV_MODE_FLAG_STABILIZE_ENABLED | mavlink.MAV_MODE_FLAG_MANUAL_INPUT_ENABLED, PX4_CUSTOM_MAIN_MODE_STABILIZED, 0 ),
  1754. "ACRO": (mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | mavlink.MAV_MODE_FLAG_MANUAL_INPUT_ENABLED, PX4_CUSTOM_MAIN_MODE_ACRO, 0 ),
  1755. "RATTITUDE": (mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | mavlink.MAV_MODE_FLAG_MANUAL_INPUT_ENABLED, PX4_CUSTOM_MAIN_MODE_RATTITUDE, 0 ),
  1756. "ALTCTL": (mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | mavlink.MAV_MODE_FLAG_STABILIZE_ENABLED | mavlink.MAV_MODE_FLAG_MANUAL_INPUT_ENABLED, PX4_CUSTOM_MAIN_MODE_ALTCTL, 0 ),
  1757. "POSCTL": (mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | mavlink.MAV_MODE_FLAG_STABILIZE_ENABLED | mavlink.MAV_MODE_FLAG_MANUAL_INPUT_ENABLED, PX4_CUSTOM_MAIN_MODE_POSCTL, 0 ),
  1758. "LOITER": (mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | auto_mode_flags, PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_LOITER ),
  1759. "MISSION": (mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | auto_mode_flags, PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_MISSION ),
  1760. "RTL": (mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | auto_mode_flags, PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_RTL ),
  1761. "LAND": (mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | auto_mode_flags, PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_LAND ),
  1762. "RTGS": (mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | auto_mode_flags, PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_RTGS ),
  1763. "FOLLOWME": (mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | auto_mode_flags, PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_TARGET ),
  1764. "OFFBOARD": (mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | auto_mode_flags, PX4_CUSTOM_MAIN_MODE_OFFBOARD, 0 ),
  1765. "TAKEOFF": (mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | auto_mode_flags, PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF )}
  1766. def interpret_px4_mode(base_mode, custom_mode):
  1767. custom_main_mode = (custom_mode & 0xFF0000) >> 16
  1768. custom_sub_mode = (custom_mode & 0xFF000000) >> 24
  1769. if base_mode & mavlink.MAV_MODE_FLAG_MANUAL_INPUT_ENABLED != 0: #manual modes
  1770. if custom_main_mode == PX4_CUSTOM_MAIN_MODE_MANUAL:
  1771. return "MANUAL"
  1772. elif custom_main_mode == PX4_CUSTOM_MAIN_MODE_ACRO:
  1773. return "ACRO"
  1774. elif custom_main_mode == PX4_CUSTOM_MAIN_MODE_RATTITUDE:
  1775. return "RATTITUDE"
  1776. elif custom_main_mode == PX4_CUSTOM_MAIN_MODE_STABILIZED:
  1777. return "STABILIZED"
  1778. elif custom_main_mode == PX4_CUSTOM_MAIN_MODE_ALTCTL:
  1779. return "ALTCTL"
  1780. elif custom_main_mode == PX4_CUSTOM_MAIN_MODE_POSCTL:
  1781. return "POSCTL"
  1782. elif (base_mode & auto_mode_flags) == auto_mode_flags: #auto modes
  1783. if custom_main_mode & PX4_CUSTOM_MAIN_MODE_AUTO != 0:
  1784. if custom_sub_mode == PX4_CUSTOM_SUB_MODE_AUTO_MISSION:
  1785. return "MISSION"
  1786. elif custom_sub_mode == PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF:
  1787. return "TAKEOFF"
  1788. elif custom_sub_mode == PX4_CUSTOM_SUB_MODE_AUTO_LOITER:
  1789. return "LOITER"
  1790. elif custom_sub_mode == PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_TARGET:
  1791. return "FOLLOWME"
  1792. elif custom_sub_mode == PX4_CUSTOM_SUB_MODE_AUTO_RTL:
  1793. return "RTL"
  1794. elif custom_sub_mode == PX4_CUSTOM_SUB_MODE_AUTO_LAND:
  1795. return "LAND"
  1796. elif custom_sub_mode == PX4_CUSTOM_SUB_MODE_AUTO_RTGS:
  1797. return "RTGS"
  1798. elif custom_sub_mode == PX4_CUSTOM_SUB_MODE_OFFBOARD:
  1799. return "OFFBOARD"
  1800. return "UNKNOWN"
  1801. def mode_mapping_byname(mav_type):
  1802. '''return dictionary mapping mode names to numbers, or None if unknown'''
  1803. map = None
  1804. if mav_type in [mavlink.MAV_TYPE_QUADROTOR,
  1805. mavlink.MAV_TYPE_HELICOPTER,
  1806. mavlink.MAV_TYPE_HEXAROTOR,
  1807. mavlink.MAV_TYPE_OCTOROTOR,
  1808. mavlink.MAV_TYPE_COAXIAL,
  1809. mavlink.MAV_TYPE_TRICOPTER]:
  1810. map = mode_mapping_acm
  1811. if mav_type == mavlink.MAV_TYPE_FIXED_WING:
  1812. map = mode_mapping_apm
  1813. if mav_type == mavlink.MAV_TYPE_GROUND_ROVER:
  1814. map = mode_mapping_rover
  1815. if mav_type == mavlink.MAV_TYPE_SURFACE_BOAT:
  1816. map = mode_mapping_rover # for the time being
  1817. if mav_type == mavlink.MAV_TYPE_ANTENNA_TRACKER:
  1818. map = mode_mapping_tracker
  1819. if mav_type == mavlink.MAV_TYPE_SUBMARINE:
  1820. map = mode_mapping_sub
  1821. if map is None:
  1822. return None
  1823. inv_map = dict((a, b) for (b, a) in map.items())
  1824. return inv_map
  1825. def mode_mapping_bynumber(mav_type):
  1826. '''return dictionary mapping mode numbers to name, or None if unknown'''
  1827. map = None
  1828. if mav_type in [mavlink.MAV_TYPE_QUADROTOR,
  1829. mavlink.MAV_TYPE_HELICOPTER,
  1830. mavlink.MAV_TYPE_HEXAROTOR,
  1831. mavlink.MAV_TYPE_OCTOROTOR,
  1832. mavlink.MAV_TYPE_DODECAROTOR,
  1833. mavlink.MAV_TYPE_COAXIAL,
  1834. mavlink.MAV_TYPE_TRICOPTER]:
  1835. map = mode_mapping_acm
  1836. if mav_type == mavlink.MAV_TYPE_FIXED_WING:
  1837. map = mode_mapping_apm
  1838. if mav_type == mavlink.MAV_TYPE_GROUND_ROVER:
  1839. map = mode_mapping_rover
  1840. if mav_type == mavlink.MAV_TYPE_SURFACE_BOAT:
  1841. map = mode_mapping_rover # for the time being
  1842. if mav_type == mavlink.MAV_TYPE_ANTENNA_TRACKER:
  1843. map = mode_mapping_tracker
  1844. if mav_type == mavlink.MAV_TYPE_SUBMARINE:
  1845. map = mode_mapping_sub
  1846. if map is None:
  1847. return None
  1848. return map
  1849. def mode_string_v10(msg):
  1850. '''mode string for 1.0 protocol, from heartbeat'''
  1851. if msg.autopilot == mavlink.MAV_AUTOPILOT_PX4:
  1852. return interpret_px4_mode(msg.base_mode, msg.custom_mode)
  1853. if not msg.base_mode & mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED:
  1854. return "Mode(0x%08x)" % msg.base_mode
  1855. if msg.type in [ mavlink.MAV_TYPE_QUADROTOR, mavlink.MAV_TYPE_HEXAROTOR,
  1856. mavlink.MAV_TYPE_OCTOROTOR, mavlink.MAV_TYPE_TRICOPTER,
  1857. mavlink.MAV_TYPE_COAXIAL,
  1858. mavlink.MAV_TYPE_HELICOPTER ]:
  1859. if msg.custom_mode in mode_mapping_acm:
  1860. return mode_mapping_acm[msg.custom_mode]
  1861. if msg.type == mavlink.MAV_TYPE_FIXED_WING:
  1862. if msg.custom_mode in mode_mapping_apm:
  1863. return mode_mapping_apm[msg.custom_mode]
  1864. if msg.type == mavlink.MAV_TYPE_GROUND_ROVER:
  1865. if msg.custom_mode in mode_mapping_rover:
  1866. return mode_mapping_rover[msg.custom_mode]
  1867. if msg.type == mavlink.MAV_TYPE_SURFACE_BOAT:
  1868. if msg.custom_mode in mode_mapping_rover:
  1869. return mode_mapping_rover[msg.custom_mode]
  1870. if msg.type == mavlink.MAV_TYPE_ANTENNA_TRACKER:
  1871. if msg.custom_mode in mode_mapping_tracker:
  1872. return mode_mapping_tracker[msg.custom_mode]
  1873. if msg.type == mavlink.MAV_TYPE_SUBMARINE:
  1874. if msg.custom_mode in mode_mapping_sub:
  1875. return mode_mapping_sub[msg.custom_mode]
  1876. return "Mode(%u)" % msg.custom_mode
  1877. def mode_string_apm(mode_number):
  1878. '''return mode string for APM:Plane'''
  1879. if mode_number in mode_mapping_apm:
  1880. return mode_mapping_apm[mode_number]
  1881. return "Mode(%u)" % mode_number
  1882. def mode_string_acm(mode_number):
  1883. '''return mode string for APM:Copter'''
  1884. if mode_number in mode_mapping_acm:
  1885. return mode_mapping_acm[mode_number]
  1886. return "Mode(%u)" % mode_number
  1887. class x25crc(object):
  1888. '''x25 CRC - based on checksum.h from mavlink library'''
  1889. def __init__(self, buf=''):
  1890. self.crc = 0xffff
  1891. self.accumulate(buf)
  1892. def accumulate(self, buf):
  1893. '''add in some more bytes'''
  1894. byte_buf = array.array('B')
  1895. if isinstance(buf, array.array):
  1896. byte_buf.extend(buf)
  1897. else:
  1898. byte_buf.fromstring(buf)
  1899. accum = self.crc
  1900. for b in byte_buf:
  1901. tmp = b ^ (accum & 0xff)
  1902. tmp = (tmp ^ (tmp<<4)) & 0xFF
  1903. accum = (accum>>8) ^ (tmp<<8) ^ (tmp<<3) ^ (tmp>>4)
  1904. accum = accum & 0xFFFF
  1905. self.crc = accum
  1906. class MavlinkSerialPort(object):
  1907. '''an object that looks like a serial port, but
  1908. transmits using mavlink SERIAL_CONTROL packets'''
  1909. def __init__(self, portname, baudrate, devnum=0, devbaud=0, timeout=3, debug=0):
  1910. from . import mavutil
  1911. self.baudrate = 0
  1912. self.timeout = timeout
  1913. self._debug = debug
  1914. self.buf = ''
  1915. self.port = devnum
  1916. self.debug("Connecting with MAVLink to %s ..." % portname)
  1917. self.mav = mavutil.mavlink_connection(portname, autoreconnect=True, baud=baudrate)
  1918. self.mav.wait_heartbeat()
  1919. self.debug("HEARTBEAT OK\n")
  1920. if devbaud != 0:
  1921. self.setBaudrate(devbaud)
  1922. self.debug("Locked serial device\n")
  1923. def debug(self, s, level=1):
  1924. '''write some debug text'''
  1925. if self._debug >= level:
  1926. print(s)
  1927. def write(self, b):
  1928. '''write some bytes'''
  1929. from . import mavutil
  1930. self.debug("sending '%s' (0x%02x) of len %u\n" % (b, ord(b[0]), len(b)), 2)
  1931. while len(b) > 0:
  1932. n = len(b)
  1933. if n > 70:
  1934. n = 70
  1935. buf = [ord(x) for x in b[:n]]
  1936. buf.extend([0]*(70-len(buf)))
  1937. self.mav.mav.serial_control_send(self.port,
  1938. mavutil.mavlink.SERIAL_CONTROL_FLAG_EXCLUSIVE |
  1939. mavutil.mavlink.SERIAL_CONTROL_FLAG_RESPOND,
  1940. 0,
  1941. 0,
  1942. n,
  1943. buf)
  1944. b = b[n:]
  1945. def _recv(self):
  1946. '''read some bytes into self.buf'''
  1947. from . import mavutil
  1948. start_time = time.time()
  1949. while time.time() < start_time + self.timeout:
  1950. m = self.mav.recv_match(condition='SERIAL_CONTROL.count!=0',
  1951. type='SERIAL_CONTROL', blocking=False, timeout=0)
  1952. if m is not None and m.count != 0:
  1953. break
  1954. self.mav.mav.serial_control_send(self.port,
  1955. mavutil.mavlink.SERIAL_CONTROL_FLAG_EXCLUSIVE |
  1956. mavutil.mavlink.SERIAL_CONTROL_FLAG_RESPOND,
  1957. 0,
  1958. 0,
  1959. 0, [0]*70)
  1960. m = self.mav.recv_match(condition='SERIAL_CONTROL.count!=0',
  1961. type='SERIAL_CONTROL', blocking=True, timeout=0.01)
  1962. if m is not None and m.count != 0:
  1963. break
  1964. if m is not None:
  1965. if self._debug > 2:
  1966. print(m)
  1967. data = m.data[:m.count]
  1968. self.buf += ''.join(str(chr(x)) for x in data)
  1969. def read(self, n):
  1970. '''read some bytes'''
  1971. if len(self.buf) == 0:
  1972. self._recv()
  1973. if len(self.buf) > 0:
  1974. if n > len(self.buf):
  1975. n = len(self.buf)
  1976. ret = self.buf[:n]
  1977. self.buf = self.buf[n:]
  1978. if self._debug >= 2:
  1979. for b in ret:
  1980. self.debug("read 0x%x" % ord(b), 2)
  1981. return ret
  1982. return ''
  1983. def flushInput(self):
  1984. '''flush any pending input'''
  1985. self.buf = ''
  1986. saved_timeout = self.timeout
  1987. self.timeout = 0.5
  1988. self._recv()
  1989. self.timeout = saved_timeout
  1990. self.buf = ''
  1991. self.debug("flushInput")
  1992. def setBaudrate(self, baudrate):
  1993. '''set baudrate'''
  1994. from . import mavutil
  1995. if self.baudrate == baudrate:
  1996. return
  1997. self.baudrate = baudrate
  1998. self.mav.mav.serial_control_send(self.port,
  1999. mavutil.mavlink.SERIAL_CONTROL_FLAG_EXCLUSIVE,
  2000. 0,
  2001. self.baudrate,
  2002. 0, [0]*70)
  2003. self.flushInput()
  2004. self.debug("Changed baudrate %u" % self.baudrate)
  2005. def decode_bitmask(messagetype, field, value):
  2006. try:
  2007. _class = eval("mavlink.MAVLink_%s_message" % messagetype.lower())
  2008. except AttributeError as e:
  2009. raise AttributeError("No such message type")
  2010. try:
  2011. display = _class.fielddisplays_by_name[field]
  2012. except KeyError as e:
  2013. raise AttributeError("Not a bitmask field (none specified)")
  2014. if display != "bitmask":
  2015. raise ValueError("Not a bitmask field")
  2016. try:
  2017. enum_name = _class.fieldenums_by_name[field]
  2018. except KeyError as e:
  2019. raise AttributeError("No enum found for bitmask field")
  2020. try:
  2021. enum = mavlink.enums[enum_name]
  2022. except KeyError as e:
  2023. raise AttributeError("Did not find specified enumeration (%s)" % enum_name)
  2024. class EnumBitInfo(object):
  2025. def __init__(self, offset, value, name):
  2026. self.offset = offset
  2027. self.value = value
  2028. self.name = name
  2029. ret = []
  2030. for i in range(0, 64):
  2031. bit_value = (1 << i)
  2032. try:
  2033. enum_entry = enum[bit_value]
  2034. enum_entry_name = enum_entry.name
  2035. except KeyError as e:
  2036. enum_entry_name = None
  2037. if value == 0:
  2038. continue
  2039. if value & bit_value:
  2040. ret.append( EnumBitInfo(i, True, enum_entry_name) )
  2041. value = value & ~bit_value
  2042. else:
  2043. ret.append( EnumBitInfo(i, False, enum_entry_name) )
  2044. return ret
  2045. def dump_message_verbose(f, m):
  2046. '''write an excruciatingly detailed dump of message m to file descriptor f'''
  2047. try:
  2048. # __getattr__ may be overridden on m, thus this try/except
  2049. timestamp = m._timestamp
  2050. except IOError as e:
  2051. timestamp = ""
  2052. if timestamp != "":
  2053. timestamp = "%s.%02u: " % (
  2054. time.strftime("%Y-%m-%d %H:%M:%S", time.localtime(timestamp)),
  2055. int(timestamp*100.0)%100)
  2056. f.write("%s%s (link=%s) (signed=%s) (seq=%u) (src=%u/%u)\n" % (timestamp, m.get_type(), str(m.get_link_id()), str(m.get_signed()), m.get_seq(), m.get_srcSystem(), m.get_srcComponent()))
  2057. for fieldname in m.get_fieldnames():
  2058. # format in those most boring way possible:
  2059. value = m.format_attr(fieldname)
  2060. # try to add units:
  2061. try:
  2062. units = m.fieldunits_by_name[fieldname]
  2063. # perform simple unit conversions:
  2064. if units == "d%":
  2065. value = value / 10.0
  2066. units = "%"
  2067. if units == "c%":
  2068. value = value / 100.0
  2069. units = "%"
  2070. if units == "cA":
  2071. value = value / 100.0
  2072. units = "A"
  2073. elif units == "cdegC":
  2074. value = value / 100.0
  2075. units = "degC"
  2076. elif units == "cdeg":
  2077. value = value / 100.0
  2078. units = "deg"
  2079. elif units == "degE7":
  2080. value = value / 10000000.0
  2081. units = "deg"
  2082. elif units == "mG":
  2083. value = value / 1000.0
  2084. units = "G"
  2085. elif units == "mrad/s":
  2086. value = value / 1000.0
  2087. units = "rad/s"
  2088. elif units == "mV":
  2089. value = value / 1000.0
  2090. units = "V"
  2091. # and give radians in degrees too:
  2092. if units == "rad":
  2093. value = "%s%s (%sdeg)" % (value, units, math.degrees(value))
  2094. elif units == "rad/s":
  2095. value = "%s%s (%sdeg/s)" % (value, units, math.degrees(value))
  2096. elif units == "rad/s/s":
  2097. value = "%s%s (%sdeg/s/s)" % (value, units, math.degrees(value))
  2098. else:
  2099. value = "%s%s" % (value, units)
  2100. except AttributeError as e:
  2101. # e.g. BAD_DATA
  2102. pass
  2103. except KeyError as e:
  2104. pass
  2105. # format any bitmask enumerations:
  2106. try:
  2107. enum_name = m.fieldenums_by_name[fieldname]
  2108. display = m.fielddisplays_by_name[fieldname]
  2109. if enum_name is not None and display == "bitmask":
  2110. bits = decode_bitmask(m.get_type(), fieldname, value)
  2111. f.write(" %s: %s\n" % (fieldname, value))
  2112. for bit in bits:
  2113. value = bit.value
  2114. name = bit.name
  2115. svalue = " "
  2116. if not value:
  2117. svalue = "!"
  2118. if name is None:
  2119. name = "[UNKNOWN]"
  2120. f.write(" %s %s\n" % (svalue, name))
  2121. continue
  2122. # except NameError as e:
  2123. # pass
  2124. except AttributeError as e:
  2125. # e.g. BAD_DATA
  2126. pass
  2127. except KeyError as e:
  2128. pass
  2129. # add any enumeration name:
  2130. try:
  2131. enum_name = m.fieldenums_by_name[fieldname]
  2132. try:
  2133. enum_value = mavlink.enums[enum_name][value].name
  2134. value = "%s (%s)" % (value, enum_value)
  2135. except KeyError as e:
  2136. value = "%s (%s)" % (value, "[UNKNOWN]")
  2137. except AttributeError as e:
  2138. # e.g. BAD_DATA
  2139. pass
  2140. except KeyError as e:
  2141. pass
  2142. f.write(" %s: %s\n" % (fieldname, value))
  2143. if __name__ == '__main__':
  2144. serial_list = auto_detect_serial(preferred_list=['*FTDI*',"*Arduino_Mega_2560*", "*3D_Robotics*", "*USB_to_UART*", '*PX4*', '*FMU*'])
  2145. for port in serial_list:
  2146. print("%s" % port)