mirror of https://github.com/ArduPilot/ardupilot
autotest: updated fakepos.py for new packet format
This commit is contained in:
parent
f96a48e42b
commit
e12fabebe9
|
@ -61,7 +61,7 @@ rollDeg = 0.0
|
||||||
pitchDeg = 0.0
|
pitchDeg = 0.0
|
||||||
yawDeg = 0.0
|
yawDeg = 0.0
|
||||||
airspeed = 0
|
airspeed = 0
|
||||||
magic = 0x4c56414d
|
magic = 0x4c56414e
|
||||||
|
|
||||||
deltaT = 0.005
|
deltaT = 0.005
|
||||||
rollDeg = 45
|
rollDeg = 45
|
||||||
|
@ -80,12 +80,12 @@ while True:
|
||||||
xAccel = sin(radians(pitchDeg)) * cos(radians(rollDeg))
|
xAccel = sin(radians(pitchDeg)) * cos(radians(rollDeg))
|
||||||
yAccel = -sin(radians(rollDeg)) * cos(radians(pitchDeg))
|
yAccel = -sin(radians(rollDeg)) * cos(radians(pitchDeg))
|
||||||
zAccel = -cos(radians(rollDeg)) * cos(radians(pitchDeg))
|
zAccel = -cos(radians(rollDeg)) * cos(radians(pitchDeg))
|
||||||
scale = m2ft(9.81 / sqrt((xAccel*xAccel)+(yAccel*yAccel)+(zAccel*zAccel)))
|
scale = 9.81 / sqrt((xAccel*xAccel)+(yAccel*yAccel)+(zAccel*zAccel))
|
||||||
xAccel *= scale;
|
xAccel *= scale;
|
||||||
yAccel *= scale;
|
yAccel *= scale;
|
||||||
zAccel *= scale;
|
zAccel *= scale;
|
||||||
|
|
||||||
buf = struct.pack('>ddddddddddddddddI',
|
buf = struct.pack('<16dI',
|
||||||
latitude, longitude, altitude, heading,
|
latitude, longitude, altitude, heading,
|
||||||
speedN, speedE,
|
speedN, speedE,
|
||||||
xAccel, yAccel, zAccel,
|
xAccel, yAccel, zAccel,
|
||||||
|
|
Loading…
Reference in New Issue