Merge pull request #1854 from UAVenture/mavros_arming

Mavros test updates
This commit is contained in:
Lorenz Meier 2015-03-02 08:31:34 +01:00
commit 9574c6dd2a
11 changed files with 239 additions and 51 deletions

View File

@ -42,9 +42,13 @@ import unittest
import rospy import rospy
from px4.msg import actuator_armed from px4.msg import actuator_armed
from px4.msg import vehicle_control_mode
from manual_input import ManualInput 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 # General callback functions used in tests
@ -52,22 +56,32 @@ class ArmTest(unittest.TestCase):
def actuator_armed_callback(self, data): def actuator_armed_callback(self, data):
self.actuatorStatus = data self.actuatorStatus = data
def vehicle_control_mode_callback(self, data):
self.controlMode = data
# #
# Test arming # Test arming
# #
def test_arm(self): def test_manual_input(self):
rospy.init_node('test_node', anonymous=True) 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 man = ManualInput()
arm = ManualInput()
arm.arm()
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__': if __name__ == '__main__':
import rostest import rostest
rostest.rosrun(PKG, 'arm_test', ArmTest) rostest.rosrun(PKG, 'direct_manual_input_test', ManualInputTest)

View File

@ -55,8 +55,14 @@ from std_msgs.msg import Header
from manual_input import ManualInput from manual_input import ManualInput
from flight_path_assertion import FlightPathAssertion 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): def setUp(self):
rospy.init_node('test_node', anonymous=True) rospy.init_node('test_node', anonymous=True)
@ -112,7 +118,7 @@ class OffboardPosctlTest(unittest.TestCase):
self.assertTrue(count < timeout, "took too long to get to position") self.assertTrue(count < timeout, "took too long to get to position")
# #
# Test offboard POSCTL # Test offboard position control
# #
def test_posctl(self): def test_posctl(self):
manIn = ManualInput() manIn = ManualInput()
@ -124,7 +130,7 @@ class OffboardPosctlTest(unittest.TestCase):
self.assertTrue(self.controlMode.flag_control_offboard_enabled, "flag_control_offboard_enabled 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") self.assertTrue(self.controlMode.flag_control_position_enabled, "flag_control_position_enabled is not set")
# prepare flight path assertion # prepare flight path
positions = ( positions = (
(0,0,0), (0,0,0),
(2,2,-2), (2,2,-2),
@ -132,6 +138,7 @@ class OffboardPosctlTest(unittest.TestCase):
(-2,-2,-2), (-2,-2,-2),
(2,2,-2)) (2,2,-2))
# flight path assertion
self.fpa = FlightPathAssertion(positions, 1, 0) self.fpa = FlightPathAssertion(positions, 1, 0)
self.fpa.start() self.fpa.start()
@ -156,5 +163,5 @@ class OffboardPosctlTest(unittest.TestCase):
if __name__ == '__main__': if __name__ == '__main__':
import rostest import rostest
rostest.rosrun(PKG, 'posctl_test', OffboardPosctlTest) rostest.rosrun(PKG, 'direct_offboard_posctl_test', DirectOffboardPosctlTest)
#unittest.main() #unittest.main()

View File

@ -13,6 +13,6 @@
<arg name="log_file" value="$(arg log_file)"/> <arg name="log_file" value="$(arg log_file)"/>
</include> </include>
<test test-name="direct_arm" pkg="px4" type="direct_arm_test.py" /> <test test-name="direct_manual_input_test" pkg="px4" type="direct_manual_input_test.py" />
<test test-name="direct_offboard_posctl" pkg="px4" type="direct_offboard_posctl_test.py" /> <test test-name="direct_offboard_posctl_test" pkg="px4" type="direct_offboard_posctl_test.py" />
</launch> </launch>

View File

@ -51,7 +51,7 @@ import numpy as np
import math 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): class FlightPathAssertion(threading.Thread):

View File

