aboutsummaryrefslogtreecommitdiff
path: root/integrationtests/demo_tests/direct_offboard_posctl_test.py
diff options
context:
space:
mode:
authorAndreas Antener <antener_a@gmx.ch>2015-03-01 23:56:05 +0100
committerAndreas Antener <antener_a@gmx.ch>2015-03-02 00:18:34 +0100
commit9252124cfc84ad31f4a88d937343c7e5682e3339 (patch)
treea9c40866f9777ed218d6678e8393a5864a529304 /integrationtests/demo_tests/direct_offboard_posctl_test.py
parentedfbde1505456e89d79c11be5c8780a1219cce30 (diff)
downloadpx4-firmware-9252124cfc84ad31f4a88d937343c7e5682e3339.tar.gz
px4-firmware-9252124cfc84ad31f4a88d937343c7e5682e3339.tar.bz2
px4-firmware-9252124cfc84ad31f4a88d937343c7e5682e3339.zip
- updated test names, fixed lying comments and updated notes, misc. cleanup
- added mavros attitude control test - using manual arming for mavros tests so they succeed for the moment, arming should be implemented soon
Diffstat (limited to 'integrationtests/demo_tests/direct_offboard_posctl_test.py')
-rwxr-xr-xintegrationtests/demo_tests/direct_offboard_posctl_test.py15
1 files changed, 11 insertions, 4 deletions
diff --git a/integrationtests/demo_tests/direct_offboard_posctl_test.py b/integrationtests/demo_tests/direct_offboard_posctl_test.py
index 42667757b..0db4fd131 100755
--- a/integrationtests/demo_tests/direct_offboard_posctl_test.py
+++ b/integrationtests/demo_tests/direct_offboard_posctl_test.py
@@ -55,7 +55,13 @@ from std_msgs.msg import Header
from manual_input import ManualInput
from flight_path_assertion import FlightPathAssertion
-
+#
+# Tests flying a path in offboard control by directly sending setpoints
+# to the position controller (position_setpoint_triplet).
+#
+# For the test to be successful it needs to stay on the predefined path
+# and reach all setpoints in a certain time.
+#
class OffboardPosctlTest(unittest.TestCase):
def setUp(self):
@@ -112,7 +118,7 @@ class OffboardPosctlTest(unittest.TestCase):
self.assertTrue(count < timeout, "took too long to get to position")
#
- # Test offboard POSCTL
+ # Test offboard position control
#
def test_posctl(self):
manIn = ManualInput()
@@ -124,7 +130,7 @@ class OffboardPosctlTest(unittest.TestCase):
self.assertTrue(self.controlMode.flag_control_offboard_enabled, "flag_control_offboard_enabled is not set")
self.assertTrue(self.controlMode.flag_control_position_enabled, "flag_control_position_enabled is not set")
- # prepare flight path assertion
+ # prepare flight path
positions = (
(0,0,0),
(2,2,-2),
@@ -132,6 +138,7 @@ class OffboardPosctlTest(unittest.TestCase):
(-2,-2,-2),
(2,2,-2))
+ # flight path assertion
self.fpa = FlightPathAssertion(positions, 1, 0)
self.fpa.start()
@@ -156,5 +163,5 @@ class OffboardPosctlTest(unittest.TestCase):
if __name__ == '__main__':
import rostest
- rostest.rosrun(PKG, 'posctl_test', OffboardPosctlTest)
+ rostest.rosrun(PKG, 'direct_offboard_posctl_test', OffboardPosctlTest)
#unittest.main()