mirror of https://github.com/ArduPilot/ardupilot
autotest: fixed initial yaw in copter sim
This commit is contained in:
parent
6ecd2d74a3
commit
6288487814
|
@ -155,6 +155,7 @@ a.yaw = float(v[3])
|
||||||
a.ground_level = a.home_altitude
|
a.ground_level = a.home_altitude
|
||||||
a.position.z = 0
|
a.position.z = 0
|
||||||
a.wind = util.Wind(opts.wind)
|
a.wind = util.Wind(opts.wind)
|
||||||
|
a.set_yaw_degrees(a.yaw)
|
||||||
|
|
||||||
print("Starting at lat=%f lon=%f alt=%.1f heading=%.1f" % (
|
print("Starting at lat=%f lon=%f alt=%.1f heading=%.1f" % (
|
||||||
a.home_latitude,
|
a.home_latitude,
|
||||||
|
|
Loading…
Reference in New Issue