@ -45,7 +45,7 @@ from std_msgs.msg import Header
# #
# Manual input control helper # 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. # the simulator does not instantiate our controller.
# #
class ManualInput: class ManualInput:
@ -74,7 +74,7 @@ class ManualInput:
pos.offboard_switch = 3 pos.offboard_switch = 3
count = 0 count = 0
while not rospy.is_shutdown() and count < 10: while not rospy.is_shutdown() and count < 5:
rospy.loginfo("zeroing") rospy.loginfo("zeroing")
time = rospy.get_rostime().now() time = rospy.get_rostime().now()
pos.timestamp = time.secs * 1e6 + time.nsecs / 1000 pos.timestamp = time.secs * 1e6 + time.nsecs / 1000
@ -86,7 +86,7 @@ class ManualInput:
pos.r = 1 pos.r = 1
count = 0 count = 0
while not rospy.is_shutdown() and count < 10: while not rospy.is_shutdown() and count < 5:
rospy.loginfo("arming") rospy.loginfo("arming")
time = rospy.get_rostime().now() time = rospy.get_rostime().now()
pos.timestamp = time.secs * 1e6 + time.nsecs / 1000 pos.timestamp = time.secs * 1e6 + time.nsecs / 1000
@ -111,7 +111,7 @@ class ManualInput:
pos.offboard_switch = 3 pos.offboard_switch = 3
count = 0 count = 0
while not rospy.is_shutdown() and count < 10: while not rospy.is_shutdown() and count < 5:
rospy.loginfo("triggering posctl") rospy.loginfo("triggering posctl")
time = rospy.get_rostime().now() time = rospy.get_rostime().now()
pos.timestamp = time.secs * 1e6 + time.nsecs / 1000 pos.timestamp = time.secs * 1e6 + time.nsecs / 1000
@ -122,7 +122,7 @@ class ManualInput:
def offboard(self): def offboard(self):
rate = rospy.Rate(10) # 10hz rate = rospy.Rate(10) # 10hz
# triggers posctl # triggers offboard
pos = manual_control_setpoint() pos = manual_control_setpoint()
pos.x = 0 pos.x = 0
pos.z = 0 pos.z = 0
@ -136,8 +136,8 @@ class ManualInput:
pos.offboard_switch = 1 pos.offboard_switch = 1
count = 0 count = 0
while not rospy.is_shutdown() and count < 10: while not rospy.is_shutdown() and count < 5:
rospy.loginfo("triggering posctl") rospy.loginfo("triggering offboard")
time = rospy.get_rostime().now() time = rospy.get_rostime().now()
pos.timestamp = time.secs * 1e6 + time.nsecs / 1000 pos.timestamp = time.secs * 1e6 + time.nsecs / 1000
self.pubMcsp.publish(pos) self.pubMcsp.publish(pos)

View File

@ -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()

View File

