@@ -25,7 +25,7 @@ def object_detection_loop(camera: CameraInterface, model: ModelInterface, args):
2525 "--out" ,
2626 args .output ,
2727 "--out" ,
28- "udpout:127 .0.0.1 :14550" ,
28+ "udpout:0 .0.0.0 :14550" ,
2929 "--baudrate" ,
3030 str (args .baud ),
3131 ],
@@ -53,7 +53,7 @@ def object_detection_loop(camera: CameraInterface, model: ModelInterface, args):
5353 print ("MAVProxy process terminated unexpectedly." )
5454 break
5555
56- stream = Stream ("picam" , size = ( 640 , 640 ), fps = 3 , quality = 100 )
56+ stream = Stream ("picam" , fps = 1 )
5757 server = MjpegServer ("0.0.0.0" , 8080 )
5858 server .add_stream (stream )
5959 server .start ()
@@ -103,35 +103,6 @@ def run_object_detection(
103103
104104 no_person_detected = all (res .name != "person" for res in results )
105105
106- # Only run this code if a MAVLink connection exists
107- if master :
108- msg = master .recv_match (
109- type = "HEARTBEAT" , blocking = True
110- ) # pulls heartbeat message
111- mode = mavutil .mode_string_v10 (msg ) # pulls flight mode from heartbeat message
112- # print(f"Current flight mode: {mode}")
113-
114- if no_person_detected :
115- if mode != "LOITER" :
116- # print("✅ No person detected") removed so this is not constantly printed, is return the correct thing to put next?
117- return
118-
119- else : # meaning the drone is currently in loiter mode
120- print ("✅ No person detected" )
121- # change mode to auto because no person detected
122- master .mav .set_mode_send (master .target_system , mavutil .mavlink .MAV_MODE_FLAG_CUSTOM_MODE_ENABLED , master .mode_mapping ()['AUTO' ])
123-
124- else : # person is detected
125- if mode != "LOITER" :
126- print ("🚨 Human detected! Halting drone for 5 seconds... 🚨" )
127- # change mode to loiter because person detected
128- master .mav .set_mode_send (master .target_system , mavutil .mavlink .MAV_MODE_FLAG_CUSTOM_MODE_ENABLED , master .mode_mapping ()['LOITER' ])
129- time .sleep (5 ) # wait 5 seconds
130-
131- else : # drone already in loiter mode
132- print ("🚨 Human detected! Halting drone for 5 seconds... 🚨" )
133- time .sleep (5 ) # wait 5 seconds
134-
135106 # Loop through all results and draw boxes and labels for them
136107 for result in results :
137108 # Detection box
@@ -166,4 +137,34 @@ def run_object_detection(
166137 2 ,
167138 )
168139
140+ # Only run this code if a MAVLink connection exists
141+ if master :
142+ msg = master .recv_match (
143+ type = "HEARTBEAT" , blocking = True
144+ ) # pulls heartbeat message
145+ mode = mavutil .mode_string_v10 (msg ) # pulls flight mode from heartbeat message
146+ # print(f"Current flight mode: {mode}")
147+
148+ if no_person_detected :
149+ if mode != "LOITER" :
150+ # print("✅ No person detected") removed so this is not constantly printed, is return the correct thing to put next?
151+ return image
152+
153+ else : # meaning the drone is currently in loiter mode
154+ print ("✅ No person detected" )
155+ # change mode to auto because no person detected
156+ master .mav .set_mode_send (master .target_system , mavutil .mavlink .MAV_MODE_FLAG_CUSTOM_MODE_ENABLED , master .mode_mapping ()['AUTO' ])
157+
158+ else : # person is detected
159+ if mode != "LOITER" :
160+ print ("🚨 Human detected! Halting drone for 5 seconds... 🚨" )
161+ # change mode to loiter because person detected
162+ master .mav .set_mode_send (master .target_system , mavutil .mavlink .MAV_MODE_FLAG_CUSTOM_MODE_ENABLED , master .mode_mapping ()['LOITER' ])
163+ time .sleep (5 ) # wait 5 seconds
164+
165+ else : # drone already in loiter mode
166+ print ("🚨 Human detected! Halting drone for 5 seconds... 🚨" )
167+ time .sleep (5 ) # wait 5 seconds
168+
169+
169170 return image
0 commit comments