Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Tools/autotest/run_mission.py
9316 views
1
#!/usr/bin/env python3
2
3
'''
4
Run a mission in SITL
5
6
AP_FLAKE8_CLEAN
7
'''
8
9
import os
10
11
os.environ['MAVLINK20'] = '1'
12
13
import vehicle_test_suite # noqa:E402
14
import sys # noqa:E402
15
import argparse # noqa:E402
16
from pysim import util # noqa:E402
17
18
19
class RunMission(vehicle_test_suite.TestSuite):
20
def __init__(self, vehicle_binary, model, mission_filepath, speedup=None, sim_rate_hz=None):
21
super(RunMission, self).__init__(vehicle_binary)
22
self.mission_filepath = mission_filepath
23
self.model = model
24
self.speedup = speedup
25
self.sim_rate_hz = sim_rate_hz
26
27
if self.speedup is None:
28
self.speedup = 100
29
30
def vehicleinfo_key(self):
31
'''magically guess vehicleinfo_key from filepath'''
32
path = self.binary.lower()
33
if "plane" in path:
34
return "ArduPlane"
35
if "copter" in path:
36
return "ArduCopter"
37
raise ValueError("Can't determine vehicleinfo_key from binary path")
38
39
def run(self):
40
self.start_SITL(
41
binary=self.binary,
42
model=self.model,
43
sitl_home=self.sitl_home_string_from_mission_filepath(self.mission_filepath),
44
speedup=self.speedup,
45
sim_rate_hz=self.sim_rate_hz,
46
defaults_filepath=self.model_defaults_filepath(self.model),
47
)
48
self.get_mavlink_connection_going()
49
50
# hack; Plane defaults are annoying... we should do better
51
# here somehow.
52
if self.vehicleinfo_key() == "ArduPlane":
53
self.set_parameter("RTL_AUTOLAND", 1)
54
55
self.load_mission_from_filepath(self.mission_filepath, strict=False)
56
self.change_mode('AUTO')
57
self.set_streamrate(1)
58
self.wait_ready_to_arm()
59
self.arm_vehicle()
60
self.wait_disarmed(timeout=600)
61
self.stop_SITL()
62
63
64
if __name__ == "__main__":
65
''' main program '''
66
os.environ['PYTHONUNBUFFERED'] = '1'
67
68
if sys.platform != "darwin":
69
os.putenv('TMPDIR', util.reltopdir('tmp'))
70
71
parser = argparse.ArgumentParser("run_mission.py")
72
parser.add_argument(
73
'vehicle_binary',
74
type=str,
75
help='vehicle binary to use'
76
)
77
parser.add_argument(
78
'model',
79
type=str,
80
help='vehicle model to use'
81
)
82
parser.add_argument(
83
'mission_filepath',
84
type=str,
85
help='mission file path'
86
)
87
parser.add_argument(
88
'--speedup',
89
type=int,
90
help='simulation speedup',
91
default=None,
92
)
93
parser.add_argument(
94
'--sim-rate-hz',
95
type=int,
96
help='simulation physics rate',
97
default=None,
98
)
99
100
args = parser.parse_args()
101
102
x = RunMission(
103
args.vehicle_binary,
104
args.model,
105
args.mission_filepath,
106
speedup=args.speedup,
107
sim_rate_hz=args.sim_rate_hz
108
)
109
x.run()
110
111