3 useful extra functions for use by mavlink clients 5 Copyright Andrew Tridgell 2011 6 Released under GNU GPL version 3 or later 8 from __future__
import print_function
9 from __future__
import absolute_import
10 from builtins
import object
16 from .quaternion
import Quaternion
22 from .rotmat
import Vector3, Matrix3
28 '''convert m/s to Km/h''' 31 def altitude(SCALED_PRESSURE, ground_pressure=None, ground_temp=None):
32 '''calculate barometric altitude''' 34 self = mavutil.mavfile_global
35 if ground_pressure
is None:
36 if self.param(
'GND_ABS_PRESS',
None)
is None:
38 ground_pressure = self.param(
'GND_ABS_PRESS', 1)
39 if ground_temp
is None:
40 ground_temp = self.param(
'GND_TEMP', 0)
41 scaling = ground_pressure / (SCALED_PRESSURE.press_abs*100.0)
42 temp = ground_temp + 273.15
43 return log(scaling) * temp * 29271.267 * 0.001
45 def altitude2(SCALED_PRESSURE, ground_pressure=None, ground_temp=None):
46 '''calculate barometric altitude''' 48 self = mavutil.mavfile_global
49 if ground_pressure
is None:
50 if self.param(
'GND_ABS_PRESS',
None)
is None:
52 ground_pressure = self.param(
'GND_ABS_PRESS', 1)
53 if ground_temp
is None:
54 ground_temp = self.param(
'GND_TEMP', 0)
55 scaling = SCALED_PRESSURE.press_abs*100.0 / ground_pressure
56 temp = ground_temp + 273.15
57 return 153.8462 * temp * (1.0 - exp(0.190259 *
log(scaling)))
59 def mag_heading(RAW_IMU, ATTITUDE, declination=None, SENSOR_OFFSETS=None, ofs=None):
60 '''calculate heading from raw magnetometer''' 61 if declination
is None:
63 declination = degrees(mavutil.mavfile_global.param(
'COMPASS_DEC', 0))
67 if SENSOR_OFFSETS
is not None and ofs
is not None:
68 mag_x += ofs[0] - SENSOR_OFFSETS.mag_ofs_x
69 mag_y += ofs[1] - SENSOR_OFFSETS.mag_ofs_y
70 mag_z += ofs[2] - SENSOR_OFFSETS.mag_ofs_z
74 cos_pitch_sq = 1.0-(dcm_matrix.c.x*dcm_matrix.c.x)
75 headY = mag_y * dcm_matrix.c.z - mag_z * dcm_matrix.c.y
76 headX = mag_x * cos_pitch_sq - dcm_matrix.c.x * (mag_y * dcm_matrix.c.y + mag_z * dcm_matrix.c.z)
78 heading = degrees(atan2(-headY,headX)) + declination
83 def mag_heading_motors(RAW_IMU, ATTITUDE, declination, SENSOR_OFFSETS, ofs, SERVO_OUTPUT_RAW, motor_ofs):
84 '''calculate heading from raw magnetometer''' 87 if declination
is None:
89 declination = degrees(mavutil.mavfile_global.param(
'COMPASS_DEC', 0))
93 if SENSOR_OFFSETS
is not None and ofs
is not None:
94 mag_x += ofs[0] - SENSOR_OFFSETS.mag_ofs_x
95 mag_y += ofs[1] - SENSOR_OFFSETS.mag_ofs_y
96 mag_z += ofs[2] - SENSOR_OFFSETS.mag_ofs_z
98 headX = mag_x*cos(ATTITUDE.pitch) + mag_y*sin(ATTITUDE.roll)*sin(ATTITUDE.pitch) + mag_z*cos(ATTITUDE.roll)*sin(ATTITUDE.pitch)
99 headY = mag_y*cos(ATTITUDE.roll) - mag_z*sin(ATTITUDE.roll)
100 heading = degrees(atan2(-headY,headX)) + declination
106 '''calculate magnetic field strength from raw magnetometer''' 110 if SENSOR_OFFSETS
is not None and ofs
is not None:
111 mag_x += ofs[0] - SENSOR_OFFSETS.mag_ofs_x
112 mag_y += ofs[1] - SENSOR_OFFSETS.mag_ofs_y
113 mag_z += ofs[2] - SENSOR_OFFSETS.mag_ofs_z
114 return sqrt(mag_x**2 + mag_y**2 + mag_z**2)
117 '''calculate magnetic field strength from raw magnetometer (dataflash version)''' 118 mag = Vector3(MAG.MagX, MAG.MagY, MAG.MagZ)
119 offsets = Vector3(MAG.OfsX, MAG.OfsY, MAG.OfsZ)
121 mag = (mag - offsets) + Vector3(ofs[0], ofs[1], ofs[2])
125 '''calculate magnetic field strength from raw magnetometer''' 126 from .
import mavutil
127 self = mavutil.mavfile_global
130 motor_pwm = m.servo1_raw + m.servo2_raw + m.servo3_raw + m.servo4_raw
132 rc3_min = self.param(
'RC3_MIN', 1100)
133 rc3_max = self.param(
'RC3_MAX', 1900)
134 motor = (motor_pwm - rc3_min) / (rc3_max - rc3_min)
140 motor_offsets0 = motor_ofs[0] * motor
141 motor_offsets1 = motor_ofs[1] * motor
142 motor_offsets2 = motor_ofs[2] * motor
143 ofs = (ofs[0] + motor_offsets0, ofs[1] + motor_offsets1, ofs[2] + motor_offsets2)
148 '''calculate magnetic field strength from raw magnetometer''' 155 if SENSOR_OFFSETS
is not None and ofs
is not None:
156 mag_x += ofs[0] - SENSOR_OFFSETS.mag_ofs_x
157 mag_y += ofs[1] - SENSOR_OFFSETS.mag_ofs_y
158 mag_z += ofs[2] - SENSOR_OFFSETS.mag_ofs_z
159 return sqrt(mag_x**2 + mag_y**2 + mag_z**2)
162 '''show the difference between two angles in degrees''' 163 ret = angle1 - angle2
173 '''average over N points''' 175 if not key
in average_data:
176 average_data[key] = [var]*N
178 average_data[key].pop(0)
179 average_data[key].append(var)
180 return sum(average_data[key])/N
185 '''5 point 2nd derivative''' 186 global derivative_data
187 from .
import mavutil
188 tnow = mavutil.mavfile_global.timestamp
190 if not key
in derivative_data:
191 derivative_data[key] = (tnow, [var]*5)
193 (last_time, data) = derivative_data[key]
196 derivative_data[key] = (tnow, data)
197 h = (tnow - last_time)
200 ret = ((data[4] + data[0]) - 2*data[2]) / (4*h**2)
204 '''9 point 2nd derivative''' 205 global derivative_data
206 from .
import mavutil
207 tnow = mavutil.mavfile_global.timestamp
209 if not key
in derivative_data:
210 derivative_data[key] = (tnow, [var]*9)
212 (last_time, data) = derivative_data[key]
215 derivative_data[key] = (tnow, data)
216 h = (tnow - last_time)
220 ret = ((f[8] + f[0]) + 4*(f[7] + f[1]) + 4*(f[6]+f[2]) - 4*(f[5]+f[3]) - 10*f[4])/(64*h**2)
226 '''a simple lowpass filter''' 228 if not key
in lowpass_data:
229 lowpass_data[key] = var
231 lowpass_data[key] = factor*lowpass_data[key] + (1.0 - factor)*var
232 return lowpass_data[key]
237 '''calculate differences between values''' 240 if not key
in last_diff:
243 ret = var - last_diff[key]
250 '''calculate slope''' 252 if tusec
is not None:
253 tnow = tusec * 1.0e-6
255 from .
import mavutil
256 tnow = mavutil.mavfile_global.timestamp
258 if key
in last_delta:
259 (last_v, last_t, last_ret) = last_delta[key]
265 ret = (var - last_v) / (tnow - last_t)
266 last_delta[key] = (var, tnow, ret)
270 '''calculate slope of an angle''' 272 if tusec
is not None:
273 tnow = tusec * 1.0e-6
275 from .
import mavutil
276 tnow = mavutil.mavfile_global.timestamp
279 if key
in last_delta:
280 (last_v, last_t, last_ret) = last_delta[key]
291 ret = dv / (tnow - last_t)
292 last_delta[key] = (var, tnow, ret)
295 def roll_estimate(RAW_IMU,GPS_RAW_INT=None,ATTITUDE=None,SENSOR_OFFSETS=None, ofs=None, mul=None,smooth=0.7):
296 '''estimate roll from accelerometer''' 297 rx = RAW_IMU.xacc * 9.81 / 1000.0
298 ry = RAW_IMU.yacc * 9.81 / 1000.0
299 rz = RAW_IMU.zacc * 9.81 / 1000.0
300 if ATTITUDE
is not None and GPS_RAW_INT
is not None:
301 ry -= ATTITUDE.yawspeed * GPS_RAW_INT.vel*0.01
302 rz += ATTITUDE.pitchspeed * GPS_RAW_INT.vel*0.01
303 if SENSOR_OFFSETS
is not None and ofs
is not None:
304 rx += SENSOR_OFFSETS.accel_cal_x
305 ry += SENSOR_OFFSETS.accel_cal_y
306 rz += SENSOR_OFFSETS.accel_cal_z
314 return lowpass(degrees(-asin(ry/sqrt(rx**2+ry**2+rz**2))),
'_roll',smooth)
316 def pitch_estimate(RAW_IMU, GPS_RAW_INT=None,ATTITUDE=None, SENSOR_OFFSETS=None, ofs=None, mul=None, smooth=0.7):
317 '''estimate pitch from accelerometer''' 318 rx = RAW_IMU.xacc * 9.81 / 1000.0
319 ry = RAW_IMU.yacc * 9.81 / 1000.0
320 rz = RAW_IMU.zacc * 9.81 / 1000.0
321 if ATTITUDE
is not None and GPS_RAW_INT
is not None:
322 ry -= ATTITUDE.yawspeed * GPS_RAW_INT.vel*0.01
323 rz += ATTITUDE.pitchspeed * GPS_RAW_INT.vel*0.01
324 if SENSOR_OFFSETS
is not None and ofs
is not None:
325 rx += SENSOR_OFFSETS.accel_cal_x
326 ry += SENSOR_OFFSETS.accel_cal_y
327 rz += SENSOR_OFFSETS.accel_cal_z
335 return lowpass(degrees(asin(rx/sqrt(rx**2+ry**2+rz**2))),
'_pitch',smooth)
338 '''return the current DCM rotation matrix''' 340 r.from_euler(ATTITUDE.roll, ATTITUDE.pitch, ATTITUDE.yaw)
344 '''return an attitude rotation matrix that is consistent with the current mag 346 m_body = Vector3(RAW_IMU.xmag, RAW_IMU.ymag, RAW_IMU.zmag)
347 m_earth = Vector3(m_body.length(), 0, 0)
350 r.from_euler(0, -radians(inclination), radians(declination))
351 m_earth = r * m_earth
353 r.from_two_vectors(m_earth, m_body)
356 def mag_yaw(RAW_IMU, inclination, declination):
357 '''estimate yaw from mag''' 359 (r, p, y) = m.to_euler()
366 '''estimate pithc from mag''' 368 (r, p, y) = m.to_euler()
372 '''estimate roll from mag''' 374 (r, p, y) = m.to_euler()
378 '''return expected mag vector''' 379 m_body = Vector3(RAW_IMU.xmag, RAW_IMU.ymag, RAW_IMU.zmag)
380 field_strength = m_body.length()
385 r.from_euler(0, -radians(inclination), radians(declination))
386 m_earth = r * Vector3(field_strength, 0, 0)
388 return m.transposed() * m_earth
391 '''give the magnitude of the discrepancy between observed and expected magnetic field''' 392 if declination
is None:
393 from .
import mavutil
394 declination = degrees(mavutil.mavfile_global.param(
'COMPASS_DEC', 0))
395 expected =
expected_mag(RAW_IMU, ATTITUDE, inclination, declination)
396 mag = Vector3(RAW_IMU.xmag, RAW_IMU.ymag, RAW_IMU.zmag)
397 return degrees(expected.angle(mag))
401 '''give the magnitude of the discrepancy between observed and expected magnetic field''' 402 if declination
is None:
403 from .
import mavutil
404 declination = degrees(mavutil.mavfile_global.param(
'COMPASS_DEC', 0))
406 mag1 = Vector3(RAW_IMU.xmag, RAW_IMU.ymag, RAW_IMU.zmag)
408 mag2 = Vector3(cos(radians(declination)), sin(radians(declination)), 0)
409 inclination = degrees(mag1.angle(mag2))
411 inclination = -inclination
415 '''estimate from mag''' 416 v =
expected_mag(RAW_IMU, ATTITUDE, inclination, declination)
420 '''estimate from mag''' 421 v =
expected_mag(RAW_IMU, ATTITUDE, inclination, declination)
425 '''estimate from mag''' 426 v =
expected_mag(RAW_IMU, ATTITUDE, inclination, declination)
429 def gravity(RAW_IMU, SENSOR_OFFSETS=None, ofs=None, mul=None, smooth=0.7):
430 '''estimate pitch from accelerometer''' 431 if hasattr(RAW_IMU,
'xacc'):
432 rx = RAW_IMU.xacc * 9.81 / 1000.0
433 ry = RAW_IMU.yacc * 9.81 / 1000.0
434 rz = RAW_IMU.zacc * 9.81 / 1000.0
439 if SENSOR_OFFSETS
is not None and ofs
is not None:
440 rx += SENSOR_OFFSETS.accel_cal_x
441 ry += SENSOR_OFFSETS.accel_cal_y
442 rz += SENSOR_OFFSETS.accel_cal_z
450 return sqrt(rx**2+ry**2+rz**2)
455 '''estimate pitch from SIMSTATE accels''' 456 xacc = SIMSTATE.xacc -
lowpass(
delta(GPS_RAW.v,
"v")*6.6,
"v", 0.9)
458 zacc += SIMSTATE.ygyro * GPS_RAW.v;
463 return degrees(-asin(xacc/zacc))
466 '''distance between two points''' 467 if hasattr(GPS_RAW1,
'Lat'):
468 lat1 = radians(GPS_RAW1.Lat)
469 lat2 = radians(GPS_RAW2.Lat)
470 lon1 = radians(GPS_RAW1.Lng)
471 lon2 = radians(GPS_RAW2.Lng)
474 elif hasattr(GPS_RAW1,
'cog'):
475 lat1 = radians(GPS_RAW1.lat)*1.0e-7
476 lat2 = radians(GPS_RAW2.lat)*1.0e-7
477 lon1 = radians(GPS_RAW1.lon)*1.0e-7
478 lon2 = radians(GPS_RAW2.lon)*1.0e-7
479 alt1 = GPS_RAW1.alt*0.001
480 alt2 = GPS_RAW2.alt*0.001
482 lat1 = radians(GPS_RAW1.lat)
483 lat2 = radians(GPS_RAW2.lat)
484 lon1 = radians(GPS_RAW1.lon)
485 lon2 = radians(GPS_RAW2.lon)
486 alt1 = GPS_RAW1.alt*0.001
487 alt2 = GPS_RAW2.alt*0.001
491 a = sin(0.5*dLat)**2 + sin(0.5*dLon)**2 * cos(lat1) * cos(lat2)
492 c = 2.0 * atan2(sqrt(a), sqrt(1.0-a))
493 ground_dist = 6371 * 1000 * c
496 return sqrt(ground_dist**2 + (alt2-alt1)**2)
502 '''distance from first fix point''' 504 if (hasattr(GPS_RAW,
'fix_type')
and GPS_RAW.fix_type < 2)
or \
505 (hasattr(GPS_RAW,
'Status')
and GPS_RAW.Status < 2):
508 if first_fix
is None:
514 '''sawtooth pattern based on uptime''' 515 mins = (ATTITUDE.usec * 1.0e-6)/60
516 p = fmod(mins, period*2)
518 return amplitude * (p/period)
519 return amplitude * (period - (p-period))/period
522 '''return expected rate of turn in degrees/s for given speed in m/s and 523 bank angle in degrees''' 524 if abs(speed) < 2
or abs(bank) > 80:
526 ret = degrees(9.81*tan(radians(bank))/speed)
530 '''return expected wing loading factor for a bank angle in radians''' 533 def airspeed(VFR_HUD, ratio=None, used_ratio=None, offset=None):
534 '''recompute airspeed with a different ARSPD_RATIO''' 535 from .
import mavutil
536 mav = mavutil.mavfile_global
539 if used_ratio
is None:
540 if 'ARSPD_RATIO' in mav.params:
541 used_ratio = mav.params[
'ARSPD_RATIO']
543 print(
"no ARSPD_RATIO in mav.params")
545 if hasattr(VFR_HUD,
'airspeed'):
546 airspeed = VFR_HUD.airspeed
548 airspeed = VFR_HUD.Airspeed
549 airspeed_pressure = (airspeed**2) / used_ratio
550 if offset
is not None:
551 airspeed_pressure += offset
552 if airspeed_pressure < 0:
553 airspeed_pressure = 0
554 airspeed = sqrt(airspeed_pressure * ratio)
558 '''EAS2TAS from ARSP.Temp''' 559 tempK = ground_temp + 273.15 - 0.0065 * GPS.Alt
560 return sqrt(1.225 / (BARO.Press / (287.26 * tempK)))
564 '''recompute airspeed with a different ARSPD_RATIO''' 565 from .
import mavutil
566 mav = mavutil.mavfile_global
567 airspeed_pressure = (VFR_HUD.airspeed**2) / ratio
568 airspeed = sqrt(airspeed_pressure * ratio)
572 '''back-calculate the voltage the airspeed sensor must have seen''' 573 from .
import mavutil
574 mav = mavutil.mavfile_global
577 if 'ARSPD_RATIO' in mav.params:
578 used_ratio = mav.params[
'ARSPD_RATIO']
581 if 'ARSPD_OFFSET' in mav.params:
582 offset = mav.params[
'ARSPD_OFFSET']
585 airspeed_pressure = (pow(VFR_HUD.airspeed,2)) / used_ratio
586 raw = airspeed_pressure + offset
587 SCALING_OLD_CALIBRATION = 204.8
588 voltage = 5.0 * raw / 4096
593 '''return angular velocities in earth frame''' 594 from math
import sin, cos, tan, fabs
596 p = ATTITUDE.rollspeed
597 q = ATTITUDE.pitchspeed
598 r = ATTITUDE.yawspeed
600 theta = ATTITUDE.pitch
603 phiDot = p + tan(theta)*(q*sin(phi) + r*cos(phi))
604 thetaDot = q*cos(phi) - r*sin(phi)
605 if fabs(cos(theta)) < 1.0e-20:
607 psiDot = (q*sin(phi) + r*cos(phi))/cos(theta)
608 return (phiDot, thetaDot, psiDot)
611 '''return roll rate in earth frame''' 616 '''return pitch rate in earth frame''' 621 '''return yaw rate in earth frame''' 627 '''return GPS velocity vector''' 628 return Vector3(GLOBAL_POSITION_INT.vx, GLOBAL_POSITION_INT.vy, GLOBAL_POSITION_INT.vz) * 0.01
632 '''return GPS velocity vector''' 633 return Vector3(GPS_RAW_INT.vel*0.01*cos(radians(GPS_RAW_INT.cog*0.01)),
634 GPS_RAW_INT.vel*0.01*sin(radians(GPS_RAW_INT.cog*0.01)), 0)
637 '''return GPS velocity vector in body frame''' 639 return r.transposed() * Vector3(GPS_RAW_INT.vel*0.01*cos(radians(GPS_RAW_INT.cog*0.01)),
640 GPS_RAW_INT.vel*0.01*sin(radians(GPS_RAW_INT.cog*0.01)),
641 -tan(ATTITUDE.pitch)*GPS_RAW_INT.vel*0.01)
644 '''return earth frame acceleration vector''' 646 accel = Vector3(RAW_IMU.xacc, RAW_IMU.yacc, RAW_IMU.zacc) * 9.81 * 0.001
650 '''return earth frame gyro vector''' 652 accel = Vector3(degrees(RAW_IMU.xgyro), degrees(RAW_IMU.ygyro), degrees(RAW_IMU.zgyro)) * 0.001
656 '''return airspeed energy error matching APM internals 657 This is positive when we are going too slow 659 aspeed_cm = VFR_HUD.airspeed*100
660 target_airspeed = NAV_CONTROLLER_OUTPUT.aspd_error + aspeed_cm
661 airspeed_energy_error = ((target_airspeed*target_airspeed) - (aspeed_cm*aspeed_cm))*0.00005
662 return airspeed_energy_error
666 '''return energy error matching APM internals 667 This is positive when we are too low or going too slow 670 alt_error = NAV_CONTROLLER_OUTPUT.alt_error*100
671 energy_error = aspeed_energy_error + alt_error*0.098
675 '''return turning circle (diameter) in meters for steering_angle in degrees 683 steering_angle = max_wheel_turn * (SERVO_OUTPUT_RAW.servo1_raw - 1500) / 400.0
684 theta = radians(steering_angle)
685 return (wheeltrack/2) + (wheelbase/sin(theta))
688 '''return yaw rate in degrees/second given steering_angle and speed''' 690 speed = VFR_HUD.groundspeed
692 steering_angle = max_wheel_turn * (SERVO_OUTPUT_RAW.servo1_raw - 1500) / 400.0
693 if abs(steering_angle) < 1.0e-6
or abs(speed) < 1.0e-6:
702 '''return lateral acceleration in m/s/s''' 703 speed = VFR_HUD.groundspeed
705 accel = radians(yaw_rate) * speed
710 '''de-mix a mixed servo output''' 718 '''de-mix a mixed servo output''' 725 def mixer(servo1, servo2, mixtype=1, gain=0.5):
746 return (1500+v1,1500+v2)
748 def mix1(servo1, servo2, mixtype=1, gain=0.5):
749 '''de-mix a mixed servo output''' 750 (v1,v2) =
mixer(servo1, servo2, mixtype=mixtype, gain=gain)
753 def mix2(servo1, servo2, mixtype=1, gain=0.5):
754 '''de-mix a mixed servo output''' 755 (v1,v2) =
mixer(servo1, servo2, mixtype=mixtype, gain=gain)
774 '''DCM state object''' 778 self.dcm.from_euler(radians(roll), radians(pitch), radians(yaw))
779 self.dcm2.from_euler(radians(roll), radians(pitch), radians(yaw))
796 (self.roll, self.pitch, self.yaw) = self.dcm.to_euler()
797 (self.roll2, self.pitch2, self.yaw2) = self.dcm2.to_euler()
800 if self.
gyro != gyro
or self.
accel != accel:
801 delta_angle = old_div((gyro+self.
omega_I), self.
rate)
802 self.dcm.rotate(delta_angle)
805 corrected_delta = delta_angle + 0.0833333 * correction
806 self.dcm2.rotate(corrected_delta)
810 self.dcm2.normalize()
814 (self.roll, self.pitch, self.yaw) = self.dcm.to_euler()
815 (self.roll2, self.pitch2, self.yaw2) = self.dcm2.to_euler()
820 '''implement full DCM system''' 822 if dcm_state
is None:
823 dcm_state =
DCM_State(ATT.Roll, ATT.Pitch, ATT.Yaw)
825 mag = Vector3(MAG.MagX, MAG.MagY, MAG.MagZ)
826 gyro = Vector3(IMU.GyrX, IMU.GyrY, IMU.GyrZ)
827 accel = Vector3(IMU.AccX, IMU.AccY, IMU.AccZ)
828 accel2 = Vector3(IMU.AccX, IMU.AccY, IMU.AccZ)
829 dcm_state.update(gyro, accel, mag, GPS)
833 '''PX4 DCM state object''' 836 self.dcm.from_euler(radians(roll), radians(pitch), radians(yaw))
840 (self.roll, self.pitch, self.yaw) = self.dcm.to_euler()
842 def update(self, gyro, accel, timestamp):
843 if self.
gyro != gyro
or self.
accel != accel:
844 delta_angle = gyro * (timestamp - self.
timestamp)
846 self.dcm.rotate(delta_angle)
850 (self.roll, self.pitch, self.yaw) = self.dcm.to_euler()
855 '''implement full DCM using PX4 native SD log data''' 857 if px4_state
is None:
858 px4_state =
PX4_State(degrees(ATT.Roll), degrees(ATT.Pitch), degrees(ATT.Yaw), IMU._timestamp)
860 gyro = Vector3(IMU.GyroX, IMU.GyroY, IMU.GyroZ)
861 accel = Vector3(IMU.AccX, IMU.AccY, IMU.AccZ)
862 px4_state.update(gyro, accel, IMU._timestamp)
868 '''conditional that is true on every Nth sample''' 870 _downsample_N = (_downsample_N + 1) % N
871 return _downsample_N == 0
874 '''return 1 if armed, 0 if not''' 875 from .
import mavutil
876 if HEARTBEAT.type == mavutil.mavlink.MAV_TYPE_GCS:
877 self = mavutil.mavfile_global
878 if self.motors_armed():
881 if HEARTBEAT.base_mode & mavutil.mavlink.MAV_MODE_FLAG_SAFETY_ARMED:
886 '''return the current DCM rotation matrix''' 888 r.from_euler(radians(ATT.Roll), radians(ATT.Pitch), radians(ATT.Yaw))
892 '''return the current DCM rotation matrix''' 894 r.from_euler(AHRS2.roll, AHRS2.pitch, AHRS2.yaw)
898 '''return earth frame acceleration vector from AHRS2''' 900 accel = Vector3(RAW_IMU.xacc, RAW_IMU.yacc, RAW_IMU.zacc) * 9.81 * 0.001
904 '''return earth frame acceleration vector from df log''' 906 accel = Vector3(IMU.AccX, IMU.AccY, IMU.AccZ)
910 '''return earth frame acceleration vector from df log''' 912 accel1 = Vector3(IMU.AccX, IMU.AccY, IMU.AccZ)
913 accel2 = Vector3(IMU2.AccX, IMU2.AccY, IMU2.AccZ)
914 accel = 0.5 * (accel1 + accel2)
918 '''return GPS velocity vector''' 919 vx = GPS.Spd * cos(radians(GPS.GCrs))
920 vy = GPS.Spd * sin(radians(GPS.GCrs))
921 return Vector3(vx, vy, GPS.VZ)
924 '''distance between two points''' 925 if GPS.TimeMS != GPS2.TimeMS:
931 radius_of_earth = 6378100.0
934 ''' wrap a longitude value around to always have a value in the range 935 [-180, +180) i.e 0 => 0, 1 => 1, -1 => -1, 181 => -179, -181 => 179 937 return (((lon + 180.0) % 360.0) - 180.0)
940 '''extrapolate latitude/longitude given a heading and distance 941 thanks to http://www.movable-type.co.uk/scripts/latlong.html 944 lat1 = math.radians(lat)
945 lon1 = math.radians(lon)
946 brng = math.radians(bearing)
947 dr = distance/radius_of_earth
949 lat2 = math.asin(math.sin(lat1)*math.cos(dr) +
950 math.cos(lat1)*math.sin(dr)*math.cos(brng))
951 lon2 = lon1 + math.atan2(math.sin(brng)*math.sin(dr)*math.cos(lat1),
952 math.cos(dr)-math.sin(lat1)*math.sin(lat2))
956 '''return new lat/lon after moving east/north 957 by the given number of meters''' 959 bearing = math.degrees(math.atan2(east, north))
960 distance = math.sqrt(east**2 + north**2)
961 return gps_newpos(lat, lon, bearing, distance)
966 '''calculate EKF position when EKF disabled''' 968 from .
import mavutil
969 self = mavutil.mavfile_global
971 if not 'GPS' in self.messages
or self.messages[
'GPS'].Status != 3:
973 ekf_home = self.messages[
'GPS']
974 (ekf_home.Lat, ekf_home.Lng) =
gps_offset(ekf_home.Lat, ekf_home.Lng, -EKF1.PE, -EKF1.PN)
975 (lat,lon) =
gps_offset(ekf_home.Lat, ekf_home.Lng, EKF1.PE, EKF1.PN)
980 Get Euler angles from a quaternion 981 :param q: quaternion [w, x, y , z] 982 :returns: euler angles [roll, pitch, yaw] 989 Get quaternion from euler angles 990 :param e: euler angles [roll, pitch, yaw] 991 :returns: quaternion [w, x, y , z] 998 Returns rotated quaternion 999 :param attitude: quaternion [w, x, y , z] 1000 :param roll: rotation in rad 1001 :param pitch: rotation in rad 1002 :param yaw: rotation in rad 1003 :returns: quaternion [w, x, y , z] 1005 quat = Quaternion(attitude)
1006 rotation = Quaternion([roll, pitch, yaw])
1007 res = rotation * quat
1012 '''return quaternion roll in degrees''' 1013 q = Quaternion([MSG.Q1,MSG.Q2,MSG.Q3,MSG.Q4])
1014 return degrees(q.euler[0])
1018 '''return quaternion pitch in degrees''' 1019 q = Quaternion([MSG.Q1,MSG.Q2,MSG.Q3,MSG.Q4])
1020 return degrees(q.euler[1])
1024 '''return quaternion yaw in degrees''' 1025 q = Quaternion([MSG.Q1,MSG.Q2,MSG.Q3,MSG.Q4])
1026 return degrees(q.euler[2])
1029 '''return eulers in radians from quaternion for view at given attitude in euler radians''' 1030 rot_view = Matrix3()
1031 rot_view.from_euler(roll, pitch, yaw)
1032 q = Quaternion([MSG.Q1,MSG.Q2,MSG.Q3,MSG.Q4])
1033 dcm = (rot_view * q.dcm.transposed()).transposed()
1034 return dcm.to_euler()
1037 '''return eulers in radians from quaternion for view at pitch 90''' 1041 '''return quaternion roll in degrees for view at pitch 90''' 1045 '''return quaternion roll in degrees for view at pitch 90''' 1049 '''return quaternion roll in degrees for view at pitch 90'''