Merge pull request #1922 from UAVenture/sitl_test_updates

SITL test updates (cleanup)
This commit is contained in:
Lorenz Meier 2015-03-15 17:28:06 +01:00
commit 9935707acd
9 changed files with 170 additions and 187 deletions

View File

@ -37,7 +37,6 @@
#
PKG = 'px4'
import sys
import unittest
import rospy
@ -50,14 +49,18 @@ from manual_input import ManualInput
#
class ManualInputTest(unittest.TestCase):
def setUp(self):
self.actuator_status = actuator_armed()
self.control_mode = vehicle_control_mode()
#
# General callback functions used in tests
#
def actuator_armed_callback(self, data):
self.actuatorStatus = data
self.actuator_status = data
def vehicle_control_mode_callback(self, data):
self.controlMode = data
self.control_mode = data
#
# Test arming
@ -67,19 +70,19 @@ class ManualInputTest(unittest.TestCase):
rospy.Subscriber('iris/actuator_armed', actuator_armed, self.actuator_armed_callback)
rospy.Subscriber('iris/vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback)
man = ManualInput()
man_in = ManualInput()
# Test arming
man.arm()
self.assertEquals(self.actuatorStatus.armed, True, "did not arm")
man_in.arm()
self.assertEquals(self.actuator_status.armed, True, "did not arm")
# Test posctl
man.posctl()
self.assertTrue(self.controlMode.flag_control_position_enabled, "flag_control_position_enabled is not set")
man_in.posctl()
self.assertTrue(self.control_mode.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")
man_in.offboard()
self.assertTrue(self.control_mode.flag_control_offboard_enabled, "flag_control_offboard_enabled is not set")
if __name__ == '__main__':

View File

@ -37,7 +37,6 @@
#
PKG = 'px4'
import sys
import unittest
import rospy
@ -46,11 +45,8 @@ 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
@ -68,31 +64,34 @@ class DirectOffboardPosctlTest(unittest.TestCase):
rospy.init_node('test_node', anonymous=True)
rospy.Subscriber('iris/vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback)
rospy.Subscriber("iris/vehicle_local_position", vehicle_local_position, self.position_callback)
self.pubSpt = rospy.Publisher('iris/position_setpoint_triplet', position_setpoint_triplet, queue_size=10)
self.pub_spt = rospy.Publisher('iris/position_setpoint_triplet', position_setpoint_triplet, queue_size=10)
self.rate = rospy.Rate(10) # 10hz
self.has_pos = False
self.local_position = vehicle_local_position()
self.control_mode = vehicle_control_mode()
def tearDown(self):
if (self.fpa):
if self.fpa:
self.fpa.stop()
#
# General callback functions used in tests
#
def position_callback(self, data):
self.hasPos = True
self.localPosition = data
self.has_pos = True
self.local_position = data
def vehicle_control_mode_callback(self, data):
self.controlMode = data
self.control_mode = 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))
rospy.logdebug("current position %f, %f, %f" % (self.local_position.x, self.local_position.y, self.local_position.z))
desired = np.array((x, y, z))
pos = np.array((self.localPosition.x, self.localPosition.y, self.localPosition.z))
pos = np.array((self.local_position.x, self.local_position.y, self.local_position.z))
return linalg.norm(desired - pos) < offset
def reach_position(self, x, y, z, timeout):
@ -105,12 +104,12 @@ class DirectOffboardPosctlTest(unittest.TestCase):
pos.position_valid = True
stp = position_setpoint_triplet()
stp.current = pos
self.pubSpt.publish(stp)
self.pub_spt.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)):
while count < timeout:
if self.is_at_position(pos.x, pos.y, pos.z, 0.5):
break
count = count + 1
self.rate.sleep()
@ -121,22 +120,23 @@ class DirectOffboardPosctlTest(unittest.TestCase):
# Test offboard position control
#
def test_posctl(self):
manIn = ManualInput()
man_in = 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")
man_in.arm()
man_in.offboard()
self.assertTrue(self.control_mode.flag_armed, "flag_armed is not set")
self.assertTrue(self.control_mode.flag_control_offboard_enabled, "flag_control_offboard_enabled is not set")
self.assertTrue(self.control_mode.flag_control_position_enabled, "flag_control_position_enabled is not set")
# prepare flight path
positions = (
(0,0,0),
(2,2,-2),
(2,-2,-2),
(-2,-2,-2),
(2,2,-2))
(0, 0, 0),
(0, 0, -2),
(2, 2, -2),
(2, -2, -2),
(-2, -2, -2),
(2, 2, -2))
# flight path assertion
self.fpa = FlightPathAssertion(positions, 1, 0)
@ -147,12 +147,10 @@ class DirectOffboardPosctlTest(unittest.TestCase):
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
while count < timeout:
if not self.is_at_position(2, 2, -2, 0.5):
break
count = count + 1
self.rate.sleep()

