px4-firmware/integrationtests/demo_tests/mavros_offboard_posctl_test.py

173 lines
6.2 KiB
Python
Raw Normal View History

2015-02-23 18:35:06 -04:00
#!/usr/bin/env python
#***************************************************************************
#
# Copyright (c) 2015 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 Andreas Antener <andreas@uaventure.com>
#
PKG = 'px4'
import unittest
import rospy
import math
2015-03-15 16:39:57 -03:00
import rosbag
2015-02-23 18:35:06 -04:00
from numpy import linalg
import numpy as np
from px4.msg import vehicle_control_mode
2015-03-15 16:39:57 -03:00
from px4.msg import vehicle_local_position
from px4.msg import vehicle_local_position_setpoint
2015-02-23 18:35:06 -04:00
from std_msgs.msg import Header
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 position 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)
#
2015-03-01 19:28:53 -04:00
class MavrosOffboardPosctlTest(unittest.TestCase):
2015-02-23 18:35:06 -04:00
def setUp(self):
rospy.init_node('test_node', anonymous=True)
self.helper = PX4TestHelper("mavros_offboard_posctl_test")
self.helper.setUp()
2015-04-08 04:48:27 -03:00
rospy.Subscriber('vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback)
rospy.Subscriber("mavros/local_position/local", PoseStamped, self.position_callback)
self.pub_spt = rospy.Publisher('mavros/setpoint_position/local', PoseStamped, queue_size=10)
2015-02-23 18:35:06 -04:00
self.rate = rospy.Rate(10) # 10hz
self.has_pos = False
self.local_position = PoseStamped()
self.control_mode = vehicle_control_mode()
2015-02-23 18:35:06 -04:00
2015-03-15 16:39:57 -03:00
def tearDown(self):
self.helper.tearDown()
2015-03-15 16:39:57 -03:00
2015-02-23 18:35:06 -04:00
#
# General callback functions used in tests
#
def position_callback(self, data):
self.has_pos = True
self.local_position = data
2015-02-23 18:35:06 -04:00
def vehicle_control_mode_callback(self, data):
self.control_mode = data
2015-02-23 18:35:06 -04:00
#
# Helper methods
#
def is_at_position(self, x, y, z, offset):
if not self.has_pos:
2015-02-23 18:35:06 -04:00
return False
rospy.logdebug("current position %f, %f, %f" %
(self.local_position.pose.position.x,
self.local_position.pose.position.y,
self.local_position.pose.position.z))
2015-02-23 18:35:06 -04:00
desired = np.array((x, y, z))
pos = np.array((self.local_position.pose.position.x,
self.local_position.pose.position.y,
self.local_position.pose.position.z))
2015-02-23 18:35:06 -04:00
return linalg.norm(desired - pos) < offset
def reach_position(self, x, y, z, timeout):
# set a position setpoint
pos = PoseStamped()
2015-03-07 14:27:36 -04:00
pos.header = Header()
2015-02-23 18:35:06 -04:00
pos.header.frame_id = "base_footprint"
pos.pose.position.x = x
pos.pose.position.y = y
pos.pose.position.z = z
# For demo purposes we will lock yaw/heading to north.
yaw_degrees = 0 # North
yaw = math.radians(yaw_degrees)
quaternion = quaternion_from_euler(0, 0, yaw)
pos.pose.orientation = Quaternion(*quaternion)
# does it reach the position in X seconds?
count = 0
while count < timeout:
# update timestamp for each published SP
pos.header.stamp = rospy.Time.now()
self.pub_spt.publish(pos)
self.helper.bag_write('mavros/setpoint_position/local', pos)
2015-03-07 14:27:36 -04:00
if self.is_at_position(pos.pose.position.x, pos.pose.position.y, pos.pose.position.z, 0.5):
2015-02-23 18:35:06 -04:00
break
count = count + 1
self.rate.sleep()
self.assertTrue(count < timeout, "took too long to get to position")
#
# Test offboard position control
2015-02-23 18:35:06 -04:00
#
def test_posctl(self):
# prepare flight path
2015-02-23 18:35:06 -04:00
positions = (
(0, 0, 0),
(2, 2, 2),
(2, -2, 2),
(-2, -2, 2),
(2, 2, 2))
2015-02-23 18:35:06 -04:00
for i in range(0, len(positions)):
self.reach_position(positions[i][0], positions[i][1], positions[i][2], 120)
2015-03-07 14:27:36 -04:00
2015-02-23 18:35:06 -04:00
count = 0
timeout = 50
while count < timeout:
if not self.is_at_position(2, 2, 2, 0.5):
2015-02-23 18:35:06 -04:00
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_position_enabled, "flag_control_position_enabled is not set")
self.assertTrue(self.control_mode.flag_control_offboard_enabled, "flag_control_offboard_enabled is not set")
2015-02-23 18:35:06 -04:00
self.assertTrue(count == timeout, "position could not be held")
2015-03-07 14:27:36 -04:00
2015-02-23 18:35:06 -04:00
if __name__ == '__main__':
import rostest
2015-03-01 19:28:53 -04:00
rostest.rosrun(PKG, 'mavros_offboard_posctl_test', MavrosOffboardPosctlTest)
2015-02-23 18:35:06 -04:00
#unittest.main()