mirror of
https://gitee.com/xiaohuolufeihua/bizhang_-obav.git
synced 2026-05-21 01:12:11 +00:00
Tuning to integration testing for better reporting
This commit is contained in:
@@ -111,7 +111,12 @@ class MavrosMissionTest(unittest.TestCase):
|
|||||||
self.has_global_pos = True
|
self.has_global_pos = True
|
||||||
|
|
||||||
def extended_state_callback(self, data):
|
def extended_state_callback(self, data):
|
||||||
|
|
||||||
|
prev_state = self.extended_state.vtol_state;
|
||||||
|
|
||||||
self.extended_state = data
|
self.extended_state = data
|
||||||
|
if (prev_state != self.extended_state.vtol_state):
|
||||||
|
print("VTOL state change: %d" % self.extended_state.vtol_state);
|
||||||
|
|
||||||
#
|
#
|
||||||
# Helper methods
|
# Helper methods
|
||||||
@@ -148,7 +153,7 @@ class MavrosMissionTest(unittest.TestCase):
|
|||||||
self.last_pos_d = 9999
|
self.last_pos_d = 9999
|
||||||
|
|
||||||
rospy.loginfo("trying to reach waypoint " +
|
rospy.loginfo("trying to reach waypoint " +
|
||||||
"lat: %f, lon: %f, alt: %f, timeout: %d, index: %d" %
|
"lat: %13.9f, lon: %13.9f, alt: %6.2f, timeout: %d, index: %d" %
|
||||||
(lat, lon, alt, timeout, index))
|
(lat, lon, alt, timeout, index))
|
||||||
|
|
||||||
# does it reach the position in X seconds?
|
# does it reach the position in X seconds?
|
||||||
@@ -174,9 +179,20 @@ class MavrosMissionTest(unittest.TestCase):
|
|||||||
count = count + 1
|
count = count + 1
|
||||||
self.rate.sleep()
|
self.rate.sleep()
|
||||||
|
|
||||||
|
vtol_state_string = "VTOL undefined"
|
||||||
|
|
||||||
|
if (self.extended_state.vtol_state == ExtendedState.VTOL_STATE_MC):
|
||||||
|
vtol_state_string = "VTOL MC"
|
||||||
|
if (self.extended_state.vtol_state == ExtendedState.VTOL_STATE_FW):
|
||||||
|
vtol_state_string = "VTOL FW"
|
||||||
|
if (self.extended_state.vtol_state == ExtendedState.VTOL_STATE_TRANSITION_TO_MC):
|
||||||
|
vtol_state_string = "VTOL FW->MC"
|
||||||
|
if (self.extended_state.vtol_state == ExtendedState.VTOL_STATE_TRANSITION_TO_FW):
|
||||||
|
vtol_state_string = "VTOL MC->FW"
|
||||||
|
|
||||||
self.assertTrue(count < timeout, (("(%s) took too long to get to position " +
|
self.assertTrue(count < timeout, (("(%s) took too long to get to position " +
|
||||||
"lat: %f, lon: %f, alt: %f, xy off: %f, z off: %f, timeout: %d, index: %d, pos_d: %f, alt_d: %f") %
|
"lat: %13.9f, lon: %13.9f, alt: %6.2f, xy off: %f, z off: %f, timeout: %d, index: %d, pos_d: %f, alt_d: %f, VTOL state: %s") %
|
||||||
(self.mission_name, lat, lon, alt, xy_radius, z_radius, timeout, index, self.last_pos_d, self.last_alt_d)))
|
(self.mission_name, lat, lon, alt, xy_radius, z_radius, timeout, index, self.last_pos_d, self.last_alt_d, vtol_state_string)))
|
||||||
|
|
||||||
def run_mission(self):
|
def run_mission(self):
|
||||||
"""switch mode: auto and arm"""
|
"""switch mode: auto and arm"""
|
||||||
@@ -283,6 +299,7 @@ class MavrosMissionTest(unittest.TestCase):
|
|||||||
alt = waypoint.z_alt
|
alt = waypoint.z_alt
|
||||||
if waypoint.frame == Waypoint.FRAME_GLOBAL_REL_ALT:
|
if waypoint.frame == Waypoint.FRAME_GLOBAL_REL_ALT:
|
||||||
alt += self.home_alt
|
alt += self.home_alt
|
||||||
|
|
||||||
self.reach_position(waypoint.x_lat, waypoint.y_long, alt, 600, index)
|
self.reach_position(waypoint.x_lat, waypoint.y_long, alt, 600, index)
|
||||||
|
|
||||||
# check if VTOL transition happens if applicable
|
# check if VTOL transition happens if applicable
|
||||||
|
|||||||
@@ -1,4 +1,4 @@
|
|||||||
# New style transitions, takeoff not at home
|
# New style transitions, takeoff not at home
|
||||||
QGC WPL 110
|
QGC WPL 110
|
||||||
0 1 3 84 15.0 0 0 0 47.397731862593744 8.543269295853861 12.0 1
|
0 1 3 84 15.0 0 0 0 47.397731862593744 8.543269295853861 15.0 1
|
||||||
1 0 3 85 0.0 0.0 -0.0 0.0 47.3990753922183 8.5432371088360526 0.0 1
|
1 0 3 85 0.0 0.0 -0.0 0.0 47.39651890962795 8.5433217125134888 0.0 1
|
||||||
|
|||||||
Reference in New Issue
Block a user