aboutsummaryrefslogtreecommitdiff
path: root/integrationtests
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2015-02-28 18:28:51 +0100
committerThomas Gubler <thomasgubler@gmail.com>2015-02-28 18:28:51 +0100
commitb4d7bac8c25d6b3b5cf277900295fac0c8384755 (patch)
tree0e32c46554f76f73132568bfe5897b4bdfa32de6 /integrationtests
parent1df0f25c6b112ef568f7a19a7819a8e7948d8515 (diff)
parent482f2c94424f32e45aaee68b8b515e1eab40b6de (diff)
downloadpx4-firmware-b4d7bac8c25d6b3b5cf277900295fac0c8384755.tar.gz
px4-firmware-b4d7bac8c25d6b3b5cf277900295fac0c8384755.tar.bz2
px4-firmware-b4d7bac8c25d6b3b5cf277900295fac0c8384755.zip
Merge pull request #1793 from PX4/ros_mavlink
ROS SITL: offboard setpoints
Diffstat (limited to 'integrationtests')
-rwxr-xr-xintegrationtests/demo_tests/direct_arm_test.py73
-rwxr-xr-xintegrationtests/demo_tests/direct_offboard_posctl_test.py160
-rw-r--r--integrationtests/demo_tests/direct_tests.launch18
-rw-r--r--integrationtests/demo_tests/flight_path_assertion.py171
-rwxr-xr-xintegrationtests/demo_tests/manual_input.py146
-rwxr-xr-xintegrationtests/demo_tests/mavros_offboard_posctl_test.py146
-rw-r--r--integrationtests/demo_tests/mavros_tests.launch18
7 files changed, 732 insertions, 0 deletions
diff --git a/integrationtests/demo_tests/direct_arm_test.py b/integrationtests/demo_tests/direct_arm_test.py
new file mode 100755
index 000000000..238f2d7e0
--- /dev/null
+++ b/integrationtests/demo_tests/direct_arm_test.py
@@ -0,0 +1,73 @@
+#!/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 sys
+import unittest
+import rospy
+
+from px4.msg import actuator_armed
+from manual_input import ManualInput
+
+class ArmTest(unittest.TestCase):
+
+ #
+ # General callback functions used in tests
+ #
+ def actuator_armed_callback(self, data):
+ self.actuatorStatus = data
+
+ #
+ # Test arming
+ #
+ def test_arm(self):
+ rospy.init_node('test_node', anonymous=True)
+ sub = rospy.Subscriber('px4_multicopter/actuator_armed', actuator_armed, self.actuator_armed_callback)
+
+ # method to test
+ arm = ManualInput()
+ arm.arm()
+
+ self.assertEquals(self.actuatorStatus.armed, True, "not armed")
+
+
+
+
+if __name__ == '__main__':
+ import rostest
+ rostest.rosrun(PKG, 'arm_test', ArmTest)
diff --git a/integrationtests/demo_tests/direct_offboard_posctl_test.py b/integrationtests/demo_tests/direct_offboard_posctl_test.py
new file mode 100755
index 000000000..42667757b
--- /dev/null
+++ b/integrationtests/demo_tests/direct_offboard_posctl_test.py
@@ -0,0 +1,160 @@
+#!/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 sys
+import unittest
+import rospy
+
+from numpy import linalg
+import numpy as np
+
+from px4.msg import vehicle_local_position
+from px4.msg import vehicle_control_mode
+from px4.msg import actuator_armed
+from px4.msg import position_setpoint_triplet
+from px4.msg import position_setpoint
+from sensor_msgs.msg import Joy
+from std_msgs.msg import Header
+
+from manual_input import ManualInput
+from flight_path_assertion import FlightPathAssertion
+
+
+class OffboardPosctlTest(unittest.TestCase):
+
+ def setUp(self):
+ rospy.init_node('test_node', anonymous=True)
+ rospy.Subscriber('px4_multicopter/vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback)
+ rospy.Subscriber("px4_multicopter/vehicle_local_position", vehicle_local_position, self.position_callback)
+ self.pubSpt = rospy.Publisher('px4_multicopter/position_setpoint_triplet', position_setpoint_triplet, queue_size=10)
+ self.rate = rospy.Rate(10) # 10hz
+
+ def tearDown(self):
+ if (self.fpa):
+ self.fpa.stop()
+
+ #
+ # General callback functions used in tests
+ #
+ def position_callback(self, data):
+ self.hasPos = True
+ self.localPosition = data
+
+ def vehicle_control_mode_callback(self, data):
+ self.controlMode = data
+
+
+ #
+ # Helper methods
+ #
+ def is_at_position(self, x, y, z, offset):
+ rospy.logdebug("current position %f, %f, %f" % (self.localPosition.x, self.localPosition.y, self.localPosition.z))
+ desired = np.array((x, y, z))
+ pos = np.array((self.localPosition.x, self.localPosition.y, self.localPosition.z))
+ return linalg.norm(desired - pos) < offset
+
+ def reach_position(self, x, y, z, timeout):
+ # set a position setpoint
+ pos = position_setpoint()
+ pos.valid = True
+ pos.x = x
+ pos.y = y
+ pos.z = z
+ pos.position_valid = True
+ stp = position_setpoint_triplet()
+ stp.current = pos
+ self.pubSpt.publish(stp)
+
+ # does it reach the position in X seconds?
+ count = 0
+ while(count < timeout):
+ if(self.is_at_position(pos.x, pos.y, pos.z, 0.5)):
+ break
+ count = count + 1
+ self.rate.sleep()
+
+ self.assertTrue(count < timeout, "took too long to get to position")
+
+ #
+ # Test offboard POSCTL
+ #
+ def test_posctl(self):
+ manIn = ManualInput()
+
+ # arm and go into offboard
+ manIn.arm()
+ manIn.offboard()
+ self.assertTrue(self.controlMode.flag_armed, "flag_armed is not set")
+ self.assertTrue(self.controlMode.flag_control_offboard_enabled, "flag_control_offboard_enabled is not set")
+ self.assertTrue(self.controlMode.flag_control_position_enabled, "flag_control_position_enabled is not set")
+
+ # prepare flight path assertion
+ positions = (
+ (0,0,0),
+ (2,2,-2),
+ (2,-2,-2),
+ (-2,-2,-2),
+ (2,2,-2))
+
+ self.fpa = FlightPathAssertion(positions, 1, 0)
+ self.fpa.start()
+
+ for i in range(0, len(positions)):
+ self.reach_position(positions[i][0], positions[i][1], positions[i][2], 120)
+ self.assertFalse(self.fpa.failed, "breached flight path tunnel (%d)" % i)
+
+ # does it hold the position for Y seconds?
+ positionHeld = True
+ count = 0
+ timeout = 50
+ while(count < timeout):
+ if(not self.is_at_position(2, 2, -2, 0.5)):
+ positionHeld = False
+ break
+ count = count + 1
+ self.rate.sleep()
+
+ self.assertTrue(count == timeout, "position could not be held")
+ self.fpa.stop()
+
+
+if __name__ == '__main__':
+ import rostest
+ rostest.rosrun(PKG, 'posctl_test', OffboardPosctlTest)
+ #unittest.main()
diff --git a/integrationtests/demo_tests/direct_tests.launch b/integrationtests/demo_tests/direct_tests.launch
new file mode 100644
index 000000000..d871c085c
--- /dev/null
+++ b/integrationtests/demo_tests/direct_tests.launch
@@ -0,0 +1,18 @@
+<launch>
+ <arg name="headless" default="true"/>
+ <arg name="gui" default="false"/>
+ <arg name="enable_logging" default="false"/>
+ <arg name="enable_ground_truth" default="false"/>
+ <arg name="log_file" default="iris"/>
+
+ <include file="$(find px4)/launch/gazebo_iris_empty_world.launch">
+ <arg name="headless" value="$(arg headless)"/>
+ <arg name="gui" value="$(arg gui)"/>
+ <arg name="enable_logging" value="$(arg enable_logging)" />
+ <arg name="enable_ground_truth" value="$(arg enable_ground_truth)" />
+ <arg name="log_file" value="$(arg log_file)"/>
+ </include>
+
+ <test test-name="direct_arm" pkg="px4" type="direct_arm_test.py" />
+ <test test-name="direct_offboard_posctl" pkg="px4" type="direct_offboard_posctl_test.py" />
+</launch>
diff --git a/integrationtests/demo_tests/flight_path_assertion.py b/integrationtests/demo_tests/flight_path_assertion.py
new file mode 100644
index 000000000..1f5bf01fc
--- /dev/null
+++ b/integrationtests/demo_tests/flight_path_assertion.py
@@ -0,0 +1,171 @@
+#!/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>
+#
+import sys
+import rospy
+import threading
+
+from px4.msg import vehicle_local_position
+from gazebo_msgs.srv import SpawnModel
+from gazebo_msgs.srv import SetModelState
+from gazebo_msgs.srv import DeleteModel
+from geometry_msgs.msg import Pose
+from geometry_msgs.msg import Twist
+
+from numpy import linalg
+import numpy as np
+import math
+
+#
+# Helper to test if vehicle stays in expected flight path.
+#
+class FlightPathAssertion(threading.Thread):
+
+ #
+ # Arguments
+ # - positions: tuple of tuples in the form (x, y, z, heading)
+ #
+ # TODO: yaw validation
+ # TODO: fail main test thread
+ #
+ def __init__(self, positions, tunnelRadius = 1, yawOffset = 0.2):
+ threading.Thread.__init__(self)
+ rospy.Subscriber("px4_multicopter/vehicle_local_position", vehicle_local_position, self.position_callback)
+ self.spawnModel = rospy.ServiceProxy('gazebo/spawn_sdf_model', SpawnModel)
+ self.setModelState = rospy.ServiceProxy('gazebo/set_model_state', SetModelState)
+ self.deleteModel = rospy.ServiceProxy('gazebo/delete_model', DeleteModel)
+
+ self.positions = positions
+ self.tunnelRadius = tunnelRadius
+ self.yawOffset = yawOffset
+ self.hasPos = False
+ self.shouldStop = False
+ self.center = positions[0]
+ self.endOfSegment = False
+ self.failed = False
+
+ def position_callback(self, data):
+ self.hasPos = True
+ self.localPosition = data
+
+ def spawn_indicator(self):
+ self.deleteModel("indicator")
+ xml = "<?xml version='1.0'?><sdf version='1.4'><model name='indicator'><static>true</static><link name='link'><visual name='visual'><transparency>0.7</transparency><geometry><sphere><radius>%f</radius></sphere></geometry><material><ambient>1 0 0 0.5</ambient><diffuse>1 0 0 0.5</diffuse></material></visual></link></model></sdf>" % self.tunnelRadius
+ self.spawnModel("indicator", xml, "", Pose(), "")
+
+ def position_indicator(self):
+ state = SetModelState()
+ state.model_name = "indicator"
+ pose = Pose()
+ pose.position.x = self.center[0]
+ pose.position.y = (-1) * self.center[1]
+ pose.position.z = (-1) * self.center[2]
+ state.pose = pose
+ state.twist = Twist()
+ state.reference_frame = ""
+ self.setModelState(state)
+
+ def distance_to_line(self, a, b, pos):
+ v = b - a
+ w = pos - a
+
+ c1 = np.dot(w, v)
+ if c1 <= 0: # before a
+ self.center = a
+ return linalg.norm(pos - a)
+
+ c2 = np.dot(v, v)
+ if c2 <= c1: # after b
+ self.center = b
+ self.endOfSegment = True
+ return linalg.norm(pos - b)
+
+ x = c1 / c2
+ l = a + x * v
+ self.center = l
+ return linalg.norm(pos - l)
+
+ def stop(self):
+ self.shouldStop = True
+
+ def run(self):
+ rate = rospy.Rate(10) # 10hz
+ self.spawn_indicator()
+
+ current = 0
+
+ while not self.shouldStop:
+ if (self.hasPos):
+ # calculate distance to line segment between first two points
+ # if distances > tunnelRadius
+ # exit with error
+ # advance current pos if not on the line anymore or distance to next point < tunnelRadius
+ # exit if current pos is now the last position
+
+ self.position_indicator()
+
+ pos = np.array((self.localPosition.x,
+ self.localPosition.y,
+ self.localPosition.z))
+ aPos = np.array((self.positions[current][0],
+ self.positions[current][1],
+ self.positions[current][2]))
+ bPos = np.array((self.positions[current + 1][0],
+ self.positions[current + 1][1],
+ self.positions[current + 1][2]))
+
+ dist = self.distance_to_line(aPos, bPos, pos)
+ bDist = linalg.norm(pos - bPos)
+
+ rospy.logdebug("distance to line: %f, distance to end: %f" % (dist, bDist))
+
+ if (dist > self.tunnelRadius):
+ msg = "left tunnel at position (%f, %f, %f)" % (self.localPosition.x, self.localPosition.y, self.localPosition.z)
+ rospy.logerr(msg)
+ self.failed = True
+ break
+
+ if (self.endOfSegment or bDist < self.tunnelRadius):
+ rospy.loginfo("next segment")
+ self.endOfSegment = False
+ current = current + 1
+
+ if (current == len(self.positions) - 1):
+ rospy.loginfo("no more positions")
+ break
+
+ rate.sleep()
diff --git a/integrationtests/demo_tests/manual_input.py b/integrationtests/demo_tests/manual_input.py
new file mode 100755
index 000000000..55911bede
--- /dev/null
+++ b/integrationtests/demo_tests/manual_input.py
@@ -0,0 +1,146 @@
+#!/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>
+#
+import sys
+import rospy
+
+from px4.msg import manual_control_setpoint
+from mav_msgs.msg import CommandAttitudeThrust
+from std_msgs.msg import Header
+
+#
+# Manual input control helper
+#
+# Note: this is not the way to do it. ATM it fakes input to iris/command/attitude because else
+# the simulator does not instantiate our controller.
+#
+class ManualInput:
+
+ def __init__(self):
+ rospy.init_node('test_node', anonymous=True)
+ self.pubMcsp = rospy.Publisher('px4_multicopter/manual_control_setpoint', manual_control_setpoint, queue_size=10)
+ self.pubAtt = rospy.Publisher('iris/command/attitude', CommandAttitudeThrust, queue_size=10)
+
+ def arm(self):
+ rate = rospy.Rate(10) # 10hz
+
+ att = CommandAttitudeThrust()
+ att.header = Header()
+
+ pos = manual_control_setpoint()
+ pos.x = 0
+ pos.z = 0
+ pos.y = 0
+ pos.r = 0
+ pos.mode_switch = 3
+ pos.return_switch = 3
+ pos.posctl_switch = 3
+ pos.loiter_switch = 3
+ pos.acro_switch = 0
+ pos.offboard_switch = 3
+
+ count = 0
+ while not rospy.is_shutdown() and count < 10:
+ rospy.loginfo("zeroing")
+ time = rospy.get_rostime().now()
+ pos.timestamp = time.secs * 1e6 + time.nsecs / 1000
+ self.pubMcsp.publish(pos)
+ # Fake input to iris commander
+ self.pubAtt.publish(att)
+ rate.sleep()
+ count = count + 1
+
+ pos.r = 1
+ count = 0
+ while not rospy.is_shutdown() and count < 10:
+ rospy.loginfo("arming")
+ time = rospy.get_rostime().now()
+ pos.timestamp = time.secs * 1e6 + time.nsecs / 1000
+ self.pubMcsp.publish(pos)
+ rate.sleep()
+ count = count + 1
+
+ def posctl(self):
+ rate = rospy.Rate(10) # 10hz
+
+ # triggers posctl
+ pos = manual_control_setpoint()
+ pos.x = 0
+ pos.z = 0
+ pos.y = 0
+ pos.r = 0
+ pos.mode_switch = 2
+ pos.return_switch = 3
+ pos.posctl_switch = 1
+ pos.loiter_switch = 3
+ pos.acro_switch = 0
+ pos.offboard_switch = 3
+
+ count = 0
+ while not rospy.is_shutdown() and count < 10:
+ rospy.loginfo("triggering posctl")
+ time = rospy.get_rostime().now()
+ pos.timestamp = time.secs * 1e6 + time.nsecs / 1000
+ self.pubMcsp.publish(pos)
+ rate.sleep()
+ count = count + 1
+
+ def offboard(self):
+ rate = rospy.Rate(10) # 10hz
+
+ # triggers posctl
+ pos = manual_control_setpoint()
+ pos.x = 0
+ pos.z = 0
+ pos.y = 0
+ pos.r = 0
+ pos.mode_switch = 3
+ pos.return_switch = 3
+ pos.posctl_switch = 3
+ pos.loiter_switch = 3
+ pos.acro_switch = 0
+ pos.offboard_switch = 1
+
+ count = 0
+ while not rospy.is_shutdown() and count < 10:
+ rospy.loginfo("triggering posctl")
+ time = rospy.get_rostime().now()
+ pos.timestamp = time.secs * 1e6 + time.nsecs / 1000
+ self.pubMcsp.publish(pos)
+ rate.sleep()
+ count = count + 1
+
diff --git a/integrationtests/demo_tests/mavros_offboard_posctl_test.py b/integrationtests/demo_tests/mavros_offboard_posctl_test.py
new file mode 100755
index 000000000..7468ad53f
--- /dev/null
+++ b/integrationtests/demo_tests/mavros_offboard_posctl_test.py
@@ -0,0 +1,146 @@
+#!/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 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 geometry_msgs.msg import PoseStamped, Quaternion
+from tf.transformations import quaternion_from_euler
+
+class OffboardPosctlTest(unittest.TestCase):
+
+ def setUp(self):
+ rospy.init_node('test_node', anonymous=True)
+ rospy.Subscriber('px4_multicopter/vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback)
+ rospy.Subscriber("px4_multicopter/mavros/position/local", PoseStamped, self.position_callback)
+ self.pubSpt = rospy.Publisher('px4_multicopter/mavros/setpoint/local_position', PoseStamped, queue_size=10)
+ self.rate = rospy.Rate(10) # 10hz
+ self.hasPos = False
+
+ #
+ # General callback functions used in tests
+ #
+ def position_callback(self, data):
+ self.hasPos = True
+ self.localPosition = data
+
+ def vehicle_control_mode_callback(self, data):
+ self.controlMode = data
+
+
+ #
+ # Helper methods
+ #
+ def is_at_position(self, x, y, z, offset):
+ if(not self.hasPos):
+ return False
+
+ rospy.logdebug("current position %f, %f, %f" % (self.localPosition.pose.position.x, self.localPosition.pose.position.y, self.localPosition.pose.position.z))
+ desired = np.array((x, y, z))
+ pos = np.array((self.localPosition.pose.position.x, self.localPosition.pose.position.y, self.localPosition.pose.position.z))
+ return linalg.norm(desired - pos) < offset
+
+ def reach_position(self, x, y, z, timeout):
+ # set a position setpoint
+ pos = PoseStamped()
+ pos.header = Header()
+ pos.header.frame_id = "base_footprint"
+ pos.header.stamp = rospy.Time.now()
+ 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):
+ self.pubSpt.publish(pos)
+
+ if(self.is_at_position(pos.pose.position.x, pos.pose.position.y, pos.pose.position.z, 0.5)):
+ break
+ count = count + 1
+ self.rate.sleep()
+
+ self.assertTrue(count < timeout, "took too long to get to position")
+
+ #
+ # Test offboard POSCTL
+ #
+ def test_posctl(self):
+ # prepare flight path assertion
+ positions = (
+ (0,0,0),
+ (2,2,2),
+ (2,-2,2),
+ (-2,-2,2),
+ (2,2,2))
+
+ for i in range(0, len(positions)):
+ self.reach_position(positions[i][0], positions[i][1], positions[i][2], 120)
+
+ # does it hold the position for Y seconds?
+ positionHeld = True
+ count = 0
+ timeout = 50
+ while(count < timeout):
+ if(not self.is_at_position(2, 2, 2, 0.5)):
+ positionHeld = False
+ break
+ count = count + 1
+ self.rate.sleep()
+
+ self.assertTrue(count == timeout, "position could not be held")
+
+
+if __name__ == '__main__':
+ import rostest
+ rostest.rosrun(PKG, 'posctl_test', OffboardPosctlTest)
+ #unittest.main()
diff --git a/integrationtests/demo_tests/mavros_tests.launch b/integrationtests/demo_tests/mavros_tests.launch
new file mode 100644
index 000000000..8c1ad7b4d
--- /dev/null
+++ b/integrationtests/demo_tests/mavros_tests.launch
@@ -0,0 +1,18 @@
+<launch>
+ <arg name="headless" default="true"/>
+ <arg name="gui" default="false"/>
+ <arg name="enable_logging" default="false"/>
+ <arg name="enable_ground_truth" default="false"/>
+ <arg name="log_file" default="iris"/>
+
+ <include file="$(find px4)/launch/gazebo_iris_empty_world.launch">
+ <arg name="headless" value="$(arg headless)"/>
+ <arg name="gui" value="$(arg gui)"/>
+ <arg name="enable_logging" value="$(arg enable_logging)" />
+ <arg name="enable_ground_truth" value="$(arg enable_ground_truth)" />
+ <arg name="log_file" value="$(arg log_file)"/>
+ </include>
+ <include file="$(find px4)/launch/mavros_sitl.launch" />
+
+ <test test-name="mavros_offboard_posctl_test" pkg="px4" type="mavros_offboard_posctl_test.py" />
+</launch>