@@ -697,6 +697,12 @@ def _send_camera_tracking_image_status(self):
697
697
rec_bottom_x ,
698
698
rec_bottom_y ,
699
699
)
700
+ # NOTE: leave for debugging
701
+ # print(
702
+ # f"image_status: x: {rec_top_x:.2f}, y: {rec_top_y:.2f}, "
703
+ # f"w: {(rec_bottom_x - rec_top_x):.2f}, "
704
+ # f"h: {(rec_bottom_y - rec_top_y):.2f}"
705
+ # )
700
706
self ._connection .mav .send (msg )
701
707
702
708
def _handle_camera_track_point (self , msg ):
@@ -806,7 +812,7 @@ class GimbalController:
806
812
807
813
def __init__ (self , connection ):
808
814
self ._connection = connection
809
- self ._sysid = self ._connection .source_system # system id matches vehicle
815
+ self ._sysid = self ._connection .source_system # system id matches vehicle
810
816
self ._cmpid = 1 # component id matches autopilot
811
817
812
818
print (f"Gimbal Controller: src_sys: { self ._sysid } , src_cmp: { self ._cmpid } )" )
@@ -831,8 +837,8 @@ def __init__(self, connection):
831
837
self ._gimbal_failure_flags = None
832
838
833
839
# TODO: add options for PI controller gains
834
- self ._pitch_controller = PI_controller (Pgain = 0.1 , Igain = 0.01 , IMAX = 0.1 )
835
- self ._yaw_controller = PI_controller (Pgain = 0.1 , Igain = 0.1 , IMAX = 1.0 )
840
+ self ._pitch_controller = PI_controller (Pgain = 0.1 , Igain = 0.02 , IMAX = 0.3 )
841
+ self ._yaw_controller = PI_controller (Pgain = 0.1 , Igain = 0.02 , IMAX = 0.3 )
836
842
837
843
# Start the control thread
838
844
self ._control_in_queue = queue .Queue ()
@@ -911,8 +917,8 @@ def _control_task(self):
911
917
# the current mount orientation.
912
918
_ , ay , az = euler .quat2euler (gimbal_orientation )
913
919
914
- self ._pitch_controller .gain_mul = 4 .0
915
- self ._yaw_controller .gain_mul = 40 .0
920
+ self ._pitch_controller .gain_mul = 5 .0
921
+ self ._yaw_controller .gain_mul = 5 .0
916
922
917
923
err_pitch = self ._neutral_y - ay
918
924
pitch_rate_rads = self ._pitch_controller .run (err_pitch )
@@ -937,8 +943,8 @@ def _control_task(self):
937
943
err_x = act_x - tgt_x
938
944
err_y = - (act_y - tgt_y )
939
945
940
- self ._pitch_controller .gain_mul = 1.0
941
- self ._yaw_controller .gain_mul = 2.0
946
+ self ._pitch_controller .gain_mul = 0.5
947
+ self ._yaw_controller .gain_mul = 0.5
942
948
943
949
err_pitch = math .radians (err_y )
944
950
pitch_rate_rads = self ._pitch_controller .run (err_pitch )
@@ -993,7 +999,7 @@ class PI_controller:
993
999
MAVProxy/modules/mavproxy_SIYI/PI_controller (modified)
994
1000
"""
995
1001
996
- def __init__ (self , Pgain , Igain , IMAX , gain_mul = 1.0 , max_rate = math .radians (30 .0 )):
1002
+ def __init__ (self , Pgain , Igain , IMAX , gain_mul = 1.0 , max_rate = math .radians (90 .0 )):
997
1003
self .Pgain = Pgain
998
1004
self .Igain = Igain
999
1005
self .IMAX = IMAX
0 commit comments