Skip to content

Commit 04e97bb

Browse files
committed
camtrack: intial tune of status rates and pid gains
- Reduce image status rate to 20 Hz - Set response_target in set message interval to flight-stack default - Add debug info for image status / tracker_pos - onboard_controller: apply formatter - onboard_controller: adjust controller gains Signed-off-by: Rhys Mainwaring <[email protected]>
1 parent f134a8a commit 04e97bb

File tree

3 files changed

+26
-12
lines changed

3 files changed

+26
-12
lines changed

MAVProxy/modules/mavproxy_camtrack/__init__.py

+5-4
Original file line numberDiff line numberDiff line change
@@ -57,7 +57,7 @@ def __init__(self, mpstate):
5757
# SIYI A8 camera
5858
# rtsp_url = "rtsp://192.168.144.25:8554/main.264"
5959

60-
self._camera_tracking_image_status_rate = 50 # Hz
60+
self._camera_tracking_image_status_rate = 20 # Hz
6161

6262
# GUI
6363
self.camera_view = CameraView(self.mpstate, "Camera Tracking", rtsp_url)
@@ -328,7 +328,7 @@ def send_messages(self):
328328
self.send_set_message_interval_message(
329329
mavutil.mavlink.MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS,
330330
interval_us, # requested interval in microseconds
331-
response_target=1, # flight-stack default
331+
response_target=0, # flight-stack default
332332
)
333333
self._do_request_camera_tracking_image_status = False
334334

@@ -369,9 +369,9 @@ def send_request_message(self, message_id, p1=0):
369369
)
370370

371371
def send_set_message_interval_message(
372-
self, message_id, interval_us, response_target=1
372+
self, message_id, interval_us, response_target=0
373373
):
374-
self.master.mav.command_long_send(
374+
msg = self.master.mav.command_long_encode(
375375
self.settings.target_system, # target_system
376376
self.settings.target_component, # target_component
377377
mavutil.mavlink.MAV_CMD_SET_MESSAGE_INTERVAL, # command
@@ -384,6 +384,7 @@ def send_set_message_interval_message(
384384
0, # param6
385385
response_target, # param7
386386
)
387+
self.master.mav.send(msg)
387388

388389
def idle_task(self):
389390
"""Idle tasks"""

MAVProxy/modules/mavproxy_camtrack/onboard_controller.py

+14-8
Original file line numberDiff line numberDiff line change
@@ -697,6 +697,12 @@ def _send_camera_tracking_image_status(self):
697697
rec_bottom_x,
698698
rec_bottom_y,
699699
)
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+
# )
700706
self._connection.mav.send(msg)
701707

702708
def _handle_camera_track_point(self, msg):
@@ -806,7 +812,7 @@ class GimbalController:
806812

807813
def __init__(self, connection):
808814
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
810816
self._cmpid = 1 # component id matches autopilot
811817

812818
print(f"Gimbal Controller: src_sys: {self._sysid}, src_cmp: {self._cmpid})")
@@ -831,8 +837,8 @@ def __init__(self, connection):
831837
self._gimbal_failure_flags = None
832838

833839
# 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)
836842

837843
# Start the control thread
838844
self._control_in_queue = queue.Queue()
@@ -911,8 +917,8 @@ def _control_task(self):
911917
# the current mount orientation.
912918
_, ay, az = euler.quat2euler(gimbal_orientation)
913919

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
916922

917923
err_pitch = self._neutral_y - ay
918924
pitch_rate_rads = self._pitch_controller.run(err_pitch)
@@ -937,8 +943,8 @@ def _control_task(self):
937943
err_x = act_x - tgt_x
938944
err_y = -(act_y - tgt_y)
939945

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
942948

943949
err_pitch = math.radians(err_y)
944950
pitch_rate_rads = self._pitch_controller.run(err_pitch)
@@ -993,7 +999,7 @@ class PI_controller:
993999
MAVProxy/modules/mavproxy_SIYI/PI_controller (modified)
9941000
"""
9951001

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)):
9971003
self.Pgain = Pgain
9981004
self.Igain = Igain
9991005
self.IMAX = IMAX

MAVProxy/modules/mavproxy_camtrack/tracker_image.py

+7
Original file line numberDiff line numberDiff line change
@@ -279,6 +279,13 @@ def get_position(self):
279279

280280
def set_position(self, tracker_pos):
281281
self._tracker_pos = tracker_pos
282+
# NOTE: leave for debugging
283+
# print(
284+
# f"tracker_pos: x: {self._tracker_pos.left():.2f}, "
285+
# f"y: {self._tracker_pos.top():.2f}, "
286+
# f"w: {(self._tracker_pos.right() - self._tracker_pos.left()):.2f}, "
287+
# f"h: {(self._tracker_pos.bottom() - self._tracker_pos.top()):.2f}"
288+
# )
282289

283290

284291
def create_tracker(name, state):

0 commit comments

Comments
 (0)