View File

@ -2,7 +2,7 @@
<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="enable_ground_truth" default="true"/>
<arg name="log_file" default="iris"/>
<include file="$(find px4)/launch/gazebo_iris_empty_world.launch">

View File

@ -35,7 +35,6 @@
#
# @author Andreas Antener <andreas@uaventure.com>
#
import sys
import rospy
import threading
@ -48,7 +47,6 @@ from geometry_msgs.msg import Twist
from numpy import linalg
import numpy as np
import math
#
# Helper to test if vehicle stays on expected flight path.
@ -62,30 +60,52 @@ class FlightPathAssertion(threading.Thread):
# TODO: yaw validation
# TODO: fail main test thread
#
def __init__(self, positions, tunnelRadius = 1, yawOffset = 0.2):
def __init__(self, positions, tunnelRadius=1, yaw_offset=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)
rospy.Subscriber("iris/vehicle_local_position", vehicle_local_position, self.position_callback)
self.spawn_model = rospy.ServiceProxy('gazebo/spawn_sdf_model', SpawnModel)
self.set_model_state = rospy.ServiceProxy('gazebo/set_model_state', SetModelState)
self.delete_model = rospy.ServiceProxy('gazebo/delete_model', DeleteModel)
self.positions = positions
self.tunnelRadius = tunnelRadius
self.yawOffset = yawOffset
self.hasPos = False
self.shouldStop = False
self.tunnel_radius = tunnelRadius
self.yaw_offset = yaw_offset
self.has_pos = False
self.should_stop = False
self.center = positions[0]
self.endOfSegment = False
self.end_of_segment = False
self.failed = False
self.local_position = vehicle_local_position
def position_callback(self, data):
self.hasPos = True
self.localPosition = data
self.has_pos = True
self.local_position = 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(), "")
self.delete_model("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.tunnel_radius
self.spawn_model("indicator", xml, "", Pose(), "")
def position_indicator(self):
state = SetModelState()
@ -97,7 +117,7 @@ class FlightPathAssertion(threading.Thread):
state.pose = pose
state.twist = Twist()
state.reference_frame = ""
self.setModelState(state)
self.set_model_state(state)
def distance_to_line(self, a, b, pos):
v = b - a
@ -111,7 +131,7 @@ class FlightPathAssertion(threading.Thread):
c2 = np.dot(v, v)
if c2 <= c1: # after b
self.center = b
self.endOfSegment = True
self.end_of_segment = True
return linalg.norm(pos - b)
x = c1 / c2
@ -120,52 +140,58 @@ class FlightPathAssertion(threading.Thread):
return linalg.norm(pos - l)
def stop(self):
self.shouldStop = True
self.should_stop = True
def run(self):
rate = rospy.Rate(10) # 10hz
self.spawn_indicator()
current = 0
while not self.shouldStop:
if (self.hasPos):
count = 0
while not self.should_stop:
if self.has_pos:
# calculate distance to line segment between first two points
# if distances > tunnelRadius
# if distances > tunnel_radius
# exit with error
# advance current pos if not on the line anymore or distance to next point < tunnelRadius
# advance current pos if not on the line anymore or distance to next point < tunnel_radius
# 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]))
pos = np.array((self.local_position.x,
self.local_position.y,
self.local_position.z))
a_pos = np.array((self.positions[current][0],
self.positions[current][1],
self.positions[current][2]))
b_pos = 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)
dist = self.distance_to_line(a_pos, b_pos, pos)
b_dist = linalg.norm(pos - b_pos)
rospy.logdebug("distance to line: %f, distance to end: %f" % (dist, bDist))
rospy.logdebug("distance to line: %f, distance to end: %f" % (dist, b_dist))
if (dist > self.tunnelRadius):
msg = "left tunnel at position (%f, %f, %f)" % (self.localPosition.x, self.localPosition.y, self.localPosition.z)
if dist > self.tunnel_radius:
msg = "left tunnel at position (%f, %f, %f)" % (self.local_position.x, self.local_position.y, self.local_position.z)
rospy.logerr(msg)
self.failed = True
break
if (self.endOfSegment or bDist < self.tunnelRadius):
if self.end_of_segment or b_dist < self.tunnel_radius:
rospy.loginfo("next segment")
self.endOfSegment = False
self.end_of_segment = False
current = current + 1
if (current == len(self.positions) - 1):
if current == len(self.positions) - 1:
rospy.loginfo("no more positions")
break
rate.sleep()
count = count + 1
if count > 10 and not self.has_pos: # no position after 1 sec
rospy.logerr("no position")
self.failed = True
break

