mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
autotest: add tests against bad vel/accels in copter guided
This commit is contained in:
parent
aa5a882de8
commit
d4dabeb6fc
@ -9653,6 +9653,7 @@ class AutoTestCopter(AutoTest):
|
||||
self.SetpointGlobalPos,
|
||||
self.ThrowDoubleDrop,
|
||||
self.SetpointGlobalVel,
|
||||
self.SetpointBadVel,
|
||||
self.SplineTerrain,
|
||||
self.TakeoffCheck,
|
||||
])
|
||||
|
@ -10609,6 +10609,78 @@ Also, ignores heartbeats not from our target system'''
|
||||
self.do_RTL(distance_min=0, distance_max=wp_accuracy)
|
||||
self.disarm_vehicle()
|
||||
|
||||
def SetpointBadVel(self, timeout=30):
|
||||
'''try feeding in a very, very bad velocity and make sure it is ignored'''
|
||||
self.takeoff(mode='GUIDED')
|
||||
# following values from a real log:
|
||||
target_speed = Vector3(-3.6019095525029597e+30,
|
||||
1.7796490496925177e-41,
|
||||
3.0557017120313744e-26)
|
||||
|
||||
self.progress("Feeding in bad global data, hoping we don't move")
|
||||
|
||||
def send_speed_vector_global_int(vector , mav_frame):
|
||||
self.mav.mav.set_position_target_global_int_send(
|
||||
0, # timestamp
|
||||
self.sysid_thismav(), # target system_id
|
||||
1, # target component id
|
||||
mav_frame,
|
||||
MAV_POS_TARGET_TYPE_MASK.POS_IGNORE |
|
||||
MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |
|
||||
MAV_POS_TARGET_TYPE_MASK.YAW_IGNORE |
|
||||
MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
vector.x, # vx
|
||||
vector.y, # vy
|
||||
vector.z, # vz
|
||||
0, # afx
|
||||
0, # afy
|
||||
0, # afz
|
||||
0, # yaw
|
||||
0, # yawrate
|
||||
)
|
||||
self.wait_speed_vector(
|
||||
Vector3(0, 0, 0),
|
||||
timeout=timeout,
|
||||
called_function=lambda plop, empty: send_speed_vector_global_int(target_speed, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT), # noqa
|
||||
minimum_duration=10
|
||||
)
|
||||
|
||||
self.progress("Feeding in bad local data, hoping we don't move")
|
||||
|
||||
def send_speed_vector_local_ned(vector , mav_frame):
|
||||
self.mav.mav.set_position_target_local_ned_send(
|
||||
0, # timestamp
|
||||
self.sysid_thismav(), # target system_id
|
||||
1, # target component id
|
||||
mav_frame,
|
||||
MAV_POS_TARGET_TYPE_MASK.POS_IGNORE |
|
||||
MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |
|
||||
MAV_POS_TARGET_TYPE_MASK.YAW_IGNORE |
|
||||
MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
vector.x, # vx
|
||||
vector.y, # vy
|
||||
vector.z, # vz
|
||||
0, # afx
|
||||
0, # afy
|
||||
0, # afz
|
||||
0, # yaw
|
||||
0, # yawrate
|
||||
)
|
||||
self.wait_speed_vector(
|
||||
Vector3(0, 0, 0),
|
||||
timeout=timeout,
|
||||
called_function=lambda plop, empty: send_speed_vector_local_ned(target_speed, mavutil.mavlink.MAV_FRAME_LOCAL_NED), # noqa
|
||||
minimum_duration=10
|
||||
)
|
||||
|
||||
self.do_RTL()
|
||||
|
||||
def SetpointGlobalVel(self, timeout=30):
|
||||
"""Test set position message in guided mode."""
|
||||
# Disable heading and yaw rate test on rover type
|
||||
|
Loading…
Reference in New Issue
Block a user