From 2bbad206961ec4bf1e78ac8b6689634fa3e482b8 Mon Sep 17 00:00:00 2001 From: Andreas Antener Date: Sun, 15 Mar 2015 09:51:38 +0100 Subject: fixed some warnings and updated comments --- .../demo_tests/mavros_offboard_attctl_test.py | 20 ++++++-------------- 1 file changed, 6 insertions(+), 14 deletions(-) (limited to 'integrationtests') diff --git a/integrationtests/demo_tests/mavros_offboard_attctl_test.py b/integrationtests/demo_tests/mavros_offboard_attctl_test.py index 73cfe5a81..ecad9df4d 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): @@ -106,14 +97,15 @@ class MavrosOffboardAttctlTest(unittest.TestCase): while count < timeout: # update timestamp for each published SP att.header.stamp = rospy.Time.now() + self.pub_att.publish(att) - self.rate.sleep() + self.rate.sleep() # I'm guessing this is necessary to prevent timing issues 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): + and self.local_position.pose.position.z > 5 + and self.local_position.pose.position.y < -5): break count = count + 1 -- cgit v1.2.3