#!/usr/bin/env python'''useful extra functions for use by mavlink clientsCopyright Andrew Tridgell 2011Released under GNU GPL version 3 or later'''frommathimport*defnorm_heading(RAW_IMU,ATTITUDE,declination):'''calculate heading from RAW_IMU and ATTITUDE'''xmag=RAW_IMU.xmagymag=RAW_IMU.ymagzmag=RAW_IMU.zmagpitch=ATTITUDE.pitchroll=ATTITUDE.rollheadX=xmag*cos(pitch)+ymag*sin(roll)*sin(pitch)+zmag*cos(roll)*sin(pitch)headY=ymag*cos(roll)-zmag*sin(roll)heading=atan2(-headY,headX)heading=fmod(degrees(heading)+declination+360,360)returnheadingdefTrueHeading(SERVO_OUTPUT_RAW):rc3_min=1060rc3_max=1850p=float(SERVO_OUTPUT_RAW.servo3_raw-rc3_min)/(rc3_max-rc3_min)return172+(1.0-p)*(326-172)defkmh(mps):'''convert m/s to Km/h'''returnmps*3.6defaltitude(press_abs,ground_press=955.0,ground_temp=30):'''calculate barometric altitude'''returnlog(ground_press/press_abs)*(ground_temp+273.15)*29271.267*0.001