mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Tools: add support for MAV_CMD_DO_SET_ROI_NONE
This commit is contained in:
parent
f8c2ceced7
commit
7fe547cfce
@ -5084,6 +5084,18 @@ class AutoTestCopter(AutoTest):
|
|||||||
)
|
)
|
||||||
self.test_mount_pitch(-52, 5, mavutil.mavlink.MAV_MOUNT_MODE_GPS_POINT)
|
self.test_mount_pitch(-52, 5, mavutil.mavlink.MAV_MOUNT_MODE_GPS_POINT)
|
||||||
|
|
||||||
|
self.progress("Using MAV_CMD_DO_SET_ROI_NONE")
|
||||||
|
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_ROI_NONE,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
)
|
||||||
|
self.test_mount_pitch(0, 1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING)
|
||||||
|
|
||||||
start = self.mav.location()
|
start = self.mav.location()
|
||||||
(roi_lat, roi_lon) = mavextra.gps_offset(start.lat,
|
(roi_lat, roi_lon) = mavextra.gps_offset(start.lat,
|
||||||
start.lng,
|
start.lng,
|
||||||
|
Loading…
Reference in New Issue
Block a user