forked from alireza787b/mavsdk_drone_show
-
Notifications
You must be signed in to change notification settings - Fork 0
/
gcs_with_flask.py
684 lines (531 loc) · 27.6 KB
/
gcs_with_flask.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
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
"""
Author: Alireza Ghaderi
Email: [email protected]
GitHub: alireza787b
Repository: github.com/alireza787b/mavsdk_drone_show
Date: August 2023
---------------------------------------------------------------------------
Ground Control Station (GCS) Script for Drone Telemetry and Command Control + flask web socket
---------------------------------------------------------------------------
This script is designed to function as a Ground Control Station (GCS) in a drone network, providing functionality for receiving telemetry data from drones and
sending commands to them. The script communicates with the drones over User Datagram Protocol (UDP), and it can be easily configured and expanded to
handle multiple drones simultaneously.
Setup and Configuration:
------------------------
Flask server runs automatically with this file, sending telemetry data in JSON format to:
http://localhost:5000/telemetry
For the React Ground Control Station (GCS) Interface:
- Run the 'start_dashboard.sh' script located in the 'apps' folder for linux based.
Alternatively, use the terminal to navigate to 'apps/dashboard/drone-dashboard' and execute 'npm start'.
- Once started, the GCS interface will be available at http://localhost:3000
Prerequisites:
- Ensure Flask, Node.js, and Python are installed on your system.
Additional Information:
- Detailed documentation is available in the 'docs' folder.
- For more insights and code details, refer to the GitHub repository: https://github.com/alireza787b/mavsdk_drone_show
- Video tutorials and demonstrations are available on the associated YouTube channel.
The script is set up to read its configuration from a .csv file named 'config.csv' which should be located in the same directory as the script. The columns
in 'config.csv' should be as follows: hw_id, pos_id, x, y, ip, mavlink_port, debug_port, gcs_ip.
Each row in 'config.csv' corresponds to a drone. The 'hw_id' column indicates the hardware ID of the drone, the 'pos_id' gives its position ID, 'x' and 'y'
provide coordinates, 'ip' specifies the drone's IP address, 'mavlink_port' and 'debug_port' provide the ports for MAVLink communication and debug information,
and 'gcs_ip' specifies the IP address of the GCS.
The script supports both single-drone and multiple-drone modes. The mode is determined by the 'single_drone' variable in the script.
If 'single_drone' is True, the script will function in single-drone mode, where it communicates with a single drone specified by the hardware ID in a file
named 'i.hwID', where 'i' is the hardware ID of the drone. This file should be located in the same directory as the script.
If 'single_drone' is False, the script operates in multiple-drone mode, communicating with all drones specified in the 'config.csv' file.
Sim Mode:
---------
The script includes a 'sim_mode' boolean variable that allows the user to switch between simulation mode and real-world mode. When 'sim_mode' is set to True,
the script is in simulation mode, and the IP address of the coordinator (essentially the drone control node) is manually defined in the code.
If 'sim_mode' is False, the script uses the IP address from 'config.csv' for the drones.
Communication Protocol:
-----------------------
The script communicates with the drones over UDP using binary packets. For telemetry data, these packets have the following structure:
- Header (1 byte): A constant value of 77.
- HW_ID (1 byte): The hardware ID of the drone.
- Pos_ID (1 byte): The position ID of the drone.
- State (1 byte): The current state of the drone.
- Trigger Time (4 bytes): The Unix timestamp when the data was sent.
- Terminator (1 byte): A constant value of 88.
For commands, the packets have a similar structure, but the header value is 55 and the terminator value is 66.
Each part of the packet is packed into a binary format using the struct.pack method from Python's 'struct' library.
The '=' character ensures that the bytes are packed in standard size, 'B' specifies an unsigned char (1 byte), and 'I' specifies an unsigned int (4 bytes).
Example:
--------
For example, a command packet could look like this in binary:
Header = 55 (in binary: 00110111)
HW_ID = 3 (in binary: 00000011)
Pos_ID = 3 (in binary:
00000011)
State = 1 (in binary: 00000001)
Trigger Time = 1687840743 (in binary: 11001010001100001101101100111111)
Terminator = 66 (in binary: 01000010)
The whole packet in binary would look like this:
00110111 00000011 00000011 00000001 11001010001100001101101100111111 01000010
Please note that the actual binary representation would be a sequence of 8-bit binary numbers.
The above representation is simplified to demonstrate the concept.
Running the script:
-------------------
To run the script, simply execute it in a Python environment. You will be prompted to enter commands for the drone.
You can enter 't' to send a command to the drone or 'q' to quit the script. If you choose to send a command,
you will be asked to enter the number of seconds for the trigger time. During this time, telemetry data will not be printed.
You can enter '0' to cancel the command and resume printing of telemetry data.
License:
--------
This script is open-source and available to use and modify as per the terms of the license agreement.
Disclaimer:
-----------
The script is provided as-is, and the authors and contributors are not responsible for any damage or loss resulting from its use.
Always ensure that you comply with all local laws and regulations when operating drones.
"""
import csv
import logging
import shutil
import socket
import struct
import subprocess
from flask import Flask, jsonify, make_response, send_from_directory
from flask import request, send_file
from threading import Thread, Lock
import time
import pandas as pd
import os
import math
from enum import Enum
from flask_cors import CORS
import zipfile
from werkzeug.utils import secure_filename
import shutil
FORWARDING_IPS = ['172.27.18.28'] # Add IPs here as strings e.g. ['192.168.1.2', '192.168.1.3']
# Imports
telemetry_data_all_drones = {}
telemetry_lock = Lock()
class State(Enum):
IDLE = 0
ARMED = 1
TRIGGERED = 2
class Mission(Enum):
NONE = 0
DRONE_SHOW_FROM_CSV = 1
SMART_SWARM = 2
TAKE_OFF = 10
LAND = 101
HOLD = 102
TEST = 100
flask_telem_socket_port = 5000
# Sim Mode
sim_mode = False # Set this variable to True for simulation mode (the ip of all drones will be the same)
telem_struct_fmt = '=BHHBBIddddddddBIB'
command_struct_fmt = '=B B B B B I B'
telem_packet_size = struct.calcsize(telem_struct_fmt)
command_packet_size = struct.calcsize(command_struct_fmt)
# Setup logger
logging.basicConfig(level=logging.INFO)
logger = logging.getLogger(__name__)
# Single Drone
single_drone = False # Set this to True for single drone connection
# Read the config file
config_df = pd.read_csv('config.csv')
# Drones list
drones = []
if single_drone:
# Read the hardware ID from the '.hwID' file
hw_id_file = [file for file in os.listdir() if file.endswith('.hwID')][0] # Assuming there's only one such file
hw_id = int(hw_id_file.split('.')[0]) # Extract the hw_id
# Find the configuration for the drone in the 'config.csv' file
drone_config = config_df.loc[config_df['hw_id'] == hw_id].iloc[0]
drones = [drone_config]
else:
# Add all drones from config file to drones list
drones = [drone for _, drone in config_df.iterrows()]
# Function to send commands
def send_command(trigger_time, sock, coordinator_ip, debug_port, hw_id, pos_id, mission, state):
try:
# Debug: Log before sending command
logger.debug(f"Preparing to send command to HW_ID={hw_id}, POS_ID={pos_id}")
# Prepare the command data
header = 55 # Constant
terminator = 66 # Constant
# Encode the data
data = struct.pack(command_struct_fmt, header, hw_id, pos_id, mission, state, trigger_time, terminator)
print(f"Sending command with mission code: {mission}") # Add this line
# Send the command data
sock.sendto(data, (coordinator_ip, debug_port))
logger.info(f"Sent {len(data)} byte command: Header={header}, HW_ID={hw_id}, Pos_ID={pos_id}, Mission={mission}, State={state}, Trigger Time={trigger_time}, Terminator={terminator}")
except (OSError, struct.error) as e:
# If there is an OSError or an error in packing the data, log the error
logger.error(f"An error occurred: {e}")
def retry_pending_commands():
while True:
time.sleep(1) # Sleep for 1 second between each iteration
current_time = int(time.time())
with telemetry_lock: # Lock to ensure thread safety
for hw_id, command_data in list(pending_commands.items()): # Make a copy of items to safely modify the dictionary
if current_time - command_data['timestamp'] > 5: # If more than 5 seconds have passed
if command_data['retries'] < 5: # Maximum of 5 retries
# Resend the command (You'll need to adjust this part to fit your actual send_command function)
send_command(command_data['trigger_time'], sock, coordinator_ip, debug_port, hw_id, pos_id, command_data['mission'], command_data['state'])
# Update the number of retries and timestamp
command_data['retries'] += 1
command_data['timestamp'] = current_time
else:
# Remove this command from pending_commands if max retries reached
del pending_commands[hw_id]
def get_optional_altitude(mission):
if 10 <= mission < 60: # Range for takeoff commands with altitude
return f" (Altitude: {mission % 10}m)"
return ""
def handle_telemetry(keep_running, print_telemetry, sock):
"""
This function continuously receives and handles telemetry data.
It updates the global telemetry data and checks for any pending commands
that have been successfully executed.
:param keep_running: A control flag for the while loop.
When it's False, the function stops receiving data.
:param print_telemetry: A flag to control if the telemetry data should be printed.
:param sock: The socket from which data will be received.
"""
global telemetry_data_all_drones # Declare it as global so that we can modify it
global pending_commands # Declare it as global so that we can modify it
while keep_running[0]:
try:
# Debug: Log at the beginning of receiving telemetry
logger.debug("Waiting to receive telemetry data...")
# Receive telemetry data
data, addr = sock.recvfrom(1024)
# If received data is not of correct size, log the error and continue
if len(data) != telem_packet_size:
logger.error(f"Received packet of incorrect size. Expected {telem_packet_size}, got {len(data)}.")
continue
# Decode the data
telemetry_data = struct.unpack(telem_struct_fmt, data)
header, terminator = telemetry_data[0], telemetry_data[-1]
hw_id, pos_id, state, mission, trigger_time, position_lat, position_long, position_alt, velocity_north, velocity_east, velocity_down, yaw, battery_voltage, follow_mode, telemetry_update_time = telemetry_data[1:-1]
# Inside your existing code
if 10 <= mission < 60:
optional_altitude = get_optional_altitude(mission)
mission = 10 # Resetting mission to the default takeoff code
logger.debug(f"Unpacked Telemetry: HW_ID={hw_id}, Pos_ID={pos_id}, State={State(state).name}, Mission={Mission(mission).name}{optional_altitude}, Trigger Time={trigger_time}")
else:
logger.debug(f"Unpacked Telemetry: HW_ID={hw_id}, Pos_ID={pos_id}, State={State(state).name}, Mission={Mission(mission).name}, Trigger Time={trigger_time}")
# If header or terminator are not as expected, log the error and continue
if header != 77 or terminator != 88:
logger.error("Invalid header or terminator received in telemetry data.")
continue
# Forwarding the received telemetry data to the specified IPs
for ip in FORWARDING_IPS:
try:
sock.sendto(data, (ip, sock.getsockname()[1])) # Using the same port as the receiving port
except Exception as e:
logger.error(f"Error forwarding telemetry to IP {ip}: {e}")
# Update global telemetry data for all drones
with telemetry_lock:
telemetry_data_all_drones[hw_id] = {
'Pos_ID': pos_id,
'State': State(state).name,
'Mission': Mission(mission).name,
'Position_Lat': position_lat,
'Position_Long': position_long,
'Position_Alt': position_alt,
'Velocity_North': velocity_north,
'Velocity_East': velocity_east,
'Velocity_Down': velocity_down,
'Yaw': yaw,
'Battery_Voltage': battery_voltage,
'Follow_Mode': follow_mode,
'Update_Time': telemetry_update_time
}
# Check for pending commands
with telemetry_lock:
if hw_id in pending_commands:
logger.debug(f"Found pending command for HW_ID={hw_id}. Checking...")
pending_command = pending_commands[hw_id]
if pending_command['mission'] == Mission(mission).name and pending_command['state'] == State(state).name and pending_command['trigger_time'] == trigger_time:
# Remove this command from the pending commands as it has been successfully executed
del pending_commands[hw_id]
# If the print_telemetry flag is True, print the decoded data
if print_telemetry[0]:
# Debug log with all details
logger.debug(f"Received telemetry at {telemetry_update_time}: Header={header}, HW_ID={hw_id}, Pos_ID={pos_id}, State={State(state).name}, Mission={Mission(mission).name}, Trigger Time={trigger_time}, Position Lat={position_lat}, Position Long={position_long}, Position Alt={position_alt:.1f}, Velocity North={velocity_north:.1f}, Velocity East={velocity_east:.1f}, Velocity Down={velocity_down:.1f}, Yaw={yaw:.1f}, Battery Voltage={battery_voltage:.1f}, Follow Mode={follow_mode}, Terminator={terminator}")
except (OSError, struct.error) as e:
# If there is an OSError or an error in unpacking the data, log the error and break the loop
logger.error(f"An error occurred: {e}")
break
# Drones threads
drones_threads = []
# This flag indicates if the telemetry threads should keep running.
# We use a list so the changes in the main thread can be seen by the telemetry threads.
keep_running = [True]
# Dictionary to hold pending commands for each drone
pending_commands = {} # Key: hw_id, Value: {'mission': mission, 'state': state, 'trigger_time': trigger_time, 'retries': 0, 'timestamp': timestamp}
app = Flask(__name__)
CORS(app) # Enable CORS
@app.route('/telemetry', methods=['GET'])
def get_telemetry():
with telemetry_lock:
return jsonify(telemetry_data_all_drones)
@app.route('/send_command', defaults={'drone_ids': 'all'}, methods=['POST'])
@app.route('/send_command/<drone_ids>', methods=['POST'])
def send_command_to_drones(drone_ids):
try:
command_data = request.get_json()
print(request.json) # Debug line
mission_type = command_data['missionType']
trigger_time = int(command_data['triggerTime'])
# Here you can process altitude from the mission code if it's a TAKEOFF command
if mission_type == 10: # Assuming 10 is the code for TAKEOFF
altitude = command_data.get('altitude', 10)
if altitude > 50:
altitude = 50
mission_type += altitude # Add the altitude to the mission_type
mission, state = convert_mission_type(mission_type)
if drone_ids == 'all':
target_drones = [hw_id for _, _, _, _, hw_id, _ in drones_threads]
else:
target_drones = list(map(int, drone_ids.split(',')))
for sock, _, coordinator_ip, debug_port, hw_id, pos_id in drones_threads:
if hw_id in target_drones:
send_command(trigger_time, sock, coordinator_ip, debug_port, hw_id, pos_id, mission, state)
return jsonify({'status': 'success', 'message': f'Command sent to drones {target_drones}'})
except Exception as e:
print(f"An error occurred while sending command: {e}")
return jsonify({'status': 'error', 'message': str(e)})
@app.route('/save-swarm-data', methods=['POST'])
def save_swarm_data():
try:
data = request.json
# Convert the JSON data to CSV format
csv_data = "hw_id,follow,offset_n,offset_e,offset_alt\n"
for drone in data:
csv_data += f"{drone['hw_id']},{drone['follow']},{drone['offset_n']},{drone['offset_e']},{drone['offset_alt']}\n"
# Save to swarm.csv
with open('swarm.csv', 'w') as file:
file.write(csv_data)
return {"message": "Data saved successfully"}, 200
except Exception as e:
return {"message": f"Error: {str(e)}"}, 500
@app.route('/save-config-data', methods=['POST'])
def save_config_data():
data = request.json
try:
# Ensure that all drones have essential properties before writing to CSV
if not all('hw_id' in drone for drone in data):
return jsonify({"message": "Incomplete data received. Every drone must have an 'hw_id'."}), 400
# Specify column order
column_order = ["hw_id", "pos_id", "x", "y", "ip", "mavlink_port", "debug_port", "gcs_ip"]
with open('config.csv', 'w', newline='') as file:
writer = csv.DictWriter(file, fieldnames=column_order)
writer.writeheader()
for drone in data:
writer.writerow({col: str(drone.get(col, "")).strip() for col in column_order})
return jsonify({"message": "Configuration saved successfully!"}), 200
except Exception as e:
return jsonify({"message": "Error saving configuration!", "error": str(e)}), 500
@app.route('/get-swarm-data', methods=['GET'])
def get_swarm_data():
with open('swarm.csv', 'r') as f:
reader = csv.DictReader(f)
data = [row for row in reader]
return jsonify(data)
@app.route('/get-config-data', methods=['GET'])
def get_config_data():
with open('config.csv', 'r') as f:
reader = csv.DictReader(f)
data = [row for row in reader]
return jsonify(data)
ALLOWED_EXTENSIONS = {'zip'}
def allowed_file(filename):
return '.' in filename and \
filename.rsplit('.', 1)[1].lower() in ALLOWED_EXTENSIONS
# Function to clear show directories
def clear_show_directories():
directories = [
'shapes/swarm/skybrush',
'shapes/swarm/processed',
'shapes/swarm/plots'
]
for directory in directories:
print(f"Clearing directory: {directory}") # Debugging line
for filename in os.listdir(directory):
file_path = os.path.join(directory, filename)
try:
if os.path.isfile(file_path) or os.path.islink(file_path):
os.unlink(file_path)
elif os.path.isdir(file_path):
shutil.rmtree(file_path)
except Exception as e:
print(f'Failed to delete {file_path}. Reason: {e}') # Debugging line
# Updated route in Flask
@app.route('/import-show', methods=['POST'])
def import_show():
uploaded_file = request.files.get('file')
if uploaded_file and allowed_file(uploaded_file.filename):
clear_show_directories() # Clear existing files
# Store the uploaded ZIP file temporarily
zip_path = os.path.join('temp', 'uploaded.zip')
uploaded_file.save(zip_path)
# Unzip the file
with zipfile.ZipFile(zip_path, 'r') as zip_ref:
zip_ref.extractall('shapes/swarm/skybrush')
# Remove the temporary ZIP file
os.remove(zip_path)
# Run the processformation.py script
try:
completed_process = subprocess.run(["python3", "process_formation.py"], capture_output=True, text=True, check=True)
print("Have {} bytes in stdout:\n{}".format(len(completed_process.stdout), completed_process.stdout))
except subprocess.CalledProcessError as e:
print(str(e))
return jsonify({'success': False, 'error': 'Error in running processformation.py', 'details': str(e)})
return jsonify({'success': True})
else:
return jsonify({'success': False, 'error': 'Invalid file type. Please upload a ZIP file.'})
@app.route('/get-show-plots/<filename>')
def send_image(filename):
print("Trying to serve:", filename)
print("From directory:", os.path.abspath('shapes/swarm/plots'))
return send_from_directory('shapes/swarm/plots', filename)
@app.route('/get-show-plots', methods=['GET'])
def get_show_plots():
plots_directory = 'shapes/swarm/plots'
filenames = [f for f in os.listdir(plots_directory) if f.endswith('.png')]
# Check if 'all_drones.png' is in filenames
if 'all_drones.png' in filenames:
upload_time = time.ctime(os.path.getctime(os.path.join(plots_directory, 'all_drones.png')))
else:
upload_time = "unknown"
return jsonify({'filenames': filenames, 'uploadTime': upload_time})
@app.route('/get-first-last-row/<string:hw_id>', methods=['GET'])
def get_first_last_row(hw_id):
try:
# Construct the full path to the drone's CSV file
csv_path = os.path.join("shapes", "swarm", "skybrush", f"Drone {hw_id}.csv")
# Read the CSV file into a DataFrame
df = pd.read_csv(csv_path)
# Get the first and last row
first_row = df.iloc[0]
last_row = df.iloc[-1]
# Extract the x, y coordinates
first_x = first_row['x [m]']
first_y = first_row['y [m]']
last_x = last_row['x [m]']
last_y = last_row['y [m]']
return jsonify({
"success": True,
"firstRow": {"x": first_x, "y": first_y},
"lastRow": {"x": last_x, "y": last_y}
})
except Exception as e:
return jsonify({"success": False, "error": str(e)})
# Function to convert mission type to mission and state values
def convert_mission_type(mission_type):
if isinstance(mission_type, str):
if mission_type == 's':
return 2, 1 # Smart Swarm
elif mission_type == 'd':
return 1, 1 # Drone Show
elif mission_type == 'n':
return 0, 0 # Cancel Mission/Disarm
else:
return 0, 0 # Invalid command
elif isinstance(mission_type, int):
if 10 <= mission_type <= 60: # Takeoff to specific altitude
return mission_type, 1
elif mission_type == 101: # Land
return mission_type, 1
elif mission_type == 102: # Hold Position
return mission_type, 1
elif mission_type == 100: # Test
return mission_type, 1
else:
return 0, 0 # Invalid command
else:
return 0, 0 # Invalid command
def run_flask():
# Start the retry thread
retry_thread = Thread(target=retry_pending_commands)
retry_thread.start()
app.run(host='0.0.0.0', port=flask_telem_socket_port)
flask_thread = Thread(target=run_flask)
flask_thread.daemon = True
flask_thread.start()
try:
for drone_config in drones:
# Extract variables
if sim_mode:
coordinator_ip = '172.22.141.34' # WSL IP
else:
coordinator_ip = drone_config['ip']
debug_port = int(drone_config['debug_port']) # Debug port
gcs_ip = drone_config['gcs_ip'] # GCS IP
hw_id = drone_config['hw_id'] # Hardware ID
pos_id = drone_config['pos_id'] # Position ID
# Log information
logger.info(f"Drone {hw_id} is listening and sending on IP {coordinator_ip} and port {debug_port}")
# Socket for communication
sock = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
sock.bind(('0.0.0.0', debug_port))
# This flag controls whether telemetry is printed to the screen.
# We use a list so the changes in the main thread can be seen by the telemetry threads.
print_telemetry = [True]
# Start the telemetry thread
telemetry_thread = Thread(target=handle_telemetry, args=(keep_running, print_telemetry, sock))
telemetry_thread.daemon = True # Set the thread as a daemon thread
telemetry_thread.start()
# Add to the drones_threads
drones_threads.append((sock, telemetry_thread, coordinator_ip, debug_port, hw_id, pos_id))
# Main loop for command input
# Removed the command line since it is not needed anymore since we have GUI. if you want to reactivate it remmeber in SSH when mulitple termials open there might be some problem
mission = 0
state = 0
n = 0
#Removed the commandline input becuase it is no longer needed since we have a GUI. if you need that make sure you take care of auto linux startup since it might have problem when multiple terminal opens in one termina in one SSH. you might need to pass 'g' to startup
while True:
pass
# while True:
# command = input("\n Enter 's' for swarm, 'c' for csv_droneshow, 'n' for none, 'q' to quit: \n")
# if command.lower() == 'q':
# break
# elif command.lower() == 's':
# mission = 2 # Setting mission to smart_swarm
# n = input("\n Enter the number of seconds for the trigger time (or '0' to cancel): \n")
# if int(n) == 0:
# continue
# state = 1
# elif command.lower() == 'c':
# mission = 1 # Setting mission to csv_droneshow
# n = input("\n Enter the number of seconds for the trigger time (or '0' to cancel): \n")
# if int(n) == 0:
# continue
# state = 1
# elif command.lower() == 'n':
# mission = 0 # Unsetting the mission
# state = 0
# n = 0 # Unsetting the trigger time
# else:
# logger.warning("Invalid command.")
# continue
# # Turn off telemetry printing while sending commands
# for _, _, _, _, _, _ in drones_threads:
# print_telemetry[0] = False
# # Send command to each drone
# for sock, _, coordinator_ip, debug_port, hw_id, pos_id in drones_threads:
# trigger_time = int(time.time()) + int(n) # Now + n seconds
# send_command(trigger_time, sock, coordinator_ip, debug_port, hw_id, pos_id, mission, state)
# # Turn on telemetry printing after sending commands
# for _, _, _, _, _, _ in drones_threads:
# print_telemetry[0] = True
except (ValueError, OSError, KeyboardInterrupt) as e:
# Catch any exceptions that occur during the execution
logger.error(f"An error occurred: {e}")
finally:
# When KeyboardInterrupt happens or an error occurs, stop the telemetry threads
# keep_running[0] = False
# for sock, telemetry_thread, _, _, _, _ in drones_threads:
# # Close the socket
# sock.close()
# # Join the thread
# telemetry_thread.join()
# # Join the Flask thread
# flask_thread.join()
pass
logger.info("Exiting the application...")