CI: allow Gazebo to restart on crash (#8817)

* add respawn_gazebo arg to be used with empty_world.launch
* catch rospy sleep method's exceptions
* fix copy-paste mistake in land state failure message
This commit is contained in:
Anthony Lamping 2018-02-06 15:11:09 -05:00 committed by Daniel Agar
parent b40323b8d8
commit 86ae744266
11 changed files with 60 additions and 13 deletions

View File

@ -132,7 +132,10 @@ class MavrosOffboardAttctlTest(MavrosTestCommon):
crossed = True
break
rate.sleep()
try:
rate.sleep()
except rospy.ROSException as e:
self.fail(e)
self.assertTrue(crossed, (
"took too long to cross boundaries | current position x: {0:.2f}, y: {1:.2f}, z: {2:.2f} | timeout(seconds): {3}".

View File

@ -139,7 +139,10 @@ class MavrosOffboardPosctlTest(MavrosTestCommon):
reached = True
break
rate.sleep()
try:
rate.sleep()
except rospy.ROSException as e:
self.fail(e)
self.assertTrue(reached, (
"took too long to get to position | current position x: {0:.2f}, y: {1:.2f}, z: {2:.2f} | timeout(seconds): {3}".

View File

@ -48,7 +48,7 @@ class MavrosTestCommon(unittest.TestCase):
except rospy.ROSException:
self.fail("failed to connect to services")
self.get_param_srv = rospy.ServiceProxy('mavros/param/get', ParamGet)
self.set_arming_srv = rospy.ServiceProxy('/mavros/cmd/arming',
self.set_arming_srv = rospy.ServiceProxy('mavros/cmd/arming',
CommandBool)
self.set_mode_srv = rospy.ServiceProxy('mavros/set_mode', SetMode)
self.wp_clear_srv = rospy.ServiceProxy('mavros/mission/clear',
@ -184,7 +184,10 @@ class MavrosTestCommon(unittest.TestCase):
except rospy.ServiceException as e:
rospy.logerr(e)
rate.sleep()
try:
rate.sleep()
except rospy.ROSException as e:
self.fail(e)
self.assertTrue(arm_set, (
"failed to set arm | new arm: {0}, old arm: {1} | timeout(seconds): {2}".
@ -211,7 +214,10 @@ class MavrosTestCommon(unittest.TestCase):
except rospy.ServiceException as e:
rospy.logerr(e)
rate.sleep()
try:
rate.sleep()
except rospy.ROSException as e:
self.fail(e)
self.assertTrue(mode_set, (
"failed to set mode | new mode: {0}, old mode: {1} | timeout(seconds): {2}".
@ -232,7 +238,10 @@ class MavrosTestCommon(unittest.TestCase):
format(i / loop_freq, timeout))
break
rate.sleep()
try:
rate.sleep()
except rospy.ROSException as e:
self.fail(e)
self.assertTrue(simulation_ready, (
"failed to hear from all subscribed simulation topics | topic ready flags: {0} | timeout(seconds): {1}".
@ -252,13 +261,16 @@ class MavrosTestCommon(unittest.TestCase):
format(i / loop_freq, timeout))
break
rate.sleep()
try:
rate.sleep()
except rospy.ROSException as e:
self.fail(e)
self.assertTrue(landed_state_confirmed, (
"landed state not detected | desired: {0}, current: {1} | index: {2}, timeout(seconds): {3}".
format(mavutil.mavlink.enums['MAV_LANDED_STATE'][
desired_landed_state].name, mavutil.mavlink.enums[
'MAV_VTOL_STATE'][self.extended_state.landed_state].name,
'MAV_LANDED_STATE'][self.extended_state.landed_state].name,
index, timeout)))
def wait_for_vtol_state(self, transition, timeout, index):
@ -277,7 +289,10 @@ class MavrosTestCommon(unittest.TestCase):
transitioned = True
break
rate.sleep()
try:
rate.sleep()
except rospy.ROSException as e:
self.fail(e)
self.assertTrue(transitioned, (
"transition not detected | desired: {0}, current: {1} | index: {2} timeout(seconds): {3}".
@ -304,7 +319,10 @@ class MavrosTestCommon(unittest.TestCase):
except rospy.ServiceException as e:
rospy.logerr(e)
rate.sleep()
try:
rate.sleep()
except rospy.ROSException as e:
self.fail(e)
self.assertTrue(wps_cleared, (
"failed to clear waypoints | timeout(seconds): {0}".format(timeout)
@ -340,7 +358,10 @@ class MavrosTestCommon(unittest.TestCase):
format(i / loop_freq, timeout))
break
rate.sleep()
try:
rate.sleep()
except rospy.ROSException as e:
self.fail(e)
self.assertTrue((
wps_sent and wps_verified
@ -366,7 +387,10 @@ class MavrosTestCommon(unittest.TestCase):
except rospy.ServiceException as e:
rospy.logerr(e)
rate.sleep()
try:
rate.sleep()
except rospy.ROSException as e:
self.fail(e)
self.assertTrue(res.success, (
"MAV_TYPE param get failed | timeout(seconds): {0}".format(timeout)

View File

@ -252,7 +252,10 @@ class MavrosMissionTest(MavrosTestCommon):
format(self.mission_wp.current_seq, xy_radius, z_radius,
pos_xy_d, pos_z_d))
rate.sleep()
try:
rate.sleep()
except rospy.ROSException as e:
self.fail(e)
self.assertTrue(
reached,

View File

@ -24,6 +24,7 @@
<arg name="debug" default="false"/>
<arg name="verbose" default="false"/>
<arg name="paused" default="false"/>
<arg name="respawn_gazebo" default="false"/>
<arg name="pluginlists_yaml" default="$(find mavros)/launch/px4_pluginlists.yaml" />
<arg name="config_yaml" default="$(find mavros)/launch/px4_config.yaml" />
@ -45,6 +46,7 @@
<arg name="debug" value="$(arg debug)"/>
<arg name="verbose" value="$(arg verbose)"/>
<arg name="paused" value="$(arg paused)"/>
<arg name="respawn_gazebo" value="$(arg respawn_gazebo)"/>
</include>
<include file="$(find px4)/launch/mavros.launch">

View File

@ -20,6 +20,7 @@
<arg name="debug" default="false"/>
<arg name="verbose" default="false"/>
<arg name="paused" default="false"/>
<arg name="respawn_gazebo" default="false"/>
<node name="sitl" pkg="px4" type="px4" output="screen"
args="$(find px4) $(arg rcS)">
@ -32,6 +33,7 @@
<arg name="debug" value="$(arg debug)" />
<arg name="verbose" value="$(arg verbose)" />
<arg name="paused" value="$(arg paused)" />
<arg name="respawn_gazebo" value="$(arg respawn_gazebo)"/>
</include>
<node name="$(anon vehicle_spawn)" output="screen" pkg="gazebo_ros" type="spawn_model"

View File

@ -7,6 +7,7 @@
<arg name="est" default="ekf2"/>
<arg name="mission"/>
<arg name="vehicle"/>
<arg name="respawn_gazebo" default="true"/>
<include file="$(find px4)/launch/mavros_posix_sitl.launch">
<arg name="ns" value="$(arg ns)"/>
@ -14,6 +15,7 @@
<arg name="gui" value="$(arg gui)"/>
<arg name="vehicle" value="$(arg vehicle)"/>
<arg name="est" value="$(arg est)"/>
<arg name="respawn_gazebo" value="$(arg respawn_gazebo)"/>
</include>
<group ns="$(arg ns)">

View File

@ -5,6 +5,7 @@
<arg name="headless" default="true"/>
<arg name="gui" default="false"/>
<arg name="est" default="ekf2"/>
<arg name="respawn_gazebo" default="true"/>
<include file="$(find px4)/launch/mavros_posix_sitl.launch">
<arg name="ns" value="$(arg ns)"/>
@ -12,6 +13,7 @@
<arg name="gui" value="$(arg gui)"/>
<arg name="vehicle" value="iris_opt_flow"/>
<arg name="est" value="$(arg est)"/>
<arg name="respawn_gazebo" value="$(arg respawn_gazebo)"/>
</include>
<group ns="$(arg ns)">

View File

@ -5,6 +5,7 @@
<arg name="headless" default="true"/>
<arg name="gui" default="false"/>
<arg name="est" default="ekf2"/>
<arg name="respawn_gazebo" default="true"/>
<include file="$(find px4)/launch/mavros_posix_sitl.launch">
<arg name="ns" value="$(arg ns)"/>
@ -12,6 +13,7 @@
<arg name="gui" value="$(arg gui)"/>
<arg name="vehicle" value="standard_vtol"/>
<arg name="est" value="$(arg est)"/>
<arg name="respawn_gazebo" value="$(arg respawn_gazebo)"/>
</include>
<group ns="$(arg ns)">

View File

@ -5,6 +5,7 @@
<arg name="headless" default="true"/>
<arg name="gui" default="false"/>
<arg name="est" default="ekf2"/>
<arg name="respawn_gazebo" default="true"/>
<include file="$(find px4)/launch/mavros_posix_sitl.launch">
<arg name="ns" value="$(arg ns)"/>
@ -12,6 +13,7 @@
<arg name="gui" value="$(arg gui)"/>
<arg name="vehicle" value="iris"/>
<arg name="est" value="$(arg est)"/>
<arg name="respawn_gazebo" value="$(arg respawn_gazebo)"/>
</include>
<group ns="$(arg ns)">

View File

@ -5,6 +5,7 @@
<arg name="headless" default="true"/>
<arg name="gui" default="false"/>
<arg name="est" default="ekf2"/>
<arg name="respawn_gazebo" default="true"/>
<include file="$(find px4)/launch/mavros_posix_sitl.launch">
<arg name="ns" value="$(arg ns)"/>
@ -12,6 +13,7 @@
<arg name="gui" value="$(arg gui)"/>
<arg name="vehicle" value="iris"/>
<arg name="est" value="$(arg est)"/>
<arg name="respawn_gazebo" value="$(arg respawn_gazebo)"/>
</include>
<group ns="$(arg ns)">