mirror of https://github.com/ArduPilot/ardupilot
autotest: added GPS vertical speed to the sitl simulator
This commit is contained in:
parent
7db7d7db77
commit
f6ddc4e4a1
|
@ -51,6 +51,7 @@ altitude = 600.0
|
|||
heading = 0.0
|
||||
speedN = 0
|
||||
speedE = 0.0
|
||||
speedD = 0.0
|
||||
xAccel = 0.0
|
||||
yAccel = 0.0
|
||||
zAccel = 0.0
|
||||
|
@ -61,7 +62,7 @@ rollDeg = 0.0
|
|||
pitchDeg = 0.0
|
||||
yawDeg = 0.0
|
||||
airspeed = 0
|
||||
magic = 0x4c56414e
|
||||
magic = 0x4c56414f
|
||||
|
||||
deltaT = 0.005
|
||||
rollDeg = 45
|
||||
|
@ -85,9 +86,9 @@ while True:
|
|||
yAccel *= scale;
|
||||
zAccel *= scale;
|
||||
|
||||
buf = struct.pack('<16dI',
|
||||
buf = struct.pack('<17dI',
|
||||
latitude, longitude, altitude, heading,
|
||||
speedN, speedE,
|
||||
speedN, speedE, speedD,
|
||||
xAccel, yAccel, zAccel,
|
||||
rollRate, pitchRate, yawRate,
|
||||
rollDeg, pitchDeg, yawDeg,
|
||||
|
|
|
@ -101,13 +101,14 @@ def process_jsb_input(buf):
|
|||
if e.errno not in [ errno.ECONNREFUSED ]:
|
||||
raise
|
||||
|
||||
simbuf = struct.pack('<16dI',
|
||||
simbuf = struct.pack('<17dI',
|
||||
fdm.get('latitude', units='degrees'),
|
||||
fdm.get('longitude', units='degrees'),
|
||||
fdm.get('altitude', units='meters'),
|
||||
fdm.get('psi', units='degrees'),
|
||||
fdm.get('v_north', units='mps'),
|
||||
fdm.get('v_east', units='mps'),
|
||||
fdm.get('v_down', units='mps'),
|
||||
fdm.get('A_X_pilot', units='mpss'),
|
||||
fdm.get('A_Y_pilot', units='mpss'),
|
||||
fdm.get('A_Z_pilot', units='mpss'),
|
||||
|
@ -118,7 +119,7 @@ def process_jsb_input(buf):
|
|||
fdm.get('theta', units='degrees'),
|
||||
fdm.get('psi', units='degrees'),
|
||||
fdm.get('vcas', units='mps'),
|
||||
0x4c56414e)
|
||||
0x4c56414f)
|
||||
try:
|
||||
sim_out.send(simbuf)
|
||||
except socket.error as e:
|
||||
|
|
|
@ -38,14 +38,14 @@ def sim_send(m, a):
|
|||
if not e.errno in [ errno.ECONNREFUSED ]:
|
||||
raise
|
||||
|
||||
buf = struct.pack('<16dI',
|
||||
buf = struct.pack('<17dI',
|
||||
a.latitude, a.longitude, a.altitude, degrees(yaw),
|
||||
a.velocity.x, a.velocity.y,
|
||||
a.velocity.x, a.velocity.y, a.velocity.z,
|
||||
a.accelerometer.x, a.accelerometer.y, a.accelerometer.z,
|
||||
degrees(earth_rates.x), degrees(earth_rates.y), degrees(earth_rates.z),
|
||||
degrees(roll), degrees(pitch), degrees(yaw),
|
||||
math.sqrt(a.velocity.x*a.velocity.x + a.velocity.y*a.velocity.y),
|
||||
0x4c56414e)
|
||||
0x4c56414f)
|
||||
try:
|
||||
sim_out.send(buf)
|
||||
except socket.error as e:
|
||||
|
|
|
@ -17,14 +17,14 @@ def sim_send(a):
|
|||
earth_rates = util.BodyRatesToEarthRates(a.dcm, a.gyro)
|
||||
(roll, pitch, yaw) = a.dcm.to_euler()
|
||||
|
||||
buf = struct.pack('<16dI',
|
||||
buf = struct.pack('<17dI',
|
||||
a.latitude, a.longitude, a.altitude, degrees(yaw),
|
||||
a.velocity.x, a.velocity.y,
|
||||
a.velocity.x, a.velocity.y, a.velocity.z,
|
||||
a.accelerometer.x, a.accelerometer.y, a.accelerometer.z,
|
||||
degrees(earth_rates.x), degrees(earth_rates.y), degrees(earth_rates.z),
|
||||
degrees(roll), degrees(pitch), degrees(yaw),
|
||||
math.sqrt(a.velocity.x*a.velocity.x + a.velocity.y*a.velocity.y),
|
||||
0x4c56414e)
|
||||
0x4c56414f)
|
||||
try:
|
||||
sim_out.send(buf)
|
||||
except socket.error as e:
|
||||
|
|
Loading…
Reference in New Issue