aboutsummaryrefslogtreecommitdiff
path: root/integrationtests/demo_tests/mavros_offboard_attctl_test.py
diff options
context:
space:
mode:
authorAndreas Antener <antener_a@gmx.ch>2015-03-16 21:45:29 +0100
committerAndreas Antener <antener_a@gmx.ch>2015-03-18 08:33:46 +0100
commitf1fa57ff4297f50ccfbee86344de02554f641a7f (patch)
tree0b04ddc22fa45270824ef0ce0fc8d72a0bd592d6 /integrationtests/demo_tests/mavros_offboard_attctl_test.py
parentf3a2c66e89aa2da0e9f736b89b4da9e4e03283f0 (diff)
downloadpx4-firmware-f1fa57ff4297f50ccfbee86344de02554f641a7f.tar.gz
px4-firmware-f1fa57ff4297f50ccfbee86344de02554f641a7f.tar.bz2
px4-firmware-f1fa57ff4297f50ccfbee86344de02554f641a7f.zip
write more bags, use helper class to log default topics
Diffstat (limited to 'integrationtests/demo_tests/mavros_offboard_attctl_test.py')
-rwxr-xr-xintegrationtests/demo_tests/mavros_offboard_attctl_test.py17
1 files changed, 9 insertions, 8 deletions
diff --git a/integrationtests/demo_tests/mavros_offboard_attctl_test.py b/integrationtests/demo_tests/mavros_offboard_attctl_test.py
index aa6bd8d9f..ef875ce61 100755
--- a/integrationtests/demo_tests/mavros_offboard_attctl_test.py
+++ b/integrationtests/demo_tests/mavros_offboard_attctl_test.py
@@ -43,10 +43,13 @@ import rosbag
from px4.msg import vehicle_control_mode
from px4.msg import vehicle_local_position
+from px4.msg import vehicle_attitude_setpoint
+from px4.msg import vehicle_attitude
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 px4_test_helper import PX4TestHelper
#
# Tests flying a path in offboard control by sending attitude and thrust setpoints
@@ -58,10 +61,11 @@ class MavrosOffboardAttctlTest(unittest.TestCase):
def setUp(self):
rospy.init_node('test_node', anonymous=True)
- self.bag = rosbag.Bag('mavros_offboard_attctl_test.bag', 'w', compression="lz4")
rospy.wait_for_service('iris/mavros/cmd/arming', 30)
+ self.helper = PX4TestHelper("mavros_offboard_attctl_test")
+ self.helper.setUp()
+
rospy.Subscriber('iris/vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback)
- self.sub_vlp = rospy.Subscriber("iris/vehicle_local_position", vehicle_local_position, self.vehicle_position_callback)
rospy.Subscriber("iris/mavros/position/local", PoseStamped, self.position_callback)
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)
@@ -71,16 +75,11 @@ class MavrosOffboardAttctlTest(unittest.TestCase):
self.local_position = PoseStamped()
def tearDown(self):
- self.sub_vlp.unregister()
- self.rate.sleep()
- self.bag.close()
+ self.helper.tearDown()
#
# General callback functions used in tests
#
- def vehicle_position_callback(self, data):
- self.bag.write('vehicle_local_position', data)
-
def position_callback(self, data):
self.has_pos = True
self.local_position = data
@@ -111,7 +110,9 @@ class MavrosOffboardAttctlTest(unittest.TestCase):
att.header.stamp = rospy.Time.now()
self.pub_att.publish(att)
+ self.helper.bag_write('mavros/setpoint/attitude', att)
self.pub_thr.publish(throttle)
+ self.helper.bag_write('mavros/setpoint/att_throttle', throttle)
self.rate.sleep()
if (self.local_position.pose.position.x > 5