2016-12-13 23:23:36 +01:00
#!/usr/bin/env python2
2016-04-25 17:04:52 +02:00
#***************************************************************************
#
2016-12-25 21:13:30 +01:00
# Copyright (c) 2015-2016 PX4 Development Team. All rights reserved.
2016-04-25 17:04:52 +02:00
#
# 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>
#
2016-12-13 23:23:36 +01:00
# The shebang of this file is currently Python2 because some
# dependencies such as pymavlink don't play well with Python3 yet.
2017-12-15 10:09:40 -05:00
from __future__ import division
2016-12-13 23:23:36 +01:00
2016-04-25 17:04:52 +02:00
PKG = ' px4 '
import unittest
import rospy
2016-12-23 22:18:01 -05:00
import glob
import json
2017-12-10 16:01:17 -05:00
import math
import os
2016-12-23 22:18:01 -05:00
import px4tools
2017-12-10 16:01:17 -05:00
import sys
from mavros import mavlink
from mavros . mission import QGroundControlWP
from pymavlink import mavutil
from threading import Thread
2017-12-15 10:09:40 -05:00
from mavros_msgs . msg import Altitude , ExtendedState , HomePosition , Mavlink , \
State , Waypoint
2017-12-10 16:01:17 -05:00
from mavros_msgs . srv import CommandBool , SetMode , WaypointPush
2016-04-25 17:04:52 +02:00
from sensor_msgs . msg import NavSatFix
2017-12-10 16:01:17 -05:00
2016-04-25 17:04:52 +02:00
2016-12-23 22:18:01 -05:00
def get_last_log ( ) :
try :
log_path = os . environ [ ' PX4_LOG_DIR ' ]
except KeyError :
2017-12-10 16:01:17 -05:00
log_path = os . path . join ( os . environ [ ' HOME ' ] ,
' .ros/rootfs/fs/microsd/log ' )
last_log_dir = sorted ( glob . glob ( os . path . join ( log_path , ' * ' ) ) ) [ - 1 ]
2016-12-23 22:18:01 -05:00
last_log = sorted ( glob . glob ( os . path . join ( last_log_dir , ' *.ulg ' ) ) ) [ - 1 ]
return last_log
2017-12-10 16:01:17 -05:00
2016-12-23 22:18:01 -05:00
def read_new_mission ( f ) :
d = json . load ( f )
current = True
for wp in d [ ' items ' ] :
yield Waypoint (
2017-12-10 16:01:17 -05:00
is_current = current ,
frame = int ( wp [ ' frame ' ] ) ,
command = int ( wp [ ' command ' ] ) ,
param1 = float ( wp [ ' param1 ' ] ) ,
param2 = float ( wp [ ' param2 ' ] ) ,
param3 = float ( wp [ ' param3 ' ] ) ,
param4 = float ( wp [ ' param4 ' ] ) ,
x_lat = float ( wp [ ' coordinate ' ] [ 0 ] ) ,
y_long = float ( wp [ ' coordinate ' ] [ 1 ] ) ,
z_alt = float ( wp [ ' coordinate ' ] [ 2 ] ) ,
autocontinue = bool ( wp [ ' autoContinue ' ] ) )
2016-12-23 22:18:01 -05:00
if current :
current = False
2017-12-10 16:01:17 -05:00
2016-04-25 17:04:52 +02:00
class MavrosMissionTest ( unittest . TestCase ) :
"""
Run a mission
"""
2017-12-15 10:09:40 -05:00
# dictionaries correspond to mavros ExtendedState msg
LAND_STATES = {
0 : ' UNDEFINED ' ,
1 : ' ON_GROUND ' ,
2 : ' IN_AIR ' ,
3 : ' TAKEOFF ' ,
4 : ' LANDING '
}
VTOL_STATES = {
0 : ' VTOL UNDEFINED ' ,
1 : ' VTOL MC->FW ' ,
2 : ' VTOL FW->MC ' ,
3 : ' VTOL MC ' ,
4 : ' VTOL FW '
}
2016-04-25 17:04:52 +02:00
def setUp ( self ) :
2017-12-10 16:01:17 -05:00
self . rate = rospy . Rate ( 10 ) # 10hz
2016-04-25 17:04:52 +02:00
self . has_global_pos = False
self . global_position = NavSatFix ( )
2016-04-25 21:04:22 +02:00
self . extended_state = ExtendedState ( )
2017-12-10 16:01:17 -05:00
self . altitude = Altitude ( )
self . state = State ( )
2016-04-25 21:04:22 +02:00
self . mc_rad = 5
2016-06-28 15:45:51 +02:00
self . fw_rad = 60
2016-05-15 16:33:44 +02:00
self . fw_alt_rad = 10
2017-12-10 16:01:17 -05:00
self . last_alt_d = None
self . last_pos_d = None
2016-06-28 11:34:29 +02:00
self . mission_name = " "
2017-12-15 10:09:40 -05:00
self . sub_topics_ready = {
key : False
for key in [ ' global_pos ' , ' home_pos ' , ' ext_state ' , ' alt ' , ' state ' ]
}
2016-04-25 17:04:52 +02:00
2017-12-10 16:01:17 -05:00
# setup ROS topics and services
2017-12-15 10:09:40 -05:00
try :
rospy . wait_for_service ( ' mavros/mission/push ' , 30 )
rospy . wait_for_service ( ' mavros/cmd/arming ' , 30 )
rospy . wait_for_service ( ' mavros/set_mode ' , 30 )
except rospy . ROSException :
self . fail ( " failed to connect to mavros services " )
2017-12-10 16:01:17 -05:00
self . wp_push_srv = rospy . ServiceProxy ( ' mavros/mission/push ' ,
WaypointPush )
self . set_arming_srv = rospy . ServiceProxy ( ' /mavros/cmd/arming ' ,
CommandBool )
self . set_mode_srv = rospy . ServiceProxy ( ' /mavros/set_mode ' , SetMode )
2017-12-15 10:09:40 -05:00
self . global_pos_sub = rospy . Subscriber ( ' mavros/global_position/global ' ,
NavSatFix ,
self . global_position_callback )
self . home_pos_sub = rospy . Subscriber ( ' mavros/home_position/home ' ,
HomePosition ,
self . home_position_callback )
self . ext_state_sub = rospy . Subscriber ( ' mavros/extended_state ' ,
ExtendedState ,
self . extended_state_callback )
self . alt_sub = rospy . Subscriber ( ' mavros/altitude ' , Altitude ,
self . altitude_callback )
self . state_sub = rospy . Subscriber ( ' mavros/state ' , State ,
self . state_callback )
2017-12-10 16:01:17 -05:00
self . mavlink_pub = rospy . Publisher ( ' mavlink/to ' , Mavlink , queue_size = 1 )
# need to simulate heartbeat to prevent datalink loss detection
self . hb_mav_msg = mavutil . mavlink . MAVLink_heartbeat_message (
mavutil . mavlink . MAV_TYPE_GCS , 0 , 0 , 0 , 0 , 0 )
self . hb_mav_msg . pack ( mavutil . mavlink . MAVLink ( ' ' , 2 , 1 ) )
self . hb_ros_msg = mavlink . convert_to_rosmsg ( self . hb_mav_msg )
self . hb_thread = Thread ( target = self . send_heartbeat , args = ( ) )
self . hb_thread . daemon = True
self . hb_thread . start ( )
2016-05-15 16:02:28 +02:00
2016-04-25 17:04:52 +02:00
def tearDown ( self ) :
pass
#
2017-12-15 10:09:40 -05:00
# Callback functions
2016-04-25 17:04:52 +02:00
#
def global_position_callback ( self , data ) :
self . global_position = data
2017-12-15 10:09:40 -05:00
if not self . sub_topics_ready [ ' global_pos ' ] :
self . sub_topics_ready [ ' global_pos ' ] = True
def home_position_callback ( self , data ) :
# this topic publishing seems to be a better indicator that the sim
# is ready, it's not actually needed
self . home_pos_sub . unregister ( )
if not self . sub_topics_ready [ ' home_pos ' ] :
self . sub_topics_ready [ ' home_pos ' ] = True
2016-04-25 17:04:52 +02:00
2016-04-25 21:04:22 +02:00
def extended_state_callback ( self , data ) :
2017-12-15 10:09:40 -05:00
if self . extended_state . vtol_state != data . vtol_state :
rospy . loginfo ( " VTOL state changed from {0} to {1} " . format (
self . VTOL_STATES . get ( self . extended_state . vtol_state ) ,
self . VTOL_STATES . get ( data . vtol_state ) ) )
if self . extended_state . landed_state != data . landed_state :
rospy . loginfo ( " landed state changed from {0} to {1} " . format (
self . LAND_STATES . get ( self . extended_state . landed_state ) ,
self . LAND_STATES . get ( data . landed_state ) ) )
2016-04-25 21:04:22 +02:00
self . extended_state = data
2017-12-10 16:01:17 -05:00
2017-12-15 10:09:40 -05:00
if not self . sub_topics_ready [ ' ext_state ' ] :
self . sub_topics_ready [ ' ext_state ' ] = True
2017-12-10 16:01:17 -05:00
def state_callback ( self , data ) :
2017-12-15 10:09:40 -05:00
if self . state . armed != data . armed :
rospy . loginfo ( " armed state changed from {0} to {1} " . format (
self . state . armed , data . armed ) )
if self . state . mode != data . mode :
rospy . loginfo ( " mode changed from {0} to {1} " . format (
self . state . mode , data . mode ) )
2017-12-10 16:01:17 -05:00
self . state = data
2017-12-15 10:09:40 -05:00
if not self . sub_topics_ready [ ' state ' ] :
self . sub_topics_ready [ ' state ' ] = True
2017-12-10 16:01:17 -05:00
def altitude_callback ( self , data ) :
self . altitude = data
2016-04-25 21:04:22 +02:00
2017-12-15 10:09:40 -05:00
# amsl has been observed to be nan while other fields are valid
if not self . sub_topics_ready [ ' alt ' ] and not math . isnan ( data . amsl ) :
self . sub_topics_ready [ ' alt ' ] = True
2016-04-25 17:04:52 +02:00
#
# Helper methods
#
2017-12-10 16:01:17 -05:00
def send_heartbeat ( self ) :
2017-12-15 10:09:40 -05:00
rate = rospy . Rate ( 2 ) # Hz
2017-12-10 16:01:17 -05:00
while not rospy . is_shutdown ( ) :
self . mavlink_pub . publish ( self . hb_ros_msg )
2017-12-15 10:09:40 -05:00
try : # prevent garbage in console output when thread is killed
rate . sleep ( )
2017-12-10 16:01:17 -05:00
except rospy . ROSInterruptException :
pass
2017-12-15 10:09:40 -05:00
def set_mode ( self , mode , timeout ) :
""" mode: PX4 mode string, timeout(int): seconds """
old_mode = self . state . mode
loop_freq = 1 # Hz
rate = rospy . Rate ( loop_freq )
mode_set = False
for i in xrange ( timeout * loop_freq ) :
if self . state . mode == mode :
mode_set = True
rospy . loginfo (
" set mode success | new mode: {0} , old mode: {1} | seconds: {2} of {3} " .
format ( mode , old_mode , i / loop_freq , timeout ) )
break
else :
try :
res = self . set_mode_srv ( 0 , mode ) # 0 is custom mode
if not res . mode_sent :
rospy . logerr ( " failed to send mode command " )
except rospy . ServiceException as e :
rospy . logerr ( e )
rate . sleep ( )
self . assertTrue ( mode_set , (
" failed to set mode | new mode: {0} , old mode: {1} | timeout(seconds): {2} " .
format ( mode , old_mode , timeout ) ) )
def set_arm ( self , arm , timeout ) :
""" arm: True to arm or False to disarm, timeout(int): seconds """
old_arm = self . state . armed
loop_freq = 1 # Hz
rate = rospy . Rate ( loop_freq )
arm_set = False
for i in xrange ( timeout * loop_freq ) :
if self . state . armed == arm :
arm_set = True
rospy . loginfo (
" set arm success | new arm: {0} , old arm: {1} | seconds: {2} of {3} " .
format ( arm , old_arm , i / loop_freq , timeout ) )
break
else :
try :
res = self . set_arming_srv ( arm )
if not res . success :
rospy . logerr ( " failed to send arm command " )
except rospy . ServiceException as e :
rospy . logerr ( e )
rate . sleep ( )
self . assertTrue ( arm_set , (
" failed to set arm | new arm: {0} , old arm: {1} | timeout(seconds): {2} " .
format ( arm , old_arm , timeout ) ) )
2016-05-15 16:33:44 +02:00
def is_at_position ( self , lat , lon , alt , xy_offset , z_offset ) :
2017-12-15 10:09:40 -05:00
""" alt(amsl), xy_offset, z_offset: meters """
2017-12-10 16:01:17 -05:00
R = 6371000 # metres
2016-04-25 17:04:52 +02:00
rlat1 = math . radians ( lat )
rlat2 = math . radians ( self . global_position . latitude )
rlat_d = math . radians ( self . global_position . latitude - lat )
rlon_d = math . radians ( self . global_position . longitude - lon )
2017-12-10 16:01:17 -05:00
a = ( math . sin ( rlat_d / 2 ) * math . sin ( rlat_d / 2 ) + math . cos ( rlat1 ) *
math . cos ( rlat2 ) * math . sin ( rlon_d / 2 ) * math . sin ( rlon_d / 2 ) )
c = 2 * math . atan2 ( math . sqrt ( a ) , math . sqrt ( 1 - a ) )
2016-04-25 17:04:52 +02:00
d = R * c
2017-12-10 16:01:17 -05:00
alt_d = abs ( alt - self . altitude . amsl )
2016-05-15 16:02:28 +02:00
# remember best distances
2017-12-10 16:01:17 -05:00
if not self . last_pos_d or self . last_pos_d > d :
2016-05-15 16:02:28 +02:00
self . last_pos_d = d
2017-12-10 16:01:17 -05:00
if not self . last_alt_d or self . last_alt_d > alt_d :
2016-05-15 16:02:28 +02:00
self . last_alt_d = alt_d
2017-12-10 16:01:17 -05:00
rospy . logdebug ( " d: {0} , alt_d: {1} " . format ( d , alt_d ) )
2016-05-15 16:33:44 +02:00
return d < xy_offset and alt_d < z_offset
2016-04-25 17:04:52 +02:00
2016-05-15 16:02:28 +02:00
def reach_position ( self , lat , lon , alt , timeout , index ) :
2017-12-15 10:09:40 -05:00
""" alt(amsl): meters, timeout(int): seconds """
2016-05-15 16:02:28 +02:00
# reset best distances
2017-12-10 16:01:17 -05:00
self . last_alt_d = None
self . last_pos_d = None
2016-05-15 16:02:28 +02:00
2017-12-10 16:01:17 -05:00
rospy . loginfo (
2017-12-15 10:09:40 -05:00
" trying to reach waypoint | lat: {0:13.9f} , lon: {1:13.9f} , alt: {2:6.2f} , index: {3} " .
format ( lat , lon , alt , index ) )
2016-06-27 22:47:18 +02:00
2017-12-15 10:09:40 -05:00
# does it reach the position in 'timeout' seconds?
loop_freq = 10 # Hz
rate = rospy . Rate ( loop_freq )
2017-12-10 16:01:17 -05:00
reached = False
2017-12-15 10:09:40 -05:00
for i in xrange ( timeout * loop_freq ) :
2016-06-28 15:45:51 +02:00
# use MC radius by default
# FIXME: also check MAV_TYPE from system status, otherwise pure fixed-wing won't work
2016-05-15 16:33:44 +02:00
xy_radius = self . mc_rad
z_radius = self . mc_rad
2016-06-28 15:45:51 +02:00
# use FW radius if in FW or in transition
2017-12-10 16:01:17 -05:00
if ( self . extended_state . vtol_state == ExtendedState . VTOL_STATE_FW
or self . extended_state . vtol_state ==
ExtendedState . VTOL_STATE_TRANSITION_TO_MC or
self . extended_state . vtol_state ==
ExtendedState . VTOL_STATE_TRANSITION_TO_FW ) :
2016-05-15 16:33:44 +02:00
xy_radius = self . fw_rad
z_radius = self . fw_alt_rad
2016-04-25 21:04:22 +02:00
2016-05-15 16:33:44 +02:00
if self . is_at_position ( lat , lon , alt , xy_radius , z_radius ) :
2017-12-10 16:01:17 -05:00
reached = True
rospy . loginfo (
2017-12-15 10:09:40 -05:00
" position reached | pos_d: {0} , alt_d: {1} , index: {2} | seconds: {3} of {4} " .
format ( self . last_pos_d , self . last_alt_d , index , i /
loop_freq , timeout ) )
2016-04-25 17:04:52 +02:00
break
2016-06-27 22:47:18 +02:00
2017-12-15 10:09:40 -05:00
rate . sleep ( )
2016-12-25 17:01:51 +01:00
2017-12-10 16:01:17 -05:00
self . assertTrue ( reached , (
2017-12-15 10:09:40 -05:00
" ( {0} ) took too long to get to position | lat: {1:13.9f} , lon: {2:13.9f} , alt: {3:6.2f} , xy off: {4} , z off: {5} , pos_d: {6} , alt_d: {7} , VTOL state: {8} , index: {9} | timeout(seconds): {10} " .
2017-12-10 16:01:17 -05:00
format ( self . mission_name , lat , lon , alt , xy_radius , z_radius ,
2017-12-15 10:09:40 -05:00
self . last_pos_d , self . last_alt_d ,
self . VTOL_STATES . get ( self . extended_state . vtol_state ) , index ,
timeout ) ) )
def wait_for_topics ( self , timeout ) :
""" wait for simulation to be ready, make sure we ' re getting topic info
from all topics by checking dictionary of flag values set in callbacks ,
timeout ( int ) : seconds """
rospy . loginfo ( " waiting for simulation topics to be ready " )
loop_freq = 1 # Hz
rate = rospy . Rate ( loop_freq )
simulation_ready = False
for i in xrange ( timeout * loop_freq ) :
if all ( value for value in self . sub_topics_ready . values ( ) ) :
simulation_ready = True
rospy . loginfo ( " simulation topics ready | seconds: {0} of {1} " .
format ( i / loop_freq , timeout ) )
break
rate . sleep ( )
self . assertTrue ( simulation_ready , (
" failed to hear from all subscribed simulation topics | topic ready flags: {0} | timeout(seconds): {1} " .
format ( self . sub_topics_ready , timeout ) ) )
def wait_on_landed_state ( self , desired_landed_state , timeout , index ) :
rospy . loginfo (
" waiting for landed state | state: {0} , index: {1} " . format (
self . LAND_STATES . get ( desired_landed_state ) , index ) )
loop_freq = 10 # Hz
rate = rospy . Rate ( loop_freq )
landed_state_confirmed = False
for i in xrange ( timeout * loop_freq ) :
if self . extended_state . landed_state == desired_landed_state :
landed_state_confirmed = True
2017-12-10 16:01:17 -05:00
rospy . loginfo (
2017-12-15 10:09:40 -05:00
" landed state confirmed | state: {0} , index {1} " . format (
self . LAND_STATES . get ( desired_landed_state ) , index ) )
2016-06-27 22:47:18 +02:00
break
2017-12-15 10:09:40 -05:00
rate . sleep ( )
2016-06-27 22:47:18 +02:00
2017-12-15 10:09:40 -05:00
self . assertTrue ( landed_state_confirmed , (
" ( {0} ) landed state not detected | desired: {1} , current: {2} | index: {3} , timeout(seconds): {4} " .
format ( self . mission_name ,
self . LAND_STATES . get ( desired_landed_state ) ,
self . LAND_STATES . get ( self . extended_state . landed_state ) ,
index , timeout ) ) )
2016-06-27 22:47:18 +02:00
def wait_on_transition ( self , transition , timeout , index ) :
2017-12-15 10:09:40 -05:00
""" Wait for VTOL transition, timeout(int): seconds """
2017-12-10 16:01:17 -05:00
rospy . loginfo (
2017-12-15 10:09:40 -05:00
" waiting for VTOL transition | transition: {0} , index: {1} " . format (
self . VTOL_STATES . get ( transition ) , index ) )
loop_freq = 10 # Hz
rate = rospy . Rate ( loop_freq )
2017-12-10 16:01:17 -05:00
transitioned = False
2017-12-15 10:09:40 -05:00
for i in xrange ( timeout * loop_freq ) :
2016-06-27 22:47:18 +02:00
# transition to MC
2016-06-27 23:32:29 +02:00
if ( transition == ExtendedState . VTOL_STATE_MC and
2017-12-10 16:01:17 -05:00
self . extended_state . vtol_state ==
ExtendedState . VTOL_STATE_MC ) :
2017-12-15 10:09:40 -05:00
rospy . loginfo (
" transitioned | index: {0} | seconds: {1} of {2} " . format (
index , i / loop_freq , timeout ) )
2017-12-10 16:01:17 -05:00
transitioned = True
2016-06-27 22:47:18 +02:00
break
# transition to FW
2016-06-27 23:32:29 +02:00
if ( transition == ExtendedState . VTOL_STATE_FW and
2017-12-10 16:01:17 -05:00
self . extended_state . vtol_state ==
ExtendedState . VTOL_STATE_FW ) :
2017-12-15 10:09:40 -05:00
rospy . loginfo (
" transitioned | index: {0} | seconds: {1} of {2} " . format (
index , i / loop_freq , timeout ) )
2017-12-10 16:01:17 -05:00
transitioned = True
2016-06-27 22:47:18 +02:00
break
2017-12-15 10:09:40 -05:00
rate . sleep ( )
2016-06-27 22:47:18 +02:00
2017-12-10 16:01:17 -05:00
self . assertTrue ( transitioned , (
2017-12-15 10:09:40 -05:00
" ( {0} ) transition not detected | index: {1} | timeout(seconds): {2} , " .
format ( self . mission_name , index , timeout ) ) )
2016-04-25 17:04:52 +02:00
2017-12-10 16:01:17 -05:00
#
# Test method
#
2016-04-25 17:04:52 +02:00
def test_mission ( self ) :
""" Test mission """
if len ( sys . argv ) < 2 :
2016-04-25 21:04:22 +02:00
self . fail ( " usage: mission_test.py mission_file " )
2016-04-25 17:04:52 +02:00
return
2016-06-28 11:34:29 +02:00
self . mission_name = sys . argv [ 1 ]
2017-12-10 16:01:17 -05:00
mission_file = os . path . dirname (
os . path . realpath ( __file__ ) ) + " / " + sys . argv [ 1 ]
2016-04-25 21:04:22 +02:00
2017-12-10 16:01:17 -05:00
rospy . loginfo ( " reading mission {0} " . format ( mission_file ) )
2016-04-25 17:04:52 +02:00
wps = [ ]
2016-12-23 22:18:01 -05:00
with open ( mission_file , ' r ' ) as f :
mission_ext = os . path . splitext ( mission_file ) [ 1 ]
if mission_ext == ' .mission ' :
2017-04-17 09:45:43 -04:00
rospy . loginfo ( " new style mission file detected " )
2016-12-23 22:18:01 -05:00
for waypoint in read_new_mission ( f ) :
wps . append ( waypoint )
rospy . logdebug ( waypoint )
elif mission_ext == ' .txt ' :
2017-04-17 09:45:43 -04:00
rospy . loginfo ( " old style mission file detected " )
2016-12-23 22:18:01 -05:00
mission = QGroundControlWP ( )
for waypoint in mission . read ( f ) :
wps . append ( waypoint )
rospy . logdebug ( waypoint )
else :
raise IOError ( ' unknown mission file extension ' , mission_ext )
2016-04-25 17:04:52 +02:00
2017-12-15 10:09:40 -05:00
# delay starting the mission
self . wait_for_topics ( 30 )
2016-04-25 17:04:52 +02:00
rospy . loginfo ( " send mission " )
2017-12-10 16:01:17 -05:00
result = False
try :
res = self . wp_push_srv ( start_index = 0 , waypoints = wps )
result = res . success
except rospy . ServiceException as e :
rospy . logerr ( e )
self . assertTrue (
result ,
" ( {0} ) mission could not be transfered " . format ( self . mission_name ) )
2017-12-15 10:09:40 -05:00
# make sure the simulation is ready to start the mission
self . wait_on_landed_state ( ExtendedState . LANDED_STATE_ON_GROUND , 10 , - 1 )
rospy . loginfo ( " seting mission mode " )
self . set_mode ( " AUTO.MISSION " , 5 )
rospy . loginfo ( " arming " )
self . set_arm ( True , 5 )
2016-04-25 17:04:52 +02:00
rospy . loginfo ( " run mission " )
2017-12-10 16:01:17 -05:00
for index , waypoint in enumerate ( wps ) :
2016-06-27 22:47:18 +02:00
# only check position for waypoints where this makes sense
if waypoint . frame == Waypoint . FRAME_GLOBAL_REL_ALT or waypoint . frame == Waypoint . FRAME_GLOBAL :
alt = waypoint . z_alt
if waypoint . frame == Waypoint . FRAME_GLOBAL_REL_ALT :
2017-12-10 16:01:17 -05:00
alt + = self . altitude . amsl - self . altitude . relative
2016-12-25 17:01:51 +01:00
2017-12-15 10:09:40 -05:00
self . reach_position ( waypoint . x_lat , waypoint . y_long , alt , 60 ,
2017-12-10 16:01:17 -05:00
index )
2016-06-27 22:47:18 +02:00
2016-06-27 23:32:29 +02:00
# check if VTOL transition happens if applicable
if waypoint . command == 84 or waypoint . command == 85 or waypoint . command == 3000 :
transition = waypoint . param1
2017-12-10 16:01:17 -05:00
if waypoint . command == 84 : # VTOL takeoff implies transition to FW
2016-06-27 23:32:29 +02:00
transition = ExtendedState . VTOL_STATE_FW
2017-12-10 16:01:17 -05:00
if waypoint . command == 85 : # VTOL takeoff implies transition to MC
2016-06-27 23:32:29 +02:00
transition = ExtendedState . VTOL_STATE_MC
2017-12-15 10:09:40 -05:00
self . wait_on_transition ( transition , 60 , index )
2016-06-27 23:32:29 +02:00
2016-06-27 22:47:18 +02:00
# after reaching position, wait for landing detection if applicable
if waypoint . command == 85 or waypoint . command == 21 :
2017-12-15 10:09:40 -05:00
self . wait_on_landed_state ( ExtendedState . LANDED_STATE_ON_GROUND ,
60 , index )
2016-06-27 22:47:18 +02:00
2017-12-15 10:09:40 -05:00
rospy . loginfo ( " disarming " )
self . set_arm ( False , 5 )
2016-04-25 17:04:52 +02:00
2016-12-23 22:18:01 -05:00
rospy . loginfo ( " mission done, calculating performance metrics " )
last_log = get_last_log ( )
2017-12-10 16:01:17 -05:00
rospy . loginfo ( " log file {0} " . format ( last_log ) )
2017-12-15 10:09:40 -05:00
data = px4tools . read_ulog ( last_log ) . concat ( dt = 0.1 )
data = px4tools . compute_data ( data )
2016-12-23 22:18:01 -05:00
res = px4tools . estimator_analysis ( data , False )
# enforce performance
2017-12-10 16:01:17 -05:00
self . assertTrue ( abs ( res [ ' roll_error_mean ' ] ) < 5.0 , str ( res ) )
2016-12-23 22:18:01 -05:00
self . assertTrue ( abs ( res [ ' pitch_error_mean ' ] ) < 5.0 , str ( res ) )
self . assertTrue ( abs ( res [ ' yaw_error_mean ' ] ) < 5.0 , str ( res ) )
self . assertTrue ( res [ ' roll_error_std ' ] < 5.0 , str ( res ) )
self . assertTrue ( res [ ' pitch_error_std ' ] < 5.0 , str ( res ) )
self . assertTrue ( res [ ' yaw_error_std ' ] < 5.0 , str ( res ) )
2016-04-25 17:04:52 +02:00
2017-12-10 16:01:17 -05:00
2016-04-25 17:04:52 +02:00
if __name__ == ' __main__ ' :
import rostest
2017-12-10 16:01:17 -05:00
rospy . init_node ( ' test_node ' , anonymous = True )
2016-06-28 11:11:46 +02:00
name = " mavros_mission_test "
if len ( sys . argv ) > 1 :
name + = " - %s " % sys . argv [ 1 ]
rostest . rosrun ( PKG , name , MavrosMissionTest )