aboutsummaryrefslogtreecommitdiff
path: root/integrationtests/demo_tests/mavros_offboard_attctl_test.py
diff options
context:
space:
mode:
Diffstat (limited to 'integrationtests/demo_tests/mavros_offboard_attctl_test.py')
-rwxr-xr-xintegrationtests/demo_tests/mavros_offboard_attctl_test.py65
1 files changed, 21 insertions, 44 deletions
diff --git a/integrationtests/demo_tests/mavros_offboard_attctl_test.py b/integrationtests/demo_tests/mavros_offboard_attctl_test.py
index 92cdf1e0a..30e9fe9ba 100755
--- a/integrationtests/demo_tests/mavros_offboard_attctl_test.py
+++ b/integrationtests/demo_tests/mavros_offboard_attctl_test.py
@@ -37,29 +37,20 @@
#
PKG = 'px4'
-import sys
import unittest
import rospy
-import math
-
-from numpy import linalg
-import numpy as np
from px4.msg import vehicle_control_mode
from std_msgs.msg import Header
from std_msgs.msg import Float64
from geometry_msgs.msg import PoseStamped, Quaternion
from tf.transformations import quaternion_from_euler
-from mavros.srv import CommandBool
-
-from manual_input import ManualInput
#
-# Tests flying a path in offboard control by sending position setpoints
+# Tests flying a path in offboard control by sending attitude and thrust setpoints
# over MAVROS.
#
-# For the test to be successful it needs to reach all setpoints in a certain time.
-# FIXME: add flight path assertion (needs transformation from ROS frame to NED)
+# For the test to be successful it needs to cross a certain boundary in time.
#
class MavrosOffboardAttctlTest(unittest.TestCase):
@@ -68,45 +59,27 @@ class MavrosOffboardAttctlTest(unittest.TestCase):
rospy.wait_for_service('iris/mavros/cmd/arming', 30)
rospy.Subscriber('iris/vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback)
rospy.Subscriber("iris/mavros/position/local", PoseStamped, self.position_callback)
- self.pubAtt = rospy.Publisher('iris/mavros/setpoint/attitude', PoseStamped, queue_size=10)
- self.pubThr = rospy.Publisher('iris/mavros/setpoint/att_throttle', Float64, queue_size=10)
- self.cmdArm = rospy.ServiceProxy("iris/mavros/cmd/arming", CommandBool)
+ self.pub_att = rospy.Publisher('iris/mavros/setpoint/attitude', PoseStamped, queue_size=10)
+ self.pub_thr = rospy.Publisher('iris/mavros/setpoint/att_throttle', Float64, queue_size=10)
self.rate = rospy.Rate(10) # 10hz
- self.rateSec = rospy.Rate(1)
- self.hasPos = False
- self.controlMode = vehicle_control_mode()
+ self.has_pos = False
+ self.control_mode = vehicle_control_mode()
+ self.local_position = PoseStamped()
#
# General callback functions used in tests
#
def position_callback(self, data):
- self.hasPos = True
- self.localPosition = data
+ self.has_pos = True
+ self.local_position = data
def vehicle_control_mode_callback(self, data):
- self.controlMode = data
-
-
- #
- # Helper methods
- #
- def arm(self):
- return self.cmdArm(value=True)
+ self.control_mode = data
#
# Test offboard position control
#
def test_attctl(self):
- # FIXME: this must go ASAP when arming is implemented
- manIn = ManualInput()
- manIn.arm()
- manIn.offboard_attctl()
-
- self.assertTrue(self.arm(), "Could not arm")
- self.rateSec.sleep()
- self.rateSec.sleep()
- self.assertTrue(self.controlMode.flag_armed, "flag_armed is not set after 2 seconds")
-
# set some attitude and thrust
att = PoseStamped()
att.header = Header()
@@ -121,19 +94,23 @@ class MavrosOffboardAttctlTest(unittest.TestCase):
# does it cross expected boundaries in X seconds?
count = 0
timeout = 120
- while(count < timeout):
+ while count < timeout:
# update timestamp for each published SP
att.header.stamp = rospy.Time.now()
- self.pubAtt.publish(att)
- self.pubThr.publish(throttle)
- if (self.localPosition.pose.position.x > 5
- and self.localPosition.pose.position.z > 5
- and self.localPosition.pose.position.y < -5):
+ self.pub_att.publish(att)
+ self.pub_thr.publish(throttle)
+ self.rate.sleep()
+
+ if (self.local_position.pose.position.x > 5
+ and self.local_position.pose.position.z > 5
+ and self.local_position.pose.position.y < -5):
break
count = count + 1
- self.rate.sleep()
+ self.assertTrue(self.control_mode.flag_armed, "flag_armed is not set")
+ self.assertTrue(self.control_mode.flag_control_attitude_enabled, "flag_control_attitude_enabled is not set")
+ self.assertTrue(self.control_mode.flag_control_offboard_enabled, "flag_control_offboard_enabled is not set")
self.assertTrue(count < timeout, "took too long to cross boundaries")