Skip to content

Commit 46df94d

Browse files
committed
autotest: add test for MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET
1 parent 9878881 commit 46df94d

File tree

4 files changed

+189
-41
lines changed

4 files changed

+189
-41
lines changed

Tools/autotest/arducopter.py

Lines changed: 84 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -4887,6 +4887,62 @@ def ManualThrottleModeChange(self):
48874887
self.run_cmd_do_set_mode("ACRO")
48884888
self.wait_disarmed()
48894889

4890+
def MountWPNextOffsetMission(self, target_system=1, target_component=1):
4891+
'''check the MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET mission item'''
4892+
# setup mount parameters
4893+
self.setup_servo_mount()
4894+
self.reboot_sitl() # to handle MNT_TYPE changing
4895+
4896+
alt = 50
4897+
4898+
loc = self.mav.location()
4899+
4900+
items = [
4901+
self.mission_item_home(),
4902+
self.mission_item_copter_takeoff(alt=50),
4903+
]
4904+
4905+
# third waypoint
4906+
loc = self.offset_location_ne(loc, 100, 0)
4907+
items.append(self.mission_item_do_cmd_roi_set_wpnext_offset(p=0))
4908+
items.append(self.mission_item_waypoint(loc.lat, loc.lng, alt))
4909+
4910+
# third waypoint
4911+
loc = self.offset_location_ne(loc, 100, 0)
4912+
items.append(self.mission_item_do_cmd_roi_set_wpnext_offset(p=-45))
4913+
items.append(self.mission_item_waypoint(loc.lat, loc.lng, alt))
4914+
4915+
# fourth waypoint (offset from second)
4916+
loc = self.offset_location_ne(loc, 100, 0)
4917+
items.append(self.mission_item_do_cmd_roi_set_wpnext_offset(y=45))
4918+
items.append(self.mission_item_waypoint(loc.lat, loc.lng, alt))
4919+
4920+
# now RTL
4921+
items.append(self.mission_item_rtl())
4922+
4923+
self.renumber_mission_items(items)
4924+
self.check_mission_upload_download(items)
4925+
4926+
self.set_parameter('AUTO_OPTIONS', 3)
4927+
self.wait_ready_to_arm()
4928+
self.arm_vehicle()
4929+
self.change_mode('AUTO')
4930+
4931+
self.wait_current_waypoint(3)
4932+
# the 30 here is because the vehicle is pitching down and the
4933+
# gimbal is compensating
4934+
self.wait_mount_roll_pitch_yaw_deg(r=0, p=30, y=0)
4935+
4936+
self.wait_current_waypoint(5)
4937+
# the -15 here is because the vehicle is pitching down and the
4938+
# gimbal is compensating, and is being asked to pitch down 45 degrees
4939+
self.wait_mount_roll_pitch_yaw_deg(r=0, p=-15, y=0)
4940+
4941+
self.wait_current_waypoint(7)
4942+
self.wait_mount_roll_pitch_yaw_deg(y=45)
4943+
4944+
self.wait_disarmed()
4945+
48904946
def test_mount_pitch(self, despitch, despitch_tolerance, mount_mode, timeout=10, hold=0):
48914947
tstart = self.get_sim_time()
48924948
success_start = 0
@@ -4949,11 +5005,33 @@ def setup_servo_mount(self, roll_servo=5, pitch_servo=6, yaw_servo=7):
49495005
"SERVO%u_FUNCTION" % yaw_servo: 6, # yaw
49505006
})
49515007

5008+
# FIXME: change this to use wait_and_maintain
5009+
def wait_mount_roll_pitch_yaw_deg(self, r=None, p=None, y=None, timeout=20):
5010+
tstart = self.get_sim_time()
5011+
while True:
5012+
if self.get_sim_time_cached() - tstart > timeout:
5013+
raise NotAchievedException("Did not get rpy")
5014+
got_r, got_p, got_y = self.get_mount_roll_pitch_yaw_deg()
5015+
self.progress("want=(%s, %s, %s)" % (r, p , y))
5016+
self.progress("got=(%s, %s, %s)" % (got_r, got_p , got_y))
5017+
passed = True
5018+
for (want, got) in [(r, got_r), (p, got_p), (y, got_y)]:
5019+
if want is None:
5020+
continue
5021+
if abs(want - got) > 5:
5022+
passed = False
5023+
break
5024+
if passed:
5025+
self.progress("achieved mount rpy")
5026+
break
5027+
49525028
def get_mount_roll_pitch_yaw_deg(self):
4953-
'''return mount (aka gimbal) roll, pitch and yaw angles in degrees'''
5029+
'''return mount (aka gimbal) roll, pitch and yaw angles in degrees - in body frame'''
49545030
# wait for gimbal attitude message
49555031
m = self.assert_receive_message('GIMBAL_DEVICE_ATTITUDE_STATUS', timeout=5)
5032+
return self.eulers_in_degrees_from_GIMBAL_DEVICE_ATTITUDE_STATUS(m)
49565033