@ -49,16 +49,30 @@ from px4.msg import vehicle_control_mode
from std_msgs.msg import Header from std_msgs.msg import Header
from geometry_msgs.msg import PoseStamped, Quaternion from geometry_msgs.msg import PoseStamped, Quaternion
from tf.transformations import quaternion_from_euler from tf.transformations import quaternion_from_euler
from mavros.srv import CommandBool
class OffboardPosctlTest(unittest.TestCase): 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 MavrosOffboardPosctlTest(unittest.TestCase):
def setUp(self): def setUp(self):
rospy.init_node('test_node', anonymous=True) 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('px4_multicopter/vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback)
rospy.Subscriber("px4_multicopter/mavros/position/local", PoseStamped, self.position_callback) rospy.Subscriber("mavros/position/local", PoseStamped, self.position_callback)
self.pubSpt = rospy.Publisher('px4_multicopter/mavros/setpoint/local_position', PoseStamped, queue_size=10) self.pubSpt = rospy.Publisher('mavros/setpoint/local_position', PoseStamped, queue_size=10)
self.cmdArm = rospy.ServiceProxy("mavros/cmd/arming", CommandBool)
self.rate = rospy.Rate(10) # 10hz self.rate = rospy.Rate(10) # 10hz
self.rateSec = rospy.Rate(1)
self.hasPos = False self.hasPos = False
self.controlMode = vehicle_control_mode()
# #
# General callback functions used in tests # General callback functions used in tests
@ -88,7 +102,6 @@ class OffboardPosctlTest(unittest.TestCase):
pos = PoseStamped() pos = PoseStamped()
pos.header = Header() pos.header = Header()
pos.header.frame_id = "base_footprint" pos.header.frame_id = "base_footprint"
pos.header.stamp = rospy.Time.now()
pos.pose.position.x = x pos.pose.position.x = x
pos.pose.position.y = y pos.pose.position.y = y
pos.pose.position.z = z pos.pose.position.z = z
@ -102,6 +115,8 @@ class OffboardPosctlTest(unittest.TestCase):
# does it reach the position in X seconds? # does it reach the position in X seconds?
count = 0 count = 0
while(count < timeout): while(count < timeout):
# update timestamp for each published SP
pos.header.stamp = rospy.Time.now()
self.pubSpt.publish(pos) self.pubSpt.publish(pos)
if(self.is_at_position(pos.pose.position.x, pos.pose.position.y, pos.pose.position.z, 0.5)): if(self.is_at_position(pos.pose.position.x, pos.pose.position.y, pos.pose.position.z, 0.5)):
@ -111,11 +126,24 @@ class OffboardPosctlTest(unittest.TestCase):
self.assertTrue(count < timeout, "took too long to get to position") self.assertTrue(count < timeout, "took too long to get to position")
def arm(self):
return self.cmdArm(value=True)
# #
# Test offboard POSCTL # Test offboard position control
# #
def test_posctl(self): def test_posctl(self):
# prepare flight path assertion # FIXME: this must go ASAP when arming is implemented
manIn = ManualInput()
manIn.arm()
manIn.offboard()
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")
# prepare flight path
positions = ( positions = (
(0,0,0), (0,0,0),
(2,2,2), (2,2,2),
@ -142,5 +170,5 @@ class OffboardPosctlTest(unittest.TestCase):
if __name__ == '__main__': if __name__ == '__main__':
import rostest import rostest
rostest.rosrun(PKG, 'posctl_test', OffboardPosctlTest) rostest.rosrun(PKG, 'mavros_offboard_posctl_test', MavrosOffboardPosctlTest)
#unittest.main() #unittest.main()

View File

@ -15,4 +15,5 @@
<include file="$(find px4)/launch/mavros_sitl.launch" /> <include file="$(find px4)/launch/mavros_sitl.launch" />
<test test-name="mavros_offboard_posctl_test" pkg="px4" type="mavros_offboard_posctl_test.py" /> <test test-name="mavros_offboard_posctl_test" pkg="px4" type="mavros_offboard_posctl_test.py" />
<test test-name="mavros_offboard_attctl_test" pkg="px4" type="mavros_offboard_attctl_test.py" />
</launch> </launch>

View File

@ -3,8 +3,7 @@
<include file="$(find px4)/launch/gazebo_ardrone_empty_world.launch" /> <include file="$(find px4)/launch/gazebo_ardrone_empty_world.launch" />
<include file="$(find px4)/launch/mavros_sitl.launch" /> <include file="$(find px4)/launch/mavros_sitl.launch" />
<group ns="px4_multicopter">
<node pkg="px4" name="demo_offboard_attitude_setpoints" type="demo_offboard_attitude_setpoints"/> <node pkg="px4" name="demo_offboard_attitude_setpoints" type="demo_offboard_attitude_setpoints"/>
</group>
</launch> </launch>

View File

@ -3,8 +3,7 @@
<include file="$(find px4)/launch/gazebo_ardrone_empty_world.launch" /> <include file="$(find px4)/launch/gazebo_ardrone_empty_world.launch" />
<include file="$(find px4)/launch/mavros_sitl.launch" /> <include file="$(find px4)/launch/mavros_sitl.launch" />
<group ns="px4_multicopter">
<node pkg="px4" name="demo_offboard_position_setpoints" type="demo_offboard_position_setpoints"/> <node pkg="px4" name="demo_offboard_position_setpoints" type="demo_offboard_position_setpoints"/>
</group>
</launch> </launch>

View File

@ -2,7 +2,6 @@
<!-- vim: set ft=xml noet : --> <!-- vim: set ft=xml noet : -->
<!-- example launch script for PX4 based FCU's --> <!-- example launch script for PX4 based FCU's -->
<group ns="px4_multicopter">
<arg name="fcu_url" default="udp://localhost:14560@localhost:14565" /> <arg name="fcu_url" default="udp://localhost:14560@localhost:14565" />
<arg name="gcs_url" default="" /> <arg name="gcs_url" default="" />
<arg name="tgt_system" default="1" /> <arg name="tgt_system" default="1" />
@ -19,5 +18,4 @@
<arg name="tgt_system" value="$(arg tgt_system)" /> <arg name="tgt_system" value="$(arg tgt_system)" />
<arg name="tgt_component" value="$(arg tgt_component)" /> <arg name="tgt_component" value="$(arg tgt_component)" />
</include> </include>
</group>
</launch> </launch>