diff --git a/.ci/Jenkinsfile-SITL_tests b/.ci/Jenkinsfile-SITL_tests index 18e0152db2..2ae7022e90 100644 --- a/.ci/Jenkinsfile-SITL_tests +++ b/.ci/Jenkinsfile-SITL_tests @@ -60,6 +60,12 @@ pipeline { mission: "", vehicle: "iris" ], + [ + name: "MC_offboard_rpyrt", + test: "mavros_posix_tests_offboard_rpyrt_ctl.test", + mission: "", + vehicle: "iris" + ], [ name: "Rover 1", diff --git a/.ci/Jenkinsfile-SITL_tests_ASan b/.ci/Jenkinsfile-SITL_tests_ASan index c2874733ca..8dc8b733b3 100644 --- a/.ci/Jenkinsfile-SITL_tests_ASan +++ b/.ci/Jenkinsfile-SITL_tests_ASan @@ -60,6 +60,12 @@ pipeline { mission: "", vehicle: "iris" ], + [ + name: "MC_offboard_rpyrt", + test: "mavros_posix_tests_offboard_rpyrt_ctl.test", + mission: "", + vehicle: "iris" + ], [ name: "Rover 1", diff --git a/.ci/Jenkinsfile-SITL_tests_coverage b/.ci/Jenkinsfile-SITL_tests_coverage index 579c448ae7..e22ab1d3d8 100644 --- a/.ci/Jenkinsfile-SITL_tests_coverage +++ b/.ci/Jenkinsfile-SITL_tests_coverage @@ -34,6 +34,12 @@ pipeline { mission: "", vehicle: "iris" ], + [ + name: "MC_offboard_rpyrt", + test: "mavros_posix_tests_offboard_rpyrt_ctl.test", + mission: "", + vehicle: "iris" + ], [ name: "Rover 1", diff --git a/Makefile b/Makefile index 2cb3f0b4b0..0cb2fc2232 100644 --- a/Makefile +++ b/Makefile @@ -379,6 +379,7 @@ tests_mission_coverage: tests_offboard: rostest @"$(SRC_DIR)"/test/rostest_px4_run.sh mavros_posix_tests_offboard_attctl.test @"$(SRC_DIR)"/test/rostest_px4_run.sh mavros_posix_tests_offboard_posctl.test + @"$(SRC_DIR)"/test/rostest_px4_run.sh mavros_posix_tests_offboard_rpyrt_ctl.test tests_avoidance: rostest @"$(SRC_DIR)"/test/rostest_avoidance_run.sh mavros_posix_test_avoidance.test diff --git a/integrationtests/python_src/px4_it/mavros/mavros_offboard_yawrate_test.py b/integrationtests/python_src/px4_it/mavros/mavros_offboard_yawrate_test.py new file mode 100755 index 0000000000..315d7b373b --- /dev/null +++ b/integrationtests/python_src/px4_it/mavros/mavros_offboard_yawrate_test.py @@ -0,0 +1,177 @@ +#!/usr/bin/env python2 +#*************************************************************************** +# +# Copyright (c) 2020 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +#***************************************************************************/ +# +# @author Pedro Roque +# + +from __future__ import division + +PKG = 'px4' + +import rospy +from geometry_msgs.msg import Quaternion, Vector3 +from mavros_msgs.msg import AttitudeTarget +from mavros_test_common import MavrosTestCommon +from pymavlink import mavutil +from six.moves import xrange +from std_msgs.msg import Header +from threading import Thread +from tf.transformations import quaternion_from_euler + + +class MavrosOffboardYawrateTest(MavrosTestCommon): + """ + Tests flying in offboard control by sending a Roll Pitch Yawrate Thrust (RPYrT) + as attitude setpoint. + + For the test to be successful it needs to achieve a desired yawrate and height. + """ + + def setUp(self): + super(MavrosOffboardYawrateTest, self).setUp() + + self.att = AttitudeTarget() + + self.att_setpoint_pub = rospy.Publisher( + 'mavros/setpoint_raw/attitude', AttitudeTarget, queue_size=1) + + # send setpoints in seperate thread to better prevent failsafe + self.att_thread = Thread(target=self.send_att, args=()) + self.att_thread.daemon = True + self.att_thread.start() + + # desired yawrate target + self.des_yawrate = 0.1 + self.yawrate_tol = 0.02 + + def tearDown(self): + super(MavrosOffboardYawrateTest, self).tearDown() + + # + # Helper methods + # + def send_att(self): + rate = rospy.Rate(10) # Hz + self.att.body_rate = Vector3() + self.att.header = Header() + self.att.header.frame_id = "base_footprint" + self.att.orientation = self.local_position.pose.orientation + + self.att.body_rate.x = 0 + self.att.body_rate.y = 0 + self.att.body_rate.z = self.des_yawrate + + self.att.thrust = 0.59 + + self.att.type_mask = 3 # ignore roll and pitch rate + + while not rospy.is_shutdown(): + self.att.header.stamp = rospy.Time.now() + self.att_setpoint_pub.publish(self.att) + try: # prevent garbage in console output when thread is killed + rate.sleep() + except rospy.ROSInterruptException: + pass + + # + # Test method + # + def test_attctl(self): + """Test offboard yawrate control""" + + # boundary to cross + # Stay leveled, go up, and test yawrate + boundary_x = 5 + boundary_y = 5 + boundary_z = 10 + + + # make sure the simulation is ready to start the mission + self.wait_for_topics(60) + self.wait_for_landed_state(mavutil.mavlink.MAV_LANDED_STATE_ON_GROUND, + 10, -1) + + self.log_topic_vars() + self.set_arm(True, 5) + self.set_mode("OFFBOARD", 5) + rospy.loginfo("run mission") + rospy.loginfo("attempting to cross boundary | z: {2} , stay within x: {0} y: {1} \n and achieve {3} yawrate". + format(boundary_x, boundary_y, boundary_z, self.des_yawrate)) + + # does it cross expected boundaries in 'timeout' seconds? + timeout = 90 # (int) seconds + loop_freq = 2 # Hz + rate = rospy.Rate(loop_freq) + crossed = False + for i in xrange(timeout * loop_freq): + if (self.local_position.pose.position.x < boundary_x and + self.local_position.pose.position.x > -boundary_x and + self.local_position.pose.position.y < boundary_y and + self.local_position.pose.position.y > -boundary_y and + self.local_position.pose.position.z > boundary_z and + abs(self.imu_data.angular_velocity.z - self.des_yawrate) < self.yawrate_tol): + rospy.loginfo("Test successful. Final altitude and yawrate achieved") + crossed = True + break + + try: + rate.sleep() + except rospy.ROSException as e: + self.fail(e) + + self.assertTrue(crossed, ( + "took too long to finish test | current position x: {0:.2f}, y: {1:.2f}, z: {2:.2f} \n " \ + " | current att qx: {3:.2f}, qy: {4:.2f}, qz: {5:.2f} qw: {6:.2f}, yr: {7:.2f}| timeout(seconds): {8}". + format(self.local_position.pose.position.x, + self.local_position.pose.position.y, + self.local_position.pose.position.z, + self.imu_data.orientation.x, + self.imu_data.orientation.y, + self.imu_data.orientation.z, + self.imu_data.orientation.w, + self.imu_data.angular_velocity.z, + timeout))) + + self.set_mode("AUTO.LAND", 5) + self.wait_for_landed_state(mavutil.mavlink.MAV_LANDED_STATE_ON_GROUND, + 90, 0) + self.set_arm(False, 5) + + +if __name__ == '__main__': + import rostest + rospy.init_node('test_node', anonymous=True) + + rostest.rosrun(PKG, 'mavros_offboard_yawrate_test', + MavrosOffboardYawrateTest) diff --git a/integrationtests/python_src/px4_it/mavros/mavros_test_common.py b/integrationtests/python_src/px4_it/mavros/mavros_test_common.py index c43ed0d305..ef334e1f38 100644 --- a/integrationtests/python_src/px4_it/mavros/mavros_test_common.py +++ b/integrationtests/python_src/px4_it/mavros/mavros_test_common.py @@ -10,7 +10,7 @@ from mavros_msgs.msg import Altitude, ExtendedState, HomePosition, State, \ from mavros_msgs.srv import CommandBool, ParamGet, SetMode, WaypointClear, \ WaypointPush from pymavlink import mavutil -from sensor_msgs.msg import NavSatFix +from sensor_msgs.msg import NavSatFix, Imu from six.moves import xrange @@ -22,6 +22,7 @@ class MavrosTestCommon(unittest.TestCase): self.altitude = Altitude() self.extended_state = ExtendedState() self.global_position = NavSatFix() + self.imu_data = Imu() self.home_position = HomePosition() self.local_position = PoseStamped() self.mission_wp = WaypointList() @@ -32,7 +33,7 @@ class MavrosTestCommon(unittest.TestCase): key: False for key in [ 'alt', 'ext_state', 'global_pos', 'home_pos', 'local_pos', - 'mission_wp', 'state' + 'mission_wp', 'state', 'imu' ] } @@ -66,6 +67,9 @@ class MavrosTestCommon(unittest.TestCase): self.global_pos_sub = rospy.Subscriber('mavros/global_position/global', NavSatFix, self.global_position_callback) + self.imu_data_sub = rospy.Subscriber('mavros/imu/data', + Imu, + self.imu_data_callback) self.home_pos_sub = rospy.Subscriber('mavros/home_position/home', HomePosition, self.home_position_callback) @@ -114,6 +118,12 @@ class MavrosTestCommon(unittest.TestCase): if not self.sub_topics_ready['global_pos']: self.sub_topics_ready['global_pos'] = True + def imu_data_callback(self, data): + self.imu_data = data + + if not self.sub_topics_ready['imu']: + self.sub_topics_ready['imu'] = True + def home_position_callback(self, data): self.home_position = data diff --git a/test/mavros_posix_tests_offboard_rpyrt_ctl.test b/test/mavros_posix_tests_offboard_rpyrt_ctl.test new file mode 100644 index 0000000000..6d26412d26 --- /dev/null +++ b/test/mavros_posix_tests_offboard_rpyrt_ctl.test @@ -0,0 +1,21 @@ + + + + + + + + + + + + + + + + + + + + +