16 from mavros_msgs.msg
import Waypoint, WaypointList, CommandCode
17 from mavros_msgs.srv
import WaypointPull, WaypointPush, WaypointClear, \
22 Waypoint.FRAME_GLOBAL:
'GAA',
23 Waypoint.FRAME_GLOBAL_REL_ALT:
'GRA',
24 Waypoint.FRAME_LOCAL_ENU:
'LOC-ENU',
25 Waypoint.FRAME_LOCAL_NED:
'LOC-NED',
26 Waypoint.FRAME_MISSION:
'MIS' 30 CommandCode.NAV_LAND:
'LAND',
31 CommandCode.NAV_LOITER_TIME:
'LOITER-TIME',
32 CommandCode.NAV_LOITER_TURNS:
'LOITER-TURNS',
33 CommandCode.NAV_LOITER_UNLIM:
'LOITER-UNLIM',
34 CommandCode.NAV_RETURN_TO_LAUNCH:
'RTL',
35 CommandCode.NAV_TAKEOFF:
'TAKEOFF',
36 CommandCode.NAV_WAYPOINT:
'WAYPOINT',
39 113:
'COND-CHANGE-ALT',
43 178:
'DO-CHANGE-SPEED',
45 182:
'DO-REPEAT-RELAY',
47 184:
'DO-REPEAT-SERVO',
53 """Base class for waypoint file parsers""" 55 """Returns a iterable of waypoints""" 56 raise NotImplementedError
58 def write(self, file_, waypoints):
59 """Writes waypoints to file""" 60 raise NotImplementedError
64 """Parse QGC waypoint file""" 66 file_header =
'QGC WPL 120' 67 known_versions = (110, 120)
72 skipinitialspace =
True 73 lineterminator =
'\r\n' 74 quoting = csv.QUOTE_NONE
78 for data
in csv.reader(file_, self.
CSVDialect):
79 if data[0].startswith(
'#'):
83 qgc, wpl, ver = data[0].split(
' ', 3)
90 is_current = bool(
int(data[1])),
92 command =
int(data[3]),
93 param1 = float(data[4]),
94 param2 = float(data[5]),
95 param3 = float(data[6]),
96 param4 = float(data[7]),
97 x_lat = float(data[8]),
98 y_long = float(data[9]),
99 z_alt = float(data[10]),
100 autocontinue = bool(
int(data[11]))
106 for seq, w
in enumerate(waypoints):
131 return rospy.Subscriber(
mavros.get_topic(
'mission',
'waypoints'), WaypointList, cb, **kvargs)
135 global pull, push, clear, set_current
143 set_current =
_get_proxy(
'set_current', WaypointSetCurrent)
def subscribe_waypoints(cb, kvargs)
def _get_proxy(service, type)
def write(self, file_, waypoints)
def write(self, file_, waypoints)
def register_on_namespace_update(cb)