autotest: removed earth-frame rates usage

work only with rates in body frame
This commit is contained in:
Andrew Tridgell 2015-05-25 08:42:21 +10:00
parent 5511140f95
commit 0d20167294
2 changed files with 4 additions and 6 deletions

View File

@ -12,14 +12,13 @@ def sim_send(a):
'''send flight information to mavproxy'''
from math import degrees
earth_rates = util.BodyRatesToEarthRates(a.dcm, a.gyro)
(roll, pitch, yaw) = a.dcm.to_euler()
buf = struct.pack('<17dI',
a.latitude, a.longitude, a.altitude, degrees(yaw),
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(a.gyro.x), degrees(a.gyro.y), degrees(a.gyro.z),
degrees(roll), degrees(pitch), degrees(yaw),
math.sqrt(a.velocity.x*a.velocity.x + a.velocity.y*a.velocity.y),
0x4c56414f)

View File

@ -11,7 +11,6 @@ def sim_send(m, a):
global fdm
from math import degrees
earth_rates = util.BodyRatesToEarthRates(a.dcm, a.gyro)
(roll, pitch, yaw) = a.dcm.to_euler()
fdm.set('latitude', a.latitude, units='degrees')
@ -20,9 +19,9 @@ def sim_send(m, a):
fdm.set('phi', roll, units='radians')
fdm.set('theta', pitch, units='radians')
fdm.set('psi', yaw, units='radians')
fdm.set('phidot', earth_rates.x, units='rps')
fdm.set('thetadot', earth_rates.y, units='rps')
fdm.set('psidot', earth_rates.z, units='rps')
fdm.set('phidot', a.gyro.x, units='rps')
fdm.set('thetadot', a.gyro.y, units='rps')
fdm.set('psidot', a.gyro.z, units='rps')
fdm.set('vcas', math.sqrt(a.velocity.x*a.velocity.x + a.velocity.y*a.velocity.y), units='mps')
fdm.set('v_north', a.velocity.x, units='mps')
fdm.set('v_east', a.velocity.y, units='mps')