View File

@ -35,7 +35,6 @@
#
# @author Andreas Antener <andreas@uaventure.com>
#
import sys
import rospy
from px4.msg import manual_control_setpoint
@ -46,17 +45,12 @@ from std_msgs.msg import Header
#
# Manual input control helper
#
# 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. Probably this whole class will disappear once
# arming works correctly.
#
class ManualInput:
class ManualInput(object):
def __init__(self):
rospy.init_node('test_node', anonymous=True)
self.pubMcsp = rospy.Publisher('iris/manual_control_setpoint', manual_control_setpoint, queue_size=10)
self.pubOff = rospy.Publisher('iris/offboard_control_mode', offboard_control_mode, queue_size=10)
self.pubAtt = rospy.Publisher('iris/command/attitude', CommandAttitudeThrust, queue_size=10)
self.pub_mcsp = rospy.Publisher('iris/manual_control_setpoint', manual_control_setpoint, queue_size=10)
self.pub_off = rospy.Publisher('iris/offboard_control_mode', offboard_control_mode, queue_size=10)
def arm(self):
rate = rospy.Rate(10) # 10hz
@ -81,9 +75,7 @@ class ManualInput:
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)
self.pub_mcsp.publish(pos)
rate.sleep()
count = count + 1
@ -93,7 +85,7 @@ class ManualInput:
rospy.loginfo("arming")
time = rospy.get_rostime().now()
pos.timestamp = time.secs * 1e6 + time.nsecs / 1000
self.pubMcsp.publish(pos)
self.pub_mcsp.publish(pos)
rate.sleep()
count = count + 1
@ -118,7 +110,7 @@ class ManualInput:
rospy.loginfo("triggering posctl")
time = rospy.get_rostime().now()
pos.timestamp = time.secs * 1e6 + time.nsecs / 1000
self.pubMcsp.publish(pos)
self.pub_mcsp.publish(pos)
rate.sleep()
count = count + 1
@ -147,7 +139,7 @@ class ManualInput:
rospy.loginfo("setting offboard mode")
time = rospy.get_rostime().now()
mode.timestamp = time.secs * 1e6 + time.nsecs / 1000
self.pubOff.publish(mode)
self.pub_off.publish(mode)
rate.sleep()
count = count + 1
@ -169,7 +161,7 @@ class ManualInput:
rospy.loginfo("triggering offboard")
time = rospy.get_rostime().now()
pos.timestamp = time.secs * 1e6 + time.nsecs / 1000
self.pubMcsp.publish(pos)
self.pub_mcsp.publish(pos)
rate.sleep()
count = count + 1

View File

