-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathtelemetry.py
362 lines (319 loc) · 16.3 KB
/
telemetry.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
import time
from pymavlink import mavutil, mavwp
import pymavlink.dialects.v20.all as dialect
import threading
class Connection:
# The connection class is used to connect the vehicle,
# further, more the class can also connect wit sitl for simulation and debug purposes.
def __init__(self):
self.connection = None
self.device = None
self.baud = None
self.connection_string = None
def init(self, device, baud):
# To connect with telemetry/devices
self.device = device
self.baud = baud
def init_sitl(self, connection_string):
# to connect with software in the loop
self.connection_string = connection_string
def connect_telemetry(self):
try:
self.connection = mavutil.mavlink_connection(self.device, baud=self.baud)
self.connection.wait_heartbeat()
print("Heartbeat from system (system %u component %u)" % (
self.connection.target_system, self.connection.target_component))
except Exception as e:
print("Error connecting to Flight Controller:", str(e))
def connect_sitl(self):
try:
self.connection = mavutil.mavlink_connection(self.connection_string)
self.connection.wait_heartbeat()
print("Heartbeat from system (system %u component %u)" % (
self.connection.target_system, self.connection.target_component))
except Exception as e:
print("Error connecting to Flight Controller:", str(e))
def get_instance(self):
return self.connection
def close(self):
if self.connection:
self.connection.close()
print("Connection closed.")
class FlightController:
# Following class is used to perform the basic functions of vehicle
def __init__(self, vehicle):
self.vehicle = vehicle
self.flight_modes = {
0: 'STABILIZE',
1: 'ACRO',
2: 'ALT_HOLD',
3: 'AUTO',
4: 'GUIDED',
5: 'LOITER',
6: 'RTL',
7: 'CIRCLE',
8: 'LAND',
9: 'DRIFT',
10: 'SPORT',
11: 'FLIP',
12: 'AUTOTUNE',
13: 'POSHOLD',
14: 'BRAKE',
15: 'THROW',
16: 'AVOID_ADSB',
17: 'GUIDED_NOGPS',
18: 'SMART_RTL',
19: 'FLOWHOLD',
20: 'FOLLOW',
21: 'ZIGZAG',
22: 'SYSTEMID',
23: 'AUTOROTATE',
24: 'AUTO_RTL',
}
def turn_on_motor(self):
# arm the motors
self.vehicle.arducopter_arm()
ack = self.vehicle.recv_match(type='COMMAND_ACK', blocking=True, timeout=10)
if ack and ack.command == 400 and ack.result == 0:
print("Turning on Motors")
else:
print("Failed to turn on Motors")
def turn_off_motor(self):
# disarm the motors
self.vehicle.arducopter_disarm()
self.vehicle.motors_disarmed_wait()
print("Turning off Motors")
def set_parameter_value(self, param_id, param_value):
# get parameter type first
_, param_type = self.get_parameter_value(param_id)
time.sleep(0.1)
# To set ardu-pilot parameters
self.vehicle.mav.param_set_send(
self.vehicle.target_system,
self.vehicle.target_component,
param_id.encode('utf-8'),
param_value,
param_type
)
def set_mode(self, mode):
# function to set the vehicle mode (i-e guided auto rtl etc)
mode_id = self.vehicle.mode_mapping()[mode]
self.vehicle.set_mode_apm(mode_id)
while True:
ack = self.vehicle.recv_match(type='COMMAND_ACK', blocking=True, timeout=10)
if ack and ack.command == mavutil.mavlink.MAV_CMD_DO_SET_MODE and ack.result == mavutil.mavlink.MAV_RESULT_ACCEPTED:
print("{} mode set successfully...".format(mode))
break
def get_mode(self):
msg = self.vehicle.recv_match(type='HEARTBEAT', blocking=True)
if msg:
mode = msg.custom_mode
if mode in self.flight_modes:
print(f"Current flight mode: {self.flight_modes[mode]}")
else:
print(f"Unknown flight mode: {mode}")
def get_parameter_value(self, parameter_name):
parameter_type = None
# Request the parameter value
self.vehicle.mav.param_request_read_send(
self.vehicle.target_system, self.vehicle.target_component,
parameter_name.encode('utf-8'),
-1 # Request the value of all instances (use 0 for specific index)
)
message = self.vehicle.recv_match(type='PARAM_VALUE', blocking=True).to_dict()
return message['param_value'], message['param_type']
# To land the vehicle
def land_vehicle(self):
self.set_mode('LAND')
print("Landing...")
# To trigger Return to Launch (RTL)
def rtl_vehicle(self):
self.set_mode('RTL')
print("Returning to Launch...")
# Command the vehicle to take off
def takeoff(self, altitude=5):
self.vehicle.mav.command_long_send(
self.vehicle.target_system,
self.vehicle.target_component,
mavutil.mavlink.MAV_CMD_NAV_TAKEOFF,
0,
0, 0, 0, 0, 0, 0, altitude
)
while True:
ack = self.vehicle.recv_match(type='COMMAND_ACK', blocking=True, timeout=10)
if ack and ack.command == mavutil.mavlink.MAV_CMD_NAV_TAKEOFF and ack.result == mavutil.mavlink.MAV_RESULT_ACCEPTED:
print("Vehicle Takeoff successfully...")
break
class GPS:
def __init__(self, vehicle):
self.vehicle = vehicle
self.latitude = None
self.longitude = None
self.rel_alt = None
self._thread = None
self._stop_event = threading.Event()
def gps_3d_location(self):
self.vehicle.mav.request_data_stream_send(self.vehicle.target_system, self.vehicle.target_component,
mavutil.mavlink.MAV_DATA_STREAM_POSITION, 1, 1)
while not self._stop_event.is_set():
msg = self.vehicle.recv_match(blocking=True)
if msg:
if msg.get_type() == 'GLOBAL_POSITION_INT':
self.latitude = msg.lat / 1e7
self.longitude = msg.lon / 1e7
self.rel_alt = msg.relative_alt / 1000
print("GPS Coordinates (Global Position Int):")
print(f"Latitude: {self.latitude} degrees")
print(f"Longitude: {self.longitude} degrees")
print(f"Altitude: {msg.alt / 1000.0} meters")
print(f"Relative Altitude: {self.rel_alt} meters")
def start_thread(self):
if self._thread is None:
self._thread = threading.Thread(target=self.gps_3d_location)
self._thread.start()
def stop_thread(self):
if self._thread is not None:
self._stop_event.set()
self._thread.join()
self._thread = None
self._stop_event.clear()
class Compass:
def __init__(self, vehicle):
self.vehicle = vehicle
self.heading = None
self._thread = None
self._stop_event = threading.Event()
def get_heading(self):
# Request compass data stream
self.vehicle.mav.request_data_stream_send(self.vehicle.target_system, self.vehicle.target_component,
mavutil.mavlink.MAV_DATA_STREAM_EXTRA1, 1, 1)
while not self._stop_event.is_set():
msg = self.vehicle.recv_match(blocking=True)
if msg:
if msg.get_type() == 'VFR_HUD':
self.heading = msg.heading
print("Compass Heading (VFR HUD):")
print(f"Heading: {self.heading} degrees")
elif msg.get_type() == 'ATTITUDE':
self.heading = msg.yaw
print("Compass Heading (Attitude):")
print(f"Heading: {self.heading} degrees")
def start_thread(self):
if self._thread is None:
self._thread = threading.Thread(target=self.get_heading)
self._thread.start()
def stop_thread(self):
if self._thread is not None:
self._stop_event.set()
self._thread.join()
self._thread = None
self._stop_event.clear()
class Waypoint:
def __init__(self, vehicle):
self.vehicle = vehicle
self.target_locations = None
def init_target_locations(self, target_locations):
self.target_locations = target_locations
message = dialect.MAVLink_mission_count_message(target_system=self.vehicle.target_system,
target_component=self.vehicle.target_component,
count=len(target_locations) + 2,
mission_type=dialect.MAV_MISSION_TYPE_MISSION)
self.vehicle.mav.send(message)
# catch a message
while True:
message = self.vehicle.recv_match(blocking=True)
# convert this message to dictionary
message = message.to_dict()
# check this message is MISSION_REQUEST
if message["mavpackettype"] == dialect.MAVLink_mission_request_message.msgname:
# check this request is for mission items
if message["mission_type"] == dialect.MAV_MISSION_TYPE_MISSION:
# get the sequence number of requested mission item
seq = message["seq"]
# create mission item int message
if seq == 0:
# create mission item int message that contains the home location (0th mission item)
message = dialect.MAVLink_mission_item_int_message(target_system=self.vehicle.target_system,
target_component=self.vehicle.target_component,
seq=seq,
frame=dialect.MAV_FRAME_GLOBAL,
command=dialect.MAV_CMD_NAV_WAYPOINT,
current=0,
autocontinue=0,
param1=0,
param2=0,
param3=0,
param4=0,
x=0,
y=0,
z=0,
mission_type=dialect.MAV_MISSION_TYPE_MISSION)
# send takeoff mission item
elif seq == 1:
# create mission item int message that contains the takeoff command
message = dialect.MAVLink_mission_item_int_message(target_system=self.vehicle.target_system,
target_component=self.vehicle.target_component,
seq=seq,
frame=dialect.MAV_FRAME_GLOBAL_RELATIVE_ALT,
command=dialect.MAV_CMD_NAV_TAKEOFF,
current=0,
autocontinue=0,
param1=0,
param2=0,
param3=0,
param4=0,
x=0,
y=0,
z=target_locations[0][2],
mission_type=dialect.MAV_MISSION_TYPE_MISSION)
# send target locations to the vehicle
else:
# create mission item int message that contains a target location
message = dialect.MAVLink_mission_item_int_message(target_system=self.vehicle.target_system,
target_component=self.vehicle.target_component,
seq=seq,
frame=dialect.MAV_FRAME_GLOBAL_RELATIVE_ALT,
command=dialect.MAV_CMD_NAV_WAYPOINT,
current=0,
autocontinue=0,
param1=0,
param2=0,
param3=0,
param4=0,
x=int(target_locations[seq - 2][0] * 1e7),
y=int(target_locations[seq - 2][1] * 1e7),
z=target_locations[seq - 2][2],
mission_type=dialect.MAV_MISSION_TYPE_MISSION)
# send the mission item int message to the vehicle
self.vehicle.mav.send(message)
# check this message is MISSION_ACK
elif message["mavpackettype"] == dialect.MAVLink_mission_ack_message.msgname:
# check this acknowledgement is for mission and it is accepted
if message["mission_type"] == dialect.MAV_MISSION_TYPE_MISSION and \
message["type"] == dialect.MAV_MISSION_ACCEPTED:
# break the loop since the upload is successful
print("Mission upload is successful")
break
if __name__ == "__main__":
try:
connector = Connection()
# device = 'com8' # portself.vehicle.recv_match(type='PARAM_VALUE', blocking=True)
# baud = 115200 # baud
# connector.init(device, baud)
# connector.connect_telemetry()
connecting_string = 'tcp:127.0.0.1:5762' # sitl connecting sting
connector.init_sitl(connecting_string)
connector.connect_sitl()
flight_controller = FlightController(connector.get_instance())
waypoint_mission = Waypoint(connector.get_instance())
flight_controller.set_mode('GUIDED')
flight_controller.turn_on_motor()
flight_controller.takeoff()
target_locations = ((-35.361297, 149.161120, 50.0),
(-35.360780, 149.167151, 50.0),
(-35.365115, 149.167647, 50.0),
(-35.364419, 149.161575, 50.0))
waypoint_mission.init_target_locations(target_locations)
flight_controller.set_mode('AUTO')
except Exception as e:
print("Exception", e)