73
73
gi .require_version ("Gst" , "1.0" )
74
74
from gi .repository import Gst
75
75
76
+ # TODO: move update rate constants to CLI options
77
+ MAIN_LOOP_RATE = 30.0
78
+ GIMBAL_CONTROL_LOOP_RATE = 30.0
79
+ CAMERA_SEND_IMAGE_STATUS_RATE = 5.0
80
+ MAVLINK_RECV_RATE = 1000.0
81
+
76
82
77
83
class CameraCapFlags (Enum ):
78
84
"""
@@ -259,7 +265,7 @@ def _mavlink_recv_task(self):
259
265
"""
260
266
Task to receive a mavlink message and forwward to controllers.
261
267
"""
262
- update_rate = 1000.0 # Hz
268
+ update_rate = MAVLINK_RECV_RATE # Hz
263
269
update_period = 1.0 / update_rate
264
270
265
271
while True :
@@ -281,14 +287,6 @@ def __process_message():
281
287
sleep_time = max (0.0 , update_period - elapsed_time )
282
288
time .sleep (sleep_time )
283
289
284
- def _create_tracker (self , name ):
285
- if name == "CSTR" :
286
- return TrackerCSTR ()
287
- elif name == "KCF" :
288
- return TrackerKCF ()
289
- else :
290
- raise Exception (f"Invalid tracker name: { name } " )
291
-
292
290
def run (self ):
293
291
"""
294
292
Run the onboard controller.
@@ -334,12 +332,12 @@ def run(self):
334
332
335
333
# Create tracker
336
334
print (f"Using tracker: { self ._tracker_name } " )
337
- tracker = self . _create_tracker (self ._tracker_name )
335
+ tracker = TrackerFactory . create_tracker (self ._tracker_name )
338
336
tracking_rect = None
339
337
tracking_rect_changed = True
340
338
341
339
# TODO: how to ensure consistency of frame updates with GCS?
342
- update_rate = 50.0 # Hz
340
+ update_rate = MAIN_LOOP_RATE # Hz
343
341
update_period = 1.0 / update_rate
344
342
345
343
# TODO: consolidate common code - also used in GUI
@@ -890,7 +888,7 @@ def _mavlink_task(self):
890
888
sysid = self ._sysid
891
889
cmpid = self ._cmpid
892
890
893
- update_rate = 1000.0 # Hz
891
+ update_rate = MAVLINK_RECV_RATE # Hz
894
892
update_period = 1.0 / update_rate
895
893
896
894
while True :
@@ -927,7 +925,7 @@ def _send_status_task(self):
927
925
# TODO: stop sending image status when tracking stopped
928
926
# TODO: set streaming rate using MAV_CMD_SET_MESSAGE_INTERVAL
929
927
930
- update_rate = 20.0 # Hz
928
+ update_rate = CAMERA_SEND_IMAGE_STATUS_RATE # Hz
931
929
update_period = 1.0 / update_rate
932
930
933
931
while True :
@@ -977,9 +975,9 @@ def __init__(self, connection, enable_graphs=False):
977
975
978
976
# Pitch controller for centring gimbal
979
977
self ._pit_controller = AC_PID_Basic (
980
- initial_p = 2 .0 ,
981
- initial_i = 0.0 ,
982
- initial_d = 0.0 ,
978
+ initial_p = 1 .0 ,
979
+ initial_i = 0.01 ,
980
+ initial_d = 0.01 ,
983
981
initial_ff = 0.0 ,
984
982
initial_imax = 1.0 ,
985
983
initial_filt_E_hz = 0.0 ,
@@ -988,9 +986,9 @@ def __init__(self, connection, enable_graphs=False):
988
986
989
987
# Yaw controller for centring gimbal
990
988
self ._yaw_controller = AC_PID_Basic (
991
- initial_p = 2 .0 ,
992
- initial_i = 0.0 ,
993
- initial_d = 0.0 ,
989
+ initial_p = 1 .0 ,
990
+ initial_i = 0.01 ,
991
+ initial_d = 0.01 ,
994
992
initial_ff = 0.0 ,
995
993
initial_imax = 1.0 ,
996
994
initial_filt_E_hz = 0.0 ,
@@ -999,9 +997,9 @@ def __init__(self, connection, enable_graphs=False):
999
997
1000
998
# Gimbal pitch controller for tracking
1001
999
self ._pit_track_controller = AC_PID_Basic (
1002
- initial_p = 2 .0 ,
1003
- initial_i = 0.2 ,
1004
- initial_d = 0.01 ,
1000
+ initial_p = 1 .0 ,
1001
+ initial_i = 0.01 ,
1002
+ initial_d = 0.02 ,
1005
1003
initial_ff = 0.0 ,
1006
1004
initial_imax = 1.0 ,
1007
1005
initial_filt_E_hz = 0.0 ,
@@ -1010,9 +1008,9 @@ def __init__(self, connection, enable_graphs=False):
1010
1008
1011
1009
# Gimbal yaw controller for tracking
1012
1010
self ._yaw_track_controller = AC_PID_Basic (
1013
- initial_p = 2 .0 ,
1014
- initial_i = 0.2 ,
1015
- initial_d = 0.01 ,
1011
+ initial_p = 1 .0 ,
1012
+ initial_i = 0.01 ,
1013
+ initial_d = 0.02 ,
1016
1014
initial_ff = 0.0 ,
1017
1015
initial_imax = 1.0 ,
1018
1016
initial_filt_E_hz = 0.0 ,
@@ -1057,7 +1055,7 @@ def reset(self):
1057
1055
def mavlink_packet (self , msg ):
1058
1056
self ._control_in_queue .put (msg )
1059
1057
1060
- def _send_gimbal_manager_pitch_yaw_angles (self , pitch , yaw , pitch_rate , yaw_rate ):
1058
+ def _send_gimbal_manager_pitch_yaw_angle (self , pitch , yaw ):
1061
1059
"""
1062
1060
Send a mavlink message to set the gimbal pitch and yaw (radians).
1063
1061
"""
@@ -1068,6 +1066,22 @@ def _send_gimbal_manager_pitch_yaw_angles(self, pitch, yaw, pitch_rate, yaw_rate
1068
1066
0 ,
1069
1067
pitch ,
1070
1068
yaw ,
1069
+ float ("nan" ),
1070
+ float ("nan" ),
1071
+ )
1072
+ self ._connection .mav .send (msg )
1073
+
1074
+ def _send_gimbal_manager_pitch_yaw_rate (self , pitch_rate , yaw_rate ):
1075
+ """
1076
+ Send a mavlink message to set the gimbal pitch and yaw (radians).
1077
+ """
1078
+ msg = self ._connection .mav .gimbal_manager_set_pitchyaw_encode (
1079
+ self ._connection .target_system ,
1080
+ self ._connection .target_component ,
1081
+ 0 ,
1082
+ 0 ,
1083
+ float ("nan" ),
1084
+ float ("nan" ),
1071
1085
pitch_rate ,
1072
1086
yaw_rate ,
1073
1087
)
@@ -1082,6 +1096,9 @@ def _control_task(self):
1082
1096
1083
1097
When not tracking, return the gimbal to its neutral position.
1084
1098
"""
1099
+ update_rate = GIMBAL_CONTROL_LOOP_RATE
1100
+ update_period = 1.0 / update_rate
1101
+
1085
1102
if self ._enable_graphs :
1086
1103
self ._add_livegraphs ()
1087
1104
@@ -1139,12 +1156,11 @@ def _control_task(self):
1139
1156
# f"Out: {yaw_pid_info.out:.2f}"
1140
1157
# )
1141
1158
1142
- self ._send_gimbal_manager_pitch_yaw_angles (
1143
- float ("nan" ),
1144
- float ("nan" ),
1145
- pit_rate_rads ,
1146
- yaw_rate_rads ,
1147
- )
1159
+ # NOTE: Set pitch and yaw rates to help determine PID gains for tracking
1160
+ self ._send_gimbal_manager_pitch_yaw_rate (pit_rate_rads , yaw_rate_rads )
1161
+
1162
+ # NOTE: Set pitch and yaw angles directly (no PID controller needed)
1163
+ # self._send_gimbal_manager_pitch_yaw_angle(pit_tgt_rad, yaw_tgt_rad)
1148
1164
1149
1165
if self ._enable_graphs :
1150
1166
self ._update_livegraphs (pit_pid_info , yaw_pid_info )
@@ -1167,18 +1183,11 @@ def _control_task(self):
1167
1183
pit_pid_info = self ._pit_track_controller .pid_info
1168
1184
yaw_pid_info = self ._yaw_track_controller .pid_info
1169
1185
1170
- self ._send_gimbal_manager_pitch_yaw_angles (
1171
- float ("nan" ),
1172
- float ("nan" ),
1173
- pit_rate_rads ,
1174
- yaw_rate_rads ,
1175
- )
1186
+ self ._send_gimbal_manager_pitch_yaw_rate (pit_rate_rads , yaw_rate_rads )
1176
1187
1177
1188
if self ._enable_graphs :
1178
1189
self ._update_livegraphs (pit_pid_info , yaw_pid_info )
1179
1190
1180
- # Update at 50Hz
1181
- update_period = 0.02
1182
1191
elapsed_time = time .time () - start_time
1183
1192
sleep_time = max (0.0 , update_period - elapsed_time )
1184
1193
time .sleep (sleep_time )
@@ -1187,7 +1196,7 @@ def _mavlink_task(self):
1187
1196
"""
1188
1197
Process mavlink messages relevant to gimbal management.
1189
1198
"""
1190
- update_rate = 1000.0
1199
+ update_rate = MAVLINK_RECV_RATE
1191
1200
update_period = 1.0 / update_rate
1192
1201
1193
1202
while True :
@@ -1335,6 +1344,22 @@ def _create(self):
1335
1344
return cv2 .legacy .TrackerKCF_create ()
1336
1345
1337
1346
1347
+ class TrackerFactory :
1348
+
1349
+ @staticmethod
1350
+ def choices ():
1351
+ return ["CSTR" , "KCF" ]
1352
+
1353
+ @staticmethod
1354
+ def create_tracker (name ):
1355
+ if name == "CSTR" :
1356
+ return TrackerCSTR ()
1357
+ elif name == "KCF" :
1358
+ return TrackerKCF ()
1359
+ else :
1360
+ raise Exception (f"Invalid tracker name: { name } " )
1361
+
1362
+
1338
1363
if __name__ == "__main__" :
1339
1364
import os
1340
1365
import sys
@@ -1352,7 +1377,13 @@ def _create(self):
1352
1377
type = int ,
1353
1378
help = "source component id" ,
1354
1379
)
1355
- parser .add_argument ("--tracker-name" , default = "CSTR" , type = str , help = "tracker name" )
1380
+ parser .add_argument (
1381
+ "--tracker-name" ,
1382
+ choices = TrackerFactory .choices (),
1383
+ default = "CSTR" ,
1384
+ type = str ,
1385
+ help = "tracker name" ,
1386
+ )
1356
1387
parser .add_argument (
1357
1388
"--enable-graphs" ,
1358
1389
action = "store_const" ,
0 commit comments