forked from Archive/PX4-Autopilot
make sure FCU is connected to mavros before state topic is marked ready
This commit is contained in:
parent
ab5a268ca5
commit
f46db40b10
|
@ -213,7 +213,8 @@ class MavrosMissionTest(unittest.TestCase):
|
|||
|
||||
self.state = data
|
||||
|
||||
if not self.sub_topics_ready['state']:
|
||||
# mavros publishes a disconnected state message on init
|
||||
if not self.sub_topics_ready['state'] and data.connected:
|
||||
self.sub_topics_ready['state'] = True
|
||||
|
||||
def altitude_callback(self, data):
|
||||
|
|
Loading…
Reference in New Issue