mavwp.py 23 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641
  1. '''
  2. module for loading/saving waypoints
  3. '''
  4. from __future__ import print_function
  5. from builtins import range
  6. from builtins import object
  7. import time, copy
  8. import logging
  9. from . import mavutil
  10. try:
  11. from google.protobuf import text_format
  12. import mission_pb2
  13. HAVE_PROTOBUF = True
  14. except ImportError:
  15. HAVE_PROTOBUF = False
  16. class MAVWPError(Exception):
  17. '''MAVLink WP error class'''
  18. def __init__(self, msg):
  19. Exception.__init__(self, msg)
  20. self.message = msg
  21. class MAVWPLoader(object):
  22. '''MAVLink waypoint loader'''
  23. def __init__(self, target_system=0, target_component=0):
  24. self.wpoints = []
  25. self.target_system = target_system
  26. self.target_component = target_component
  27. self.last_change = time.time()
  28. self.colour_for_polygon = {
  29. mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION : (255,0,0),
  30. mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION : (0,255,0)
  31. }
  32. def count(self):
  33. '''return number of waypoints'''
  34. return len(self.wpoints)
  35. def wp(self, i):
  36. '''return a waypoint'''
  37. try:
  38. the_wp = self.wpoints[i]
  39. except:
  40. the_wp = None
  41. return the_wp
  42. def wp_is_loiter(self, i):
  43. '''return true if waypoint is a loiter waypoint'''
  44. loiter_cmds = [mavutil.mavlink.MAV_CMD_NAV_LOITER_UNLIM,
  45. mavutil.mavlink.MAV_CMD_NAV_LOITER_TURNS,
  46. mavutil.mavlink.MAV_CMD_NAV_LOITER_TIME,
  47. mavutil.mavlink.MAV_CMD_NAV_LOITER_TO_ALT]
  48. if (self.wpoints[i].command in loiter_cmds):
  49. return True
  50. return False
  51. def add(self, w, comment=''):
  52. '''add a waypoint'''
  53. w = copy.copy(w)
  54. if comment:
  55. w.comment = comment
  56. w.seq = self.count()
  57. self.wpoints.append(w)
  58. self.last_change = time.time()
  59. def insert(self, idx, w, comment=''):
  60. '''insert a waypoint'''
  61. if idx >= self.count():
  62. self.add(w, comment)
  63. return
  64. if idx < 0:
  65. return
  66. w = copy.copy(w)
  67. if comment:
  68. w.comment = comment
  69. w.seq = idx
  70. self.wpoints.insert(idx, w)
  71. self.last_change = time.time()
  72. self.reindex()
  73. def reindex(self):
  74. '''reindex waypoints'''
  75. for i in range(self.count()):
  76. w = self.wpoints[i]
  77. w.seq = i
  78. self.last_change = time.time()
  79. def add_latlonalt(self, lat, lon, altitude, terrain_alt=False):
  80. '''add a point via latitude/longitude/altitude'''
  81. if terrain_alt:
  82. frame = mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT
  83. else:
  84. frame = mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT
  85. p = mavutil.mavlink.MAVLink_mission_item_message(self.target_system,
  86. self.target_component,
  87. 0,
  88. frame,
  89. mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
  90. 0, 0, 0, 0, 0, 0,
  91. lat, lon, altitude)
  92. self.add(p)
  93. def set(self, w, idx):
  94. '''set a waypoint'''
  95. w.seq = idx
  96. if w.seq == self.count():
  97. return self.add(w)
  98. if self.count() <= idx:
  99. raise MAVWPError('adding waypoint at idx=%u past end of list (count=%u)' % (idx, self.count()))
  100. self.wpoints[idx] = w
  101. self.last_change = time.time()
  102. def remove(self, w):
  103. '''remove a waypoint'''
  104. self.wpoints.remove(w)
  105. self.last_change = time.time()
  106. self.reindex()
  107. def clear(self):
  108. '''clear waypoint list'''
  109. self.wpoints = []
  110. self.last_change = time.time()
  111. def _read_waypoints_v100(self, file):
  112. '''read a version 100 waypoint'''
  113. cmdmap = {
  114. 2 : mavutil.mavlink.MAV_CMD_NAV_TAKEOFF,
  115. 3 : mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH,
  116. 4 : mavutil.mavlink.MAV_CMD_NAV_LAND,
  117. 24: mavutil.mavlink.MAV_CMD_NAV_TAKEOFF,
  118. 26: mavutil.mavlink.MAV_CMD_NAV_LAND,
  119. 25: mavutil.mavlink.MAV_CMD_NAV_WAYPOINT ,
  120. 27: mavutil.mavlink.MAV_CMD_NAV_LOITER_UNLIM
  121. }
  122. comment = ''
  123. for line in file:
  124. if line.startswith('#'):
  125. comment = line[1:].lstrip()
  126. continue
  127. line = line.strip()
  128. if not line:
  129. continue
  130. a = line.split()
  131. if len(a) != 13:
  132. raise MAVWPError("invalid waypoint line with %u values" % len(a))
  133. if mavutil.mavlink10():
  134. fn = mavutil.mavlink.MAVLink_mission_item_message
  135. else:
  136. fn = mavutil.mavlink.MAVLink_waypoint_message
  137. w = fn(self.target_system, self.target_component,
  138. int(a[0]), # seq
  139. int(a[1]), # frame
  140. int(a[2]), # action
  141. int(a[7]), # current
  142. int(a[12]), # autocontinue
  143. float(a[5]), # param1,
  144. float(a[6]), # param2,
  145. float(a[3]), # param3
  146. float(a[4]), # param4
  147. float(a[9]), # x, latitude
  148. float(a[8]), # y, longitude
  149. float(a[10]) # z
  150. )
  151. if not w.command in cmdmap:
  152. raise MAVWPError("Unknown v100 waypoint action %u" % w.command)
  153. w.command = cmdmap[w.command]
  154. self.add(w, comment)
  155. comment = ''
  156. def _read_waypoints_v110(self, file):
  157. '''read a version 110 waypoint'''
  158. comment = ''
  159. for line in file:
  160. if line.startswith('#'):
  161. comment = line[1:].lstrip()
  162. continue
  163. line = line.strip()
  164. if not line:
  165. continue
  166. a = line.split()
  167. if len(a) != 12:
  168. raise MAVWPError("invalid waypoint line with %u values" % len(a))
  169. if mavutil.mavlink10():
  170. fn = mavutil.mavlink.MAVLink_mission_item_message
  171. else:
  172. fn = mavutil.mavlink.MAVLink_waypoint_message
  173. w = fn(self.target_system, self.target_component,
  174. int(a[0]), # seq
  175. int(a[2]), # frame
  176. int(a[3]), # command
  177. int(a[1]), # current
  178. int(a[11]), # autocontinue
  179. float(a[4]), # param1,
  180. float(a[5]), # param2,
  181. float(a[6]), # param3
  182. float(a[7]), # param4
  183. float(a[8]), # x (latitude)
  184. float(a[9]), # y (longitude)
  185. float(a[10]) # z (altitude)
  186. )
  187. if w.command == 0 and w.seq == 0 and self.count() == 0:
  188. # special handling for Mission Planner created home wp
  189. w.command = mavutil.mavlink.MAV_CMD_NAV_WAYPOINT
  190. self.add(w, comment)
  191. comment = ''
  192. def _read_waypoints_pb_110(self, file):
  193. if not HAVE_PROTOBUF:
  194. raise MAVWPError(
  195. 'Cannot read mission file in protobuf format without protobuf '
  196. 'library. Try "easy_install protobuf".')
  197. explicit_seq = False
  198. warned_seq = False
  199. mission = mission_pb2.Mission()
  200. text_format.Merge(file.read(), mission)
  201. defaults = mission_pb2.Waypoint()
  202. # Set defaults (may be overriden in file).
  203. defaults.current = False
  204. defaults.autocontinue = True
  205. defaults.param1 = 0.0
  206. defaults.param2 = 0.0
  207. defaults.param3 = 0.0
  208. defaults.param4 = 0.0
  209. defaults.x = 0.0
  210. defaults.y = 0.0
  211. defaults.z = 0.0
  212. # Use defaults specified in mission file, if there are any.
  213. if mission.defaults:
  214. defaults.MergeFrom(mission.defaults)
  215. for seq, waypoint in enumerate(mission.waypoint):
  216. # Consecutive sequence numbers are automatically assigned
  217. # UNLESS the mission file specifies sequence numbers of
  218. # its own.
  219. if waypoint.seq:
  220. explicit_seq = True
  221. else:
  222. if explicit_seq and not warned_seq:
  223. logging.warn(
  224. 'Waypoint file %s: mixes explicit and implicit '
  225. 'sequence numbers' % (file,))
  226. warned_seq = True
  227. # The first command has current=True, the rest have current=False.
  228. if seq > 0:
  229. current = defaults.current
  230. else:
  231. current = True
  232. w = mavutil.mavlink.MAVLink_mission_item_message(
  233. self.target_system, self.target_component,
  234. waypoint.seq or seq,
  235. waypoint.frame,
  236. waypoint.command,
  237. waypoint.current or current,
  238. waypoint.autocontinue or defaults.autocontinue,
  239. waypoint.param1 or defaults.param1,
  240. waypoint.param2 or defaults.param2,
  241. waypoint.param3 or defaults.param3,
  242. waypoint.param4 or defaults.param4,
  243. waypoint.x or defaults.x,
  244. waypoint.y or defaults.y,
  245. waypoint.z or defaults.z)
  246. self.add(w)
  247. def load(self, filename):
  248. '''load waypoints from a file.
  249. returns number of waypoints loaded'''
  250. f = open(filename, mode='r')
  251. version_line = f.readline().strip()
  252. if version_line == "QGC WPL 100":
  253. readfn = self._read_waypoints_v100
  254. elif version_line == "QGC WPL 110":
  255. readfn = self._read_waypoints_v110
  256. elif version_line == "QGC WPL PB 110":
  257. readfn = self._read_waypoints_pb_110
  258. else:
  259. f.close()
  260. raise MAVWPError("Unsupported waypoint format '%s'" % version_line)
  261. self.clear()
  262. readfn(f)
  263. f.close()
  264. return len(self.wpoints)
  265. def save_as_pb(self, filename):
  266. mission = mission_pb2.Mission()
  267. for w in self.wpoints:
  268. waypoint = mission.waypoint.add()
  269. waypoint.command = w.command
  270. waypoint.frame = w.frame
  271. waypoint.seq = w.seq
  272. waypoint.current = w.current
  273. waypoint.autocontinue = w.autocontinue
  274. waypoint.param1 = w.param1
  275. waypoint.param2 = w.param2
  276. waypoint.param3 = w.param3
  277. waypoint.param4 = w.param4
  278. waypoint.x = w.x
  279. waypoint.y = w.y
  280. waypoint.z = w.z
  281. with open(filename, 'w') as f:
  282. f.write('QGC WPL PB 110\n')
  283. f.write(text_format.MessageToString(mission))
  284. def save(self, filename):
  285. '''save waypoints to a file'''
  286. f = open(filename, mode='w')
  287. f.write("QGC WPL 110\n")
  288. for w in self.wpoints:
  289. if getattr(w, 'comment', None):
  290. f.write("# %s\n" % w.comment)
  291. f.write("%u\t%u\t%u\t%u\t%f\t%f\t%f\t%f\t%f\t%f\t%f\t%u\n" % (
  292. w.seq, w.current, w.frame, w.command,
  293. w.param1, w.param2, w.param3, w.param4,
  294. w.x, w.y, w.z, w.autocontinue))
  295. f.close()
  296. def is_location_command(self, cmd):
  297. '''see if cmd is a MAV_CMD with a latitide/longitude.
  298. We check if it has Latitude and Longitude params in the right indexes'''
  299. mav_cmd = mavutil.mavlink.enums['MAV_CMD']
  300. if not cmd in mav_cmd:
  301. return False
  302. if not mav_cmd[cmd].param.get(5,'').startswith('Latitude'):
  303. return False
  304. if not mav_cmd[cmd].param.get(6,'').startswith('Longitude'):
  305. return False
  306. return True
  307. def view_indexes(self, done=None):
  308. '''return a list waypoint indexes in view order'''
  309. ret = []
  310. if done is None:
  311. done = set()
  312. idx = 0
  313. # find first point not done yet
  314. while idx < self.count():
  315. if not idx in done:
  316. break
  317. idx += 1
  318. exclusion_start = -1
  319. exclusion_count = -1
  320. inclusion_start = -1
  321. inclusion_count = -1
  322. while idx < self.count():
  323. w = self.wp(idx)
  324. if idx in done:
  325. if w.x != 0 or w.y != 0:
  326. ret.append(idx)
  327. break
  328. done.add(idx)
  329. if w.command == mavutil.mavlink.MAV_CMD_DO_JUMP:
  330. idx = int(w.param1)
  331. w = self.wp(idx)
  332. if w.x != 0 or w.y != 0:
  333. ret.append(idx)
  334. continue
  335. # display loops for exclusion and inclusion zones
  336. if w.command == mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION:
  337. if exclusion_start == -1:
  338. exclusion_count = int(w.param1)
  339. exclusion_start = idx
  340. if idx == exclusion_start + exclusion_count - 1:
  341. ret.append(idx)
  342. ret.append(exclusion_start)
  343. return ret
  344. if w.command == mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION:
  345. if inclusion_start == -1:
  346. inclusion_count = int(w.param1)
  347. inclusion_start = idx
  348. if idx == inclusion_start + inclusion_count - 1:
  349. ret.append(idx)
  350. ret.append(inclusion_start)
  351. return ret
  352. if (w.x != 0 or w.y != 0) and self.is_location_command(w.command):
  353. ret.append(idx)
  354. exc_zones = [mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION,
  355. mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION]
  356. w2 = self.wp(idx+1)
  357. if w2 is not None and w.command not in exc_zones and w2.command in exc_zones:
  358. # don't draw a line from last WP to first exc zone
  359. return ret
  360. idx += 1
  361. return ret
  362. def polygon(self, done=None):
  363. '''return a polygon for the waypoints'''
  364. indexes = self.view_indexes(done)
  365. points = []
  366. for idx in indexes:
  367. w = self.wp(idx)
  368. if w.command in self.colour_for_polygon:
  369. points.append((w.x, w.y, self.colour_for_polygon[w.command]))
  370. else:
  371. points.append((w.x, w.y))
  372. return points
  373. def polygon_list(self):
  374. '''return a list of polygons for the waypoints'''
  375. done = set()
  376. ret = []
  377. while len(done) != self.count():
  378. p = self.polygon(done)
  379. if len(p) > 0:
  380. ret.append(p)
  381. return ret
  382. def view_list(self):
  383. '''return a list of polygon indexes lists for the waypoints'''
  384. done = set()
  385. ret = []
  386. while len(done) != self.count():
  387. p = self.view_indexes(done)
  388. if len(p) > 0:
  389. ret.append(p)
  390. return ret
  391. class MAVRallyError(Exception):
  392. '''MAVLink rally point error class'''
  393. def __init__(self, msg):
  394. Exception.__init__(self, msg)
  395. self.message = msg
  396. class MAVRallyLoader(object):
  397. '''MAVLink Rally points and Rally Land ponts loader'''
  398. def __init__(self, target_system=0, target_component=0):
  399. self.rally_points = []
  400. self.target_system = target_system
  401. self.target_component = target_component
  402. self.last_change = time.time()
  403. def rally_count(self):
  404. '''return number of rally points'''
  405. return len(self.rally_points)
  406. def rally_point(self, i):
  407. '''return rally point i'''
  408. return self.rally_points[i]
  409. def reindex(self):
  410. '''reset counters and indexes'''
  411. for i in range(self.rally_count()):
  412. self.rally_points[i].count = self.rally_count()
  413. self.rally_points[i].idx = i
  414. self.last_change = time.time()
  415. def append_rally_point(self, p):
  416. '''add rallypoint to end of list'''
  417. if (self.rally_count() > 9):
  418. print("Can't have more than 10 rally points, not adding.")
  419. return
  420. self.rally_points.append(p)
  421. self.reindex()
  422. def create_and_append_rally_point(self, lat, lon, alt, break_alt, land_dir, flags):
  423. '''add a point via latitude/longitude'''
  424. p = mavutil.mavlink.MAVLink_rally_point_message(self.target_system, self.target_component,
  425. self.rally_count(), 0, int(lat), int(lon), int(alt), int(break_alt), int(land_dir), flags)
  426. self.append_rally_point(p)
  427. def clear(self):
  428. '''clear all point lists (rally and rally_land)'''
  429. self.rally_points = []
  430. self.last_change = time.time()
  431. def remove(self, i):
  432. '''remove a rally point'''
  433. if i < 1 or i > self.rally_count():
  434. print("Invalid rally point number %u" % i)
  435. self.rally_points.pop(i-1)
  436. self.reindex()
  437. def move(self, i, lat, lng, change_time=True):
  438. '''move a rally point'''
  439. if i < 1 or i > self.rally_count():
  440. print("Invalid rally point number %u" % i)
  441. self.rally_points[i-1].lat = int(lat*1e7)
  442. self.rally_points[i-1].lng = int(lng*1e7)
  443. if change_time:
  444. self.last_change = time.time()
  445. def set_alt(self, i, alt, break_alt=None, change_time=True):
  446. '''set rally point altitude(s)'''
  447. if i < 1 or i > self.rally_count():
  448. print("Inavlid rally point number %u" % i)
  449. return
  450. self.rally_points[i-1].alt = int(alt)
  451. if break_alt is not None:
  452. self.rally_points[i-1].break_alt = break_alt
  453. if change_time:
  454. self.last_change = time.time()
  455. def load(self, filename):
  456. '''load rally and rally_land points from a file.
  457. returns number of points loaded'''
  458. f = open(filename, mode='r')
  459. self.clear()
  460. for line in f:
  461. if line.startswith('#'):
  462. continue
  463. line = line.strip()
  464. if not line:
  465. continue
  466. a = line.split()
  467. if len(a) != 7:
  468. raise MAVRallyError("invalid rally file line: %s" % line)
  469. if (a[0].lower() == "rally"):
  470. self.create_and_append_rally_point(float(a[1]) * 1e7, float(a[2]) * 1e7,
  471. float(a[3]), float(a[4]), float(a[5]) * 100.0, int(a[6]))
  472. f.close()
  473. return len(self.rally_points)
  474. def save(self, filename):
  475. '''save fence points to a file'''
  476. f = open(filename, mode='w')
  477. for p in self.rally_points:
  478. f.write("RALLY %f\t%f\t%f\t%f\t%f\t%d\n" % (p.lat * 1e-7, p.lng * 1e-7, p.alt,
  479. p.break_alt, p.land_dir, p.flags))
  480. f.close()
  481. class MAVFenceError(Exception):
  482. '''MAVLink fence error class'''
  483. def __init__(self, msg):
  484. Exception.__init__(self, msg)
  485. self.message = msg
  486. class MAVFenceLoader(object):
  487. '''MAVLink geo-fence loader'''
  488. def __init__(self, target_system=0, target_component=0):
  489. self.points = []
  490. self.target_system = target_system
  491. self.target_component = target_component
  492. self.last_change = time.time()
  493. def count(self):
  494. '''return number of points'''
  495. return len(self.points)
  496. def point(self, i):
  497. '''return a point'''
  498. return self.points[i]
  499. def add(self, p):
  500. '''add a point'''
  501. self.points.append(p)
  502. self.reindex()
  503. def reindex(self):
  504. '''reindex waypoints'''
  505. for i in range(self.count()):
  506. w = self.points[i]
  507. w.idx = i
  508. w.count = self.count()
  509. w.target_system = self.target_system
  510. w.target_component = self.target_component
  511. self.last_change = time.time()
  512. def add_latlon(self, lat, lon):
  513. '''add a point via latitude/longitude'''
  514. p = mavutil.mavlink.MAVLink_fence_point_message(self.target_system, self.target_component,
  515. self.count(), 0, lat, lon)
  516. self.add(p)
  517. def clear(self):
  518. '''clear point list'''
  519. self.points = []
  520. self.last_change = time.time()
  521. def load(self, filename):
  522. '''load points from a file.
  523. returns number of points loaded'''
  524. f = open(filename, mode='r')
  525. self.clear()
  526. for line in f:
  527. if line.startswith('#'):
  528. continue
  529. line = line.strip()
  530. if not line:
  531. continue
  532. a = line.split()
  533. if len(a) != 2:
  534. raise MAVFenceError("invalid fence point line: %s" % line)
  535. self.add_latlon(float(a[0]), float(a[1]))
  536. f.close()
  537. return len(self.points)
  538. def save(self, filename):
  539. '''save fence points to a file'''
  540. f = open(filename, mode='w')
  541. for p in self.points:
  542. f.write("%f\t%f\n" % (p.lat, p.lng))
  543. f.close()
  544. def move(self, i, lat, lng, change_time=True):
  545. '''move a fence point'''
  546. if i < 0 or i >= self.count():
  547. print("Invalid fence point number %u" % i)
  548. self.points[i].lat = lat
  549. self.points[i].lng = lng
  550. # ensure we close the polygon
  551. if i == 1:
  552. self.points[self.count()-1].lat = lat
  553. self.points[self.count()-1].lng = lng
  554. if i == self.count() - 1:
  555. self.points[1].lat = lat
  556. self.points[1].lng = lng
  557. if change_time:
  558. self.last_change = time.time()
  559. def remove(self, i, change_time=True):
  560. '''remove a fence point'''
  561. if i < 0 or i >= self.count():
  562. print("Invalid fence point number %u" % i)
  563. self.points.pop(i)
  564. # ensure we close the polygon
  565. if i == 1:
  566. self.points[self.count()-1].lat = self.points[1].lat
  567. self.points[self.count()-1].lng = self.points[1].lng
  568. if i == self.count():
  569. self.points[1].lat = self.points[self.count()-1].lat
  570. self.points[1].lng = self.points[self.count()-1].lng
  571. if change_time:
  572. self.last_change = time.time()
  573. def polygon(self):
  574. '''return a polygon for the fence'''
  575. points = []
  576. for fp in self.points[1:]:
  577. points.append((fp.lat, fp.lng))
  578. return points