aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorAndreas Antener <antener_a@gmx.ch>2015-03-15 16:39:35 +0100
committerAndreas Antener <antener_a@gmx.ch>2015-03-15 16:39:35 +0100
commit1d5beb1edf63fef52a8c68993bcfe80b51a1aba8 (patch)
tree7e2a8dd2e48f5fe48ee744aef14fe9e5345d4a94
parent15a5c0a9bebf113ddcb6f1b95a8672fa882dcdcc (diff)
downloadpx4-firmware-1d5beb1edf63fef52a8c68993bcfe80b51a1aba8.tar.gz
px4-firmware-1d5beb1edf63fef52a8c68993bcfe80b51a1aba8.tar.bz2
px4-firmware-1d5beb1edf63fef52a8c68993bcfe80b51a1aba8.zip
- updated flight path assertion position subscription and added check if it does not get a position after 1 sec
- modified test so it works iwth new _Z_P parameter
-rwxr-xr-xintegrationtests/demo_tests/direct_offboard_posctl_test.py1
-rw-r--r--integrationtests/demo_tests/flight_path_assertion.py12
2 files changed, 10 insertions, 3 deletions
diff --git a/integrationtests/demo_tests/direct_offboard_posctl_test.py b/integrationtests/demo_tests/direct_offboard_posctl_test.py
index 225760d6c..d61eec063 100755
--- a/integrationtests/demo_tests/direct_offboard_posctl_test.py
+++ b/integrationtests/demo_tests/direct_offboard_posctl_test.py
@@ -132,6 +132,7 @@ class DirectOffboardPosctlTest(unittest.TestCase):
# prepare flight path
positions = (
(0, 0, 0),
+ (0, 0, -2),
(2, 2, -2),
(2, -2, -2),
(-2, -2, -2),
diff --git a/integrationtests/demo_tests/flight_path_assertion.py b/integrationtests/demo_tests/flight_path_assertion.py
index ccadd1ab9..244324cd0 100644
--- a/integrationtests/demo_tests/flight_path_assertion.py
+++ b/integrationtests/demo_tests/flight_path_assertion.py
@@ -62,7 +62,7 @@ class FlightPathAssertion(threading.Thread):
#
def __init__(self, positions, tunnelRadius=1, yaw_offset=0.2):
threading.Thread.__init__(self)
- rospy.Subscriber("px4_multicopter/vehicle_local_position", vehicle_local_position, self.position_callback)
+ rospy.Subscriber("iris/vehicle_local_position", vehicle_local_position, self.position_callback)
self.spawn_model = rospy.ServiceProxy('gazebo/spawn_sdf_model', SpawnModel)
self.set_model_state = rospy.ServiceProxy('gazebo/set_model_state', SetModelState)
self.delete_model = rospy.ServiceProxy('gazebo/delete_model', DeleteModel)
@@ -103,7 +103,7 @@ class FlightPathAssertion(threading.Thread):
"</visual>" +
"</link>" +
"</model>" +
- "</sdf>" % self.tunnel_radius)
+ "</sdf>") % self.tunnel_radius
self.spawn_model("indicator", xml, "", Pose(), "")
@@ -147,7 +147,7 @@ class FlightPathAssertion(threading.Thread):
self.spawn_indicator()
current = 0
-
+ count = 0
while not self.should_stop:
if self.has_pos:
# calculate distance to line segment between first two points
@@ -189,3 +189,9 @@ class FlightPathAssertion(threading.Thread):
break
rate.sleep()
+ count = count + 1
+
+ if count > 10 and not self.has_pos: # no position after 1 sec
+ rospy.logerr("no position")
+ self.failed = True
+ break