Skip to content

Commit

Permalink
Merge pull request PX4#1854 from UAVenture/mavros_arming
Browse files Browse the repository at this point in the history
Mavros test updates
  • Loading branch information
LorenzMeier committed Mar 2, 2015
2 parents 48bf84f + 3f8c011 commit 9574c6d
Show file tree
Hide file tree
Showing 11 changed files with 239 additions and 51 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -42,32 +42,46 @@
import rospy

from px4.msg import actuator_armed
from px4.msg import vehicle_control_mode
from manual_input import ManualInput

class ArmTest(unittest.TestCase):
#
# Tests if commander reacts to manual input and sets control flags accordingly
#
class ManualInputTest(unittest.TestCase):

#
# General callback functions used in tests
#
def actuator_armed_callback(self, data):
self.actuatorStatus = data

def vehicle_control_mode_callback(self, data):
self.controlMode = data

#
# Test arming
#
def test_arm(self):
def test_manual_input(self):
rospy.init_node('test_node', anonymous=True)
sub = rospy.Subscriber('px4_multicopter/actuator_armed', actuator_armed, self.actuator_armed_callback)
rospy.Subscriber('px4_multicopter/actuator_armed', actuator_armed, self.actuator_armed_callback)
rospy.Subscriber('px4_multicopter/vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback)

# method to test
arm = ManualInput()
arm.arm()
man = ManualInput()

self.assertEquals(self.actuatorStatus.armed, True, "not armed")
# Test arming
man.arm()
self.assertEquals(self.actuatorStatus.armed, True, "did not arm")

# Test posctl
man.posctl()
self.assertTrue(self.controlMode.flag_control_position_enabled, "flag_control_position_enabled is not set")

# Test offboard
man.offboard()
self.assertTrue(self.controlMode.flag_control_offboard_enabled, "flag_control_offboard_enabled is not set")


if __name__ == '__main__':
import rostest
rostest.rosrun(PKG, 'arm_test', ArmTest)
rostest.rosrun(PKG, 'direct_manual_input_test', ManualInputTest)
17 changes: 12 additions & 5 deletions integrationtests/demo_tests/direct_offboard_posctl_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -55,8 +55,14 @@
from manual_input import ManualInput
from flight_path_assertion import FlightPathAssertion


class OffboardPosctlTest(unittest.TestCase):
#
# Tests flying a path in offboard control by directly sending setpoints
# to the position controller (position_setpoint_triplet).
#
# For the test to be successful it needs to stay on the predefined path
# and reach all setpoints in a certain time.
#
class DirectOffboardPosctlTest(unittest.TestCase):

def setUp(self):
rospy.init_node('test_node', anonymous=True)
Expand Down Expand Up @@ -112,7 +118,7 @@ def reach_position(self, x, y, z, timeout):
self.assertTrue(count < timeout, "took too long to get to position")

#
# Test offboard POSCTL
# Test offboard position control
#
def test_posctl(self):
manIn = ManualInput()
Expand All @@ -124,14 +130,15 @@ def test_posctl(self):
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
# prepare flight path
positions = (
(0,0,0),
(2,2,-2),
(2,-2,-2),
(-2,-2,-2),
(2,2,-2))

# flight path assertion
self.fpa = FlightPathAssertion(positions, 1, 0)
self.fpa.start()

Expand All @@ -156,5 +163,5 @@ def test_posctl(self):

if __name__ == '__main__':
import rostest
rostest.rosrun(PKG, 'posctl_test', OffboardPosctlTest)
rostest.rosrun(PKG, 'direct_offboard_posctl_test', DirectOffboardPosctlTest)
#unittest.main()
4 changes: 2 additions & 2 deletions integrationtests/demo_tests/direct_tests.launch
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,6 @@
<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" />
<test test-name="direct_manual_input_test" pkg="px4" type="direct_manual_input_test.py" />
<test test-name="direct_offboard_posctl_test" pkg="px4" type="direct_offboard_posctl_test.py" />
</launch>
2 changes: 1 addition & 1 deletion integrationtests/demo_tests/flight_path_assertion.py
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@
import math

#
# Helper to test if vehicle stays in expected flight path.
# Helper to test if vehicle stays on expected flight path.
#
class FlightPathAssertion(threading.Thread):

Expand Down
14 changes: 7 additions & 7 deletions integrationtests/demo_tests/manual_input.py
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@
#
# Manual input control helper
#
# Note: this is not the way to do it. ATM it fakes input to iris/command/attitude because else
# FIXME: 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:
Expand Down Expand Up @@ -74,7 +74,7 @@ def arm(self):
pos.offboard_switch = 3

count = 0
while not rospy.is_shutdown() and count < 10:
while not rospy.is_shutdown() and count < 5:
rospy.loginfo("zeroing")
time = rospy.get_rostime().now()
pos.timestamp = time.secs * 1e6 + time.nsecs / 1000
Expand All @@ -86,7 +86,7 @@ def arm(self):

pos.r = 1
count = 0
while not rospy.is_shutdown() and count < 10:
while not rospy.is_shutdown() and count < 5:
rospy.loginfo("arming")
time = rospy.get_rostime().now()
pos.timestamp = time.secs * 1e6 + time.nsecs / 1000
Expand All @@ -111,7 +111,7 @@ def posctl(self):
pos.offboard_switch = 3

count = 0
while not rospy.is_shutdown() and count < 10:
while not rospy.is_shutdown() and count < 5:
rospy.loginfo("triggering posctl")
time = rospy.get_rostime().now()
pos.timestamp = time.secs * 1e6 + time.nsecs / 1000
Expand All @@ -122,7 +122,7 @@ def posctl(self):
def offboard(self):
rate = rospy.Rate(10) # 10hz

# triggers posctl
# triggers offboard
pos = manual_control_setpoint()
pos.x = 0
pos.z = 0
Expand All @@ -136,8 +136,8 @@ def offboard(self):
pos.offboard_switch = 1

count = 0
while not rospy.is_shutdown() and count < 10:
rospy.loginfo("triggering posctl")
while not rospy.is_shutdown() and count < 5:
rospy.loginfo("triggering offboard")
time = rospy.get_rostime().now()
pos.timestamp = time.secs * 1e6 + time.nsecs / 1000
self.pubMcsp.publish(pos)
Expand Down
142 changes: 142 additions & 0 deletions integrationtests/demo_tests/mavros_offboard_attctl_test.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,142 @@
#!/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 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
# 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)
#
class MavrosOffboardAttctlTest(unittest.TestCase):

def setUp(self):
rospy.init_node('test_node', anonymous=True)
rospy.wait_for_service('mavros/cmd/arming', 30)
rospy.Subscriber('px4_multicopter/vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback)
rospy.Subscriber("mavros/position/local", PoseStamped, self.position_callback)
self.pubAtt = rospy.Publisher('mavros/setpoint/attitude', PoseStamped, queue_size=10)
self.pubThr = rospy.Publisher('mavros/setpoint/att_throttle', Float64, queue_size=10)
self.cmdArm = rospy.ServiceProxy("mavros/cmd/arming", CommandBool)
self.rate = rospy.Rate(10) # 10hz
self.rateSec = rospy.Rate(1)
self.hasPos = False
self.controlMode = vehicle_control_mode()

#
# 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 arm(self):
return self.cmdArm(value=True)

#
# Test offboard position control
#
def test_attctl(self):
# FIXME: this must go ASAP when arming is implemented
manIn = ManualInput()
manIn.arm()

self.assertTrue(self.arm(), "Could not arm")
self.rateSec.sleep()
self.rateSec.sleep()
self.assertTrue(self.controlMode.flag_armed, "flag_armed is not set after 2 seconds")

# set some attitude and thrust
att = PoseStamped()
att.header = Header()
att.header.frame_id = "base_footprint"
att.header.stamp = rospy.Time.now()
quaternion = quaternion_from_euler(0.2, 0.2, 0)
att.pose.orientation = Quaternion(*quaternion)

throttle = Float64()
throttle.data = 0.6

# does it cross expected boundaries in X seconds?
count = 0
timeout = 120
while(count < timeout):
# update timestamp for each published SP
att.header.stamp = rospy.Time.now()
self.pubAtt.publish(att)
self.pubThr.publish(throttle)

if (self.localPosition.pose.position.x > 5
and self.localPosition.pose.position.z > 5
and self.localPosition.pose.position.y < -5):
break
count = count + 1
self.rate.sleep()

self.assertTrue(count < timeout, "took too long to cross boundaries")


if __name__ == '__main__':
import rostest
rostest.rosrun(PKG, 'mavros_offboard_attctl_test', MavrosOffboardAttctlTest)
#unittest.main()
Loading

0 comments on commit 9574c6d

Please sign in to comment.