5034+
def eulers_in_degrees_from_GIMBAL_DEVICE_ATTITUDE_STATUS(self, m):
49575035
# convert quaternion to euler angles and return
49585036
q = quaternion.Quaternion(m.q)
49595037
euler = q.euler
@@ -5065,6 +5143,7 @@ def test_mount_rc_targetting(self):
50655143

50665144
def Mount(self):
50675145
'''Test Camera/Antenna Mount'''
5146+
50685147
ex = None
50695148
self.context_push()
50705149
old_srcSystem = self.mav.mav.srcSystem
@@ -5328,6 +5407,9 @@ def Mount(self):
53285407
self.set_mount_mode(mavutil.mavlink.MAV_MOUNT_MODE_NEUTRAL)
53295408
self.test_mount_pitch(0, 0.1, mavutil.mavlink.MAV_MOUNT_MODE_NEUTRAL)
53305409

5410+
self.start_subtest("Testing MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET")
5411+
self.test_mount_mav_cmd_do_set_roi_wpnext_offset_mission()
5412+
53315413
except Exception as e:
53325414
self.print_exception_caught(e)
53335415
ex = e
@@ -9975,6 +10057,7 @@ def tests1e(self):
997510057
self.MountYawVehicleForMountROI,
997610058
self.MAV_CMD_DO_MOUNT_CONTROL,
997710059
self.MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE,
10060+
self.MountWPNextOffsetMission,
997810061
self.Button,
997910062
self.ShipTakeoff,
998010063
self.RangeFinder,

Tools/autotest/common.py

Lines changed: 101 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -3764,6 +3764,107 @@ def create_simple_relhome_mission(self, items_in, target_system=1, target_compon
37643764

37653765
return ret
37663766

3767+
def renumber_mission_items(self, items):
3768+
'''make item's seq sequential starting from zero'''
3769+
count = 0
3770+
for item in items:
3771+
item.seq = count
3772+
count += 1
3773+
3774+
def mission_item_copter_takeoff(self, alt=30, target_system=1, target_component=1):
3775+
'''returns a mission_item_int which can be used as takeoff in a mission'''
3776+
return self.mav.mav.mission_item_int_encode(
3777+
target_system,
3778+
target_component,
3779+
1, # seq
3780+
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
3781+
mavutil.mavlink.MAV_CMD_NAV_TAKEOFF,
3782+
0, # current
3783+
0, # autocontinue
3784+
0, # p1
3785+
0, # p2
3786+
0, # p3
3787+
0, # p4
3788+
int(1.0000 * 1e7), # latitude
3789+
int(1.0000 * 1e7), # longitude
3790+
alt, # altitude
3791+
mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
3792+
3793+
def mission_item_rtl(self, target_system=1, target_component=1):
3794+
'''returns a mission_item_int which can be used as RTL in a mission'''
3795+
return self.mav.mav.mission_item_int_encode(
3796+
target_system,
3797+
target_component,
3798+
1, # seq
3799+
mavutil.mavlink.MAV_FRAME_GLOBAL,
3800+
mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH,
3801+
0, # current
3802+
0, # autocontinue
3803+
0, # p1
3804+
0, # p2
3805+
0, # p3
3806+
0, # p4
3807+
0, # latitude
3808+
0, # longitude
3809+
0.0000, # altitude
3810+
mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
3811+
3812+
def mission_item_do_cmd_roi_set_wpnext_offset(self, r=0, p=0, y=0, target_system=1, target_component=1):
3813+
return self.mav.mav.mission_item_encode(
3814+
target_system,
3815+
target_component,
3816+
0, # seq
3817+
mavutil.mavlink.MAV_FRAME_GLOBAL,
3818+
mavutil.mavlink.MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET,
3819+
0, # current
3820+
0, # autocontinue
3821+
0, # param1
3822+
0, # param2
3823+
0, # param3
3824+
0, # param4
3825+
r, # param5
3826+
p, # param6
3827+
y # param7
3828+
)
3829+
3830+
def mission_item_waypoint(self, lat, lng, alt, target_system=1, target_component=1):
3831+
'''returns a mission_item_int which can be used as waypoint in a mission'''
3832+
return self.mav.mav.mission_item_int_encode(
3833+
target_system,
3834+
target_component,
3835+
0, # seq
3836+
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
3837+
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
3838+
0, # current
3839+
0, # autocontinue
3840+
0, # p1
3841+
0, # p2
3842+
0, # p3
3843+
0, # p4
3844+
int(lat*1e7), # latitude
3845+
int(lng*1e7), # longitude
3846+
alt, # altitude
3847+
mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
3848+
3849+
def mission_item_home(self, target_system=1, target_component=1):
3850+
'''returns a mission_item_int which can be used as home in a mission'''
3851+
return self.mav.mav.mission_item_int_encode(
3852+
target_system,
3853+
target_component,
3854+
0, # seq
3855+
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
3856+
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
3857+
0, # current
3858+
0, # autocontinue
3859+
3, # p1
3860+
0, # p2
3861+
0, # p3
3862+
0, # p4
3863+
int(1.0000 * 1e7), # latitude
3864+
int(2.0000 * 1e7), # longitude
3865+
31.0000, # altitude
3866+
mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
3867+
37673868
def upload_simple_relhome_mission(self, items, target_system=1, target_component=1):
37683869
mission = self.create_simple_relhome_mission(
37693870
items,

Tools/autotest/helicopter.py

Lines changed: 2 additions & 40 deletions
Original file line numberDiff line numberDiff line change
@@ -436,44 +436,6 @@ def ManAutoRotation(self, timeout=600):
436436
self.wait_servo_channel_value(8, 1000, timeout=3)
437437
self.wait_disarmed()
438438

439-
def mission_item_home(self, target_system, target_component):
440-
'''returns a mission_item_int which can be used as home in a mission'''
441-
return self.mav.mav.mission_item_int_encode(
442-
target_system,
443-
target_component,
444-
0, # seq
445-
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
446-
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
447-
0, # current
448-
0, # autocontinue
449-
3, # p1
450-
0, # p2
451-
0, # p3
452-
0, # p4
453-
int(1.0000 * 1e7), # latitude
454-
int(2.0000 * 1e7), # longitude
455-
31.0000, # altitude
456-
mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
457-
458-
def mission_item_takeoff(self, target_system, target_component):
459-
'''returns a mission_item_int which can be used as takeoff in a mission'''
460-
return self.mav.mav.mission_item_int_encode(
461-
target_system,
462-
target_component,
463-
1, # seq
464-
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
465-
mavutil.mavlink.MAV_CMD_NAV_TAKEOFF,
466-
0, # current
467-
0, # autocontinue
468-
0, # p1
469-
0, # p2
470-
0, # p3
471-
0, # p4
472-
int(1.0000 * 1e7), # latitude
473-
int(1.0000 * 1e7), # longitude
474-
31.0000, # altitude
475-
mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
476-
477439
def mission_item_rtl(self, target_system, target_component):
478440
'''returns a mission_item_int which can be used as takeoff in a mission'''
479441
return self.mav.mav.mission_item_int_encode(
@@ -545,7 +507,7 @@ def scurve_nasty_mission(self, target_system=1, target_component=1):
545507
# slot 0 is home
546508
self.mission_item_home(target_system=target_system, target_component=target_component),
547509
# slot 1 is takeoff
548-
self.mission_item_takeoff(target_system=target_system, target_component=target_component),
510+
self.mission_item_copter_takeoff(target_system=target_system, target_component=target_component),
549511
# now three spline waypoints right on top of one another:
550512
copy.copy(wp2_by_three),
551513
copy.copy(wp2_by_three),
@@ -619,7 +581,7 @@ def scurve_nasty_up_mission(self, target_system=1, target_component=1):
619581
# slot 0 is home
620582
self.mission_item_home(target_system=target_system, target_component=target_component),
621583
# slot 1 is takeoff
622-
self.mission_item_takeoff(target_system=target_system, target_component=target_component),
584+
self.mission_item_copter_takeoff(target_system=target_system, target_component=target_component),
623585
wp2,
624586
wp3,
625587
wp4,

libraries/AP_Mount/AP_Mount.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -537,6 +537,8 @@ MAV_RESULT AP_Mount::handle_command(const mavlink_command_int_t &packet, const m
537537
return handle_command_do_set_roi_sysid(packet);
538538
case MAV_CMD_DO_SET_ROI_NONE:
539539
return handle_command_do_set_roi_none();
540+
case MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET:
541+
return handle_command_do_set_roi_wpnext_offset(packet);
540542
default:
541543
return MAV_RESULT_UNSUPPORTED;
542544
}

0 commit comments

Comments
 (0)