@ -37,29 +37,20 @@
#
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
# Tests flying a path in offboard control by sending attitude and thrust 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)
# For the test to be successful it needs to cross a certain boundary in time.
#
class MavrosOffboardAttctlTest(unittest.TestCase):
@ -68,45 +59,27 @@ class MavrosOffboardAttctlTest(unittest.TestCase):
rospy.wait_for_service('iris/mavros/cmd/arming', 30)
rospy.Subscriber('iris/vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback)
rospy.Subscriber("iris/mavros/position/local", PoseStamped, self.position_callback)
self.pubAtt = rospy.Publisher('iris/mavros/setpoint/attitude', PoseStamped, queue_size=10)
self.pubThr = rospy.Publisher('iris/mavros/setpoint/att_throttle', Float64, queue_size=10)
self.cmdArm = rospy.ServiceProxy("iris/mavros/cmd/arming", CommandBool)
self.pub_att = rospy.Publisher('iris/mavros/setpoint/attitude', PoseStamped, queue_size=10)
self.pub_thr = rospy.Publisher('iris/mavros/setpoint/att_throttle', Float64, queue_size=10)
self.rate = rospy.Rate(10) # 10hz
self.rateSec = rospy.Rate(1)
self.hasPos = False
self.controlMode = vehicle_control_mode()
self.has_pos = False
self.control_mode = vehicle_control_mode()
self.local_position = PoseStamped()
#
# General callback functions used in tests
#
def position_callback(self, data):
self.hasPos = True
self.localPosition = data
self.has_pos = True
self.local_position = data
def vehicle_control_mode_callback(self, data):
self.controlMode = data
#
# Helper methods
#
def arm(self):
return self.cmdArm(value=True)
self.control_mode = data
#
# Test offboard position control
#
def test_attctl(self):
# FIXME: this must go ASAP when arming is implemented
manIn = ManualInput()
manIn.arm()
manIn.offboard_attctl()
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()
@ -121,19 +94,23 @@ class MavrosOffboardAttctlTest(unittest.TestCase):
# does it cross expected boundaries in X seconds?
count = 0
timeout = 120
while(count < timeout):
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.pub_att.publish(att)
self.pub_thr.publish(throttle)
self.rate.sleep()
if (self.local_position.pose.position.x > 5
and self.local_position.pose.position.z > 5
and self.local_position.pose.position.y < -5):
break
count = count + 1
self.assertTrue(self.control_mode.flag_armed, "flag_armed is not set")
self.assertTrue(self.control_mode.flag_control_attitude_enabled, "flag_control_attitude_enabled is not set")
self.assertTrue(self.control_mode.flag_control_offboard_enabled, "flag_control_offboard_enabled is not set")
self.assertTrue(count < timeout, "took too long to cross boundaries")

View File

@ -37,7 +37,6 @@
#
PKG = 'px4'
import sys
import unittest
import rospy
import math
@ -49,9 +48,6 @@ 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
from mavros.srv import CommandBool
from manual_input import ManualInput
#
# Tests flying a path in offboard control by sending position setpoints
@ -64,37 +60,41 @@ class MavrosOffboardPosctlTest(unittest.TestCase):
def setUp(self):
rospy.init_node('test_node', anonymous=True)
rospy.wait_for_service('iris/mavros/cmd/arming', 30)
rospy.Subscriber('iris/vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback)
rospy.Subscriber("iris/mavros/position/local", PoseStamped, self.position_callback)
self.pubSpt = rospy.Publisher('iris/mavros/setpoint/local_position', PoseStamped, queue_size=10)
self.cmdArm = rospy.ServiceProxy("iris/mavros/cmd/arming", CommandBool)
self.pub_spt = rospy.Publisher('iris/mavros/setpoint/local_position', PoseStamped, queue_size=10)
self.rate = rospy.Rate(10) # 10hz
self.rateSec = rospy.Rate(1)
self.hasPos = False
self.controlMode = vehicle_control_mode()
self.has_pos = False
self.local_position = PoseStamped()
self.control_mode = vehicle_control_mode()
#
# General callback functions used in tests
#
def position_callback(self, data):
self.hasPos = True
self.localPosition = data
self.has_pos = True
self.local_position = data
def vehicle_control_mode_callback(self, data):
self.controlMode = data
self.control_mode = data
#
# Helper methods
#
def is_at_position(self, x, y, z, offset):
if(not self.hasPos):
if not self.has_pos:
return False
rospy.logdebug("current position %f, %f, %f" % (self.localPosition.pose.position.x, self.localPosition.pose.position.y, self.localPosition.pose.position.z))
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))
desired = np.array((x, y, z))
pos = np.array((self.localPosition.pose.position.x, self.localPosition.pose.position.y, self.localPosition.pose.position.z))
pos = np.array((self.local_position.pose.position.x,
self.local_position.pose.position.y,
self.local_position.pose.position.z))
return linalg.norm(desired - pos) < offset
def reach_position(self, x, y, z, timeout):
@ -114,57 +114,44 @@ class MavrosOffboardPosctlTest(unittest.TestCase):
# does it reach the position in X seconds?
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.pub_spt.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):
break
count = count + 1
self.rate.sleep()
self.assertTrue(count < timeout, "took too long to get to position")
def arm(self):
return self.cmdArm(value=True)
#
# Test offboard position control
#
def test_posctl(self):
# FIXME: this must go ASAP when arming is implemented
manIn = ManualInput()
manIn.arm()
manIn.offboard_posctl()
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 = (
(0,0,0),
(2,2,2),
(2,-2,2),
(-2,-2,2),
(2,2,2))
(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
while count < timeout:
if not self.is_at_position(2, 2, 2, 0.5):
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")
self.assertTrue(count == timeout, "position could not be held")

View File

@ -2,7 +2,7 @@
<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="enable_ground_truth" default="true"/>
<arg name="ns" default="iris"/>
<arg name="log_file" default="$(arg ns)"/>

View File

@ -3,7 +3,7 @@
<arg name="headless" default="false"/>
<arg name="gui" default="true"/>
<arg name="enable_logging" default="false"/>
<arg name="enable_ground_truth" default="false"/>
<arg name="enable_ground_truth" default="true"/>
<arg name="ns" default="ardrone"/>
<arg name="log_file" default="$(arg ns)"/>