Classes | |
class | DCM_State |
class | PX4_State |
Functions | |
def | airspeed (VFR_HUD, ratio=None, used_ratio=None, offset=None) |
def | airspeed_energy_error (NAV_CONTROLLER_OUTPUT, VFR_HUD) |
def | airspeed_ratio (VFR_HUD) |
def | airspeed_voltage (VFR_HUD, ratio=None) |
def | altitude (SCALED_PRESSURE, ground_pressure=None, ground_temp=None) |
def | altitude2 (SCALED_PRESSURE, ground_pressure=None, ground_temp=None) |
def | angle_diff (angle1, angle2) |
def | armed (HEARTBEAT) |
def | average (var, key, N) |
def | DCM_update (IMU, ATT, MAG, GPS) |
def | delta (var, key, tusec=None) |
def | delta_angle (var, key, tusec=None) |
def | demix1 (servo1, servo2, gain=0.5) |
def | demix2 (servo1, servo2, gain=0.5) |
def | diff (var, key) |
def | distance_gps2 (GPS, GPS2) |
def | distance_home (GPS_RAW) |
def | distance_two (GPS_RAW1, GPS_RAW2, horizontal=True) |
def | downsample (N) |
def | earth_accel (RAW_IMU, ATTITUDE) |
def | earth_accel2 (RAW_IMU, ATTITUDE) |
def | earth_accel2_df (IMU, IMU2, ATT) |
def | earth_accel_df (IMU, ATT) |
def | earth_gyro (RAW_IMU, ATTITUDE) |
def | earth_rates (ATTITUDE) |
def | EAS2TAS (ARSP, GPS, BARO, ground_temp=25) |
def | ekf1_pos (EKF1) |
def | energy_error (NAV_CONTROLLER_OUTPUT, VFR_HUD) |
def | euler_p90 (MSG) |
def | euler_rotated (MSG, roll, pitch, yaw) |
def | euler_to_quat (e) |
def | expected_mag (RAW_IMU, ATTITUDE, inclination, declination) |
def | expected_magx (RAW_IMU, ATTITUDE, inclination, declination) |
def | expected_magy (RAW_IMU, ATTITUDE, inclination, declination) |
def | expected_magz (RAW_IMU, ATTITUDE, inclination, declination) |
def | get_motor_offsets (SERVO_OUTPUT_RAW, ofs, motor_ofs) |
def | gps_newpos (lat, lon, bearing, distance) |
def | gps_offset (lat, lon, east, north) |
def | gps_velocity (GLOBAL_POSITION_INT) |
def | gps_velocity_body (GPS_RAW_INT, ATTITUDE) |
def | gps_velocity_df (GPS) |
def | gps_velocity_old (GPS_RAW_INT) |
def | gravity (RAW_IMU, SENSOR_OFFSETS=None, ofs=None, mul=None, smooth=0.7) |
def | kmh (mps) |
def | lowpass (var, key, factor) |
def | mag_discrepancy (RAW_IMU, ATTITUDE, inclination, declination=None) |
def | mag_field (RAW_IMU, SENSOR_OFFSETS=None, ofs=None) |
def | mag_field_df (MAG, ofs=None) |
def | mag_field_motors (RAW_IMU, SENSOR_OFFSETS, ofs, SERVO_OUTPUT_RAW, motor_ofs) |
def | mag_heading (RAW_IMU, ATTITUDE, declination=None, SENSOR_OFFSETS=None, ofs=None) |
def | mag_heading_motors (RAW_IMU, ATTITUDE, declination, SENSOR_OFFSETS, ofs, SERVO_OUTPUT_RAW, motor_ofs) |
def | mag_inclination (RAW_IMU, ATTITUDE, declination=None) |
def | mag_pitch (RAW_IMU, inclination, declination) |
def | mag_roll (RAW_IMU, inclination, declination) |
def | mag_rotation (RAW_IMU, inclination, declination) |
def | mag_yaw (RAW_IMU, inclination, declination) |
def | mix1 (servo1, servo2, mixtype=1, gain=0.5) |
def | mix2 (servo1, servo2, mixtype=1, gain=0.5) |
def | mixer (servo1, servo2, mixtype=1, gain=0.5) |
def | pitch_estimate (RAW_IMU, GPS_RAW_INT=None, ATTITUDE=None, SENSOR_OFFSETS=None, ofs=None, mul=None, smooth=0.7) |
def | pitch_rate (ATTITUDE) |
def | pitch_sim (SIMSTATE, GPS_RAW) |
def | PX4_update (IMU, ATT) |
def | qpitch (MSG) |
def | qpitch_p90 (MSG) |
def | qroll (MSG) |
def | qroll_p90 (MSG) |
def | quat_to_euler (q) |
def | qyaw (MSG) |
def | qyaw_p90 (MSG) |
def | rate_of_turn (speed, bank) |
def | roll_estimate (RAW_IMU, GPS_RAW_INT=None, ATTITUDE=None, SENSOR_OFFSETS=None, ofs=None, mul=None, smooth=0.7) |
def | roll_rate (ATTITUDE) |
def | rotate_quat (attitude, roll, pitch, yaw) |
def | rotation (ATTITUDE) |
def | rotation2 (AHRS2) |
def | rotation_df (ATT) |
def | rover_lat_accel (VFR_HUD, SERVO_OUTPUT_RAW) |
def | rover_turn_circle (SERVO_OUTPUT_RAW) |
def | rover_yaw_rate (VFR_HUD, SERVO_OUTPUT_RAW) |
def | sawtooth (ATTITUDE, amplitude=2.0, period=5.0) |
def | second_derivative_5 (var, key) |
def | second_derivative_9 (var, key) |
def | wingloading (bank) |
def | wrap_180 (angle) |
def | wrap_360 (angle) |
def | wrap_valid_longitude (lon) |
def | yaw_rate (ATTITUDE) |
Variables | |
int | _downsample_N = 0 |
dictionary | average_data = {} |
dcm_state = None | |
dictionary | derivative_data = {} |
ekf_home = None | |
first_fix = None | |
dictionary | last_delta = {} |
dictionary | last_diff = {} |
dictionary | lowpass_data = {} |
px4_state = None | |
float | radius_of_earth = 6378100.0 |
useful extra functions for use by mavlink clients Copyright Andrew Tridgell 2011 Released under GNU GPL version 3 or later
def pymavlink.mavextra.airspeed | ( | VFR_HUD, | |
ratio = None , |
|||
used_ratio = None , |
|||
offset = None |
|||
) |
recompute airspeed with a different ARSPD_RATIO
Definition at line 533 of file mavextra.py.
def pymavlink.mavextra.airspeed_energy_error | ( | NAV_CONTROLLER_OUTPUT, | |
VFR_HUD | |||
) |
return airspeed energy error matching APM internals This is positive when we are going too slow
Definition at line 655 of file mavextra.py.
def pymavlink.mavextra.airspeed_ratio | ( | VFR_HUD | ) |
recompute airspeed with a different ARSPD_RATIO
Definition at line 563 of file mavextra.py.
def pymavlink.mavextra.airspeed_voltage | ( | VFR_HUD, | |
ratio = None |
|||
) |
back-calculate the voltage the airspeed sensor must have seen
Definition at line 571 of file mavextra.py.
def pymavlink.mavextra.altitude | ( | SCALED_PRESSURE, | |
ground_pressure = None , |
|||
ground_temp = None |
|||
) |
calculate barometric altitude
Definition at line 31 of file mavextra.py.
def pymavlink.mavextra.altitude2 | ( | SCALED_PRESSURE, | |
ground_pressure = None , |
|||
ground_temp = None |
|||
) |
calculate barometric altitude
Definition at line 45 of file mavextra.py.
def pymavlink.mavextra.angle_diff | ( | angle1, | |
angle2 | |||
) |
show the difference between two angles in degrees
Definition at line 161 of file mavextra.py.
def pymavlink.mavextra.armed | ( | HEARTBEAT | ) |
return 1 if armed, 0 if not
Definition at line 873 of file mavextra.py.
def pymavlink.mavextra.average | ( | var, | |
key, | |||
N | |||
) |
average over N points
Definition at line 172 of file mavextra.py.
def pymavlink.mavextra.DCM_update | ( | IMU, | |
ATT, | |||
MAG, | |||
GPS | |||
) |
implement full DCM system
Definition at line 819 of file mavextra.py.
def pymavlink.mavextra.delta | ( | var, | |
key, | |||
tusec = None |
|||
) |
calculate slope
Definition at line 249 of file mavextra.py.
def pymavlink.mavextra.delta_angle | ( | var, | |
key, | |||
tusec = None |
|||
) |
calculate slope of an angle
Definition at line 269 of file mavextra.py.
def pymavlink.mavextra.demix1 | ( | servo1, | |
servo2, | |||
gain = 0.5 |
|||
) |
de-mix a mixed servo output
Definition at line 709 of file mavextra.py.
def pymavlink.mavextra.demix2 | ( | servo1, | |
servo2, | |||
gain = 0.5 |
|||
) |
de-mix a mixed servo output
Definition at line 717 of file mavextra.py.
def pymavlink.mavextra.diff | ( | var, | |
key | |||
) |
calculate differences between values
Definition at line 236 of file mavextra.py.
def pymavlink.mavextra.distance_gps2 | ( | GPS, | |
GPS2 | |||
) |
distance between two points
Definition at line 923 of file mavextra.py.
def pymavlink.mavextra.distance_home | ( | GPS_RAW | ) |
distance from first fix point
Definition at line 501 of file mavextra.py.
def pymavlink.mavextra.distance_two | ( | GPS_RAW1, | |
GPS_RAW2, | |||
horizontal = True |
|||
) |
distance between two points
Definition at line 465 of file mavextra.py.
def pymavlink.mavextra.downsample | ( | N | ) |
conditional that is true on every Nth sample
Definition at line 867 of file mavextra.py.
def pymavlink.mavextra.earth_accel | ( | RAW_IMU, | |
ATTITUDE | |||
) |
return earth frame acceleration vector
Definition at line 643 of file mavextra.py.
def pymavlink.mavextra.earth_accel2 | ( | RAW_IMU, | |
ATTITUDE | |||
) |
return earth frame acceleration vector from AHRS2
Definition at line 897 of file mavextra.py.
def pymavlink.mavextra.earth_accel2_df | ( | IMU, | |
IMU2, | |||
ATT | |||
) |
return earth frame acceleration vector from df log
Definition at line 909 of file mavextra.py.
def pymavlink.mavextra.earth_accel_df | ( | IMU, | |
ATT | |||
) |
return earth frame acceleration vector from df log
Definition at line 903 of file mavextra.py.
def pymavlink.mavextra.earth_gyro | ( | RAW_IMU, | |
ATTITUDE | |||
) |
return earth frame gyro vector
Definition at line 649 of file mavextra.py.
def pymavlink.mavextra.earth_rates | ( | ATTITUDE | ) |
return angular velocities in earth frame
Definition at line 592 of file mavextra.py.
def pymavlink.mavextra.EAS2TAS | ( | ARSP, | |
GPS, | |||
BARO, | |||
ground_temp = 25 |
|||
) |
EAS2TAS from ARSP.Temp
Definition at line 557 of file mavextra.py.
def pymavlink.mavextra.ekf1_pos | ( | EKF1 | ) |
calculate EKF position when EKF disabled
Definition at line 965 of file mavextra.py.
def pymavlink.mavextra.energy_error | ( | NAV_CONTROLLER_OUTPUT, | |
VFR_HUD | |||
) |
return energy error matching APM internals This is positive when we are too low or going too slow
Definition at line 665 of file mavextra.py.
def pymavlink.mavextra.euler_p90 | ( | MSG | ) |
return eulers in radians from quaternion for view at pitch 90
Definition at line 1036 of file mavextra.py.
def pymavlink.mavextra.euler_rotated | ( | MSG, | |
roll, | |||
pitch, | |||
yaw | |||
) |
return eulers in radians from quaternion for view at given attitude in euler radians
Definition at line 1028 of file mavextra.py.
def pymavlink.mavextra.euler_to_quat | ( | e | ) |
Get quaternion from euler angles :param e: euler angles [roll, pitch, yaw] :returns: quaternion [w, x, y , z]
Definition at line 987 of file mavextra.py.
def pymavlink.mavextra.expected_mag | ( | RAW_IMU, | |
ATTITUDE, | |||
inclination, | |||
declination | |||
) |
return expected mag vector
Definition at line 377 of file mavextra.py.
def pymavlink.mavextra.expected_magx | ( | RAW_IMU, | |
ATTITUDE, | |||
inclination, | |||
declination | |||
) |
estimate from mag
Definition at line 414 of file mavextra.py.
def pymavlink.mavextra.expected_magy | ( | RAW_IMU, | |
ATTITUDE, | |||
inclination, | |||
declination | |||
) |
estimate from mag
Definition at line 419 of file mavextra.py.
def pymavlink.mavextra.expected_magz | ( | RAW_IMU, | |
ATTITUDE, | |||
inclination, | |||
declination | |||
) |
estimate from mag
Definition at line 424 of file mavextra.py.
def pymavlink.mavextra.get_motor_offsets | ( | SERVO_OUTPUT_RAW, | |
ofs, | |||
motor_ofs | |||
) |
calculate magnetic field strength from raw magnetometer
Definition at line 124 of file mavextra.py.
def pymavlink.mavextra.gps_newpos | ( | lat, | |
lon, | |||
bearing, | |||
distance | |||
) |
extrapolate latitude/longitude given a heading and distance thanks to http://www.movable-type.co.uk/scripts/latlong.html
Definition at line 939 of file mavextra.py.
def pymavlink.mavextra.gps_offset | ( | lat, | |
lon, | |||
east, | |||
north | |||
) |
return new lat/lon after moving east/north by the given number of meters
Definition at line 955 of file mavextra.py.
def pymavlink.mavextra.gps_velocity | ( | GLOBAL_POSITION_INT | ) |
return GPS velocity vector
Definition at line 626 of file mavextra.py.
def pymavlink.mavextra.gps_velocity_body | ( | GPS_RAW_INT, | |
ATTITUDE | |||
) |
return GPS velocity vector in body frame
Definition at line 636 of file mavextra.py.
def pymavlink.mavextra.gps_velocity_df | ( | GPS | ) |
return GPS velocity vector
Definition at line 917 of file mavextra.py.
def pymavlink.mavextra.gps_velocity_old | ( | GPS_RAW_INT | ) |
return GPS velocity vector
Definition at line 631 of file mavextra.py.
def pymavlink.mavextra.gravity | ( | RAW_IMU, | |
SENSOR_OFFSETS = None , |
|||
ofs = None , |
|||
mul = None , |
|||
smooth = 0.7 |
|||
) |
estimate pitch from accelerometer
Definition at line 429 of file mavextra.py.
def pymavlink.mavextra.kmh | ( | mps | ) |
convert m/s to Km/h
Definition at line 27 of file mavextra.py.
def pymavlink.mavextra.lowpass | ( | var, | |
key, | |||
factor | |||
) |
a simple lowpass filter
Definition at line 225 of file mavextra.py.
def pymavlink.mavextra.mag_discrepancy | ( | RAW_IMU, | |
ATTITUDE, | |||
inclination, | |||
declination = None |
|||
) |
give the magnitude of the discrepancy between observed and expected magnetic field
Definition at line 390 of file mavextra.py.
def pymavlink.mavextra.mag_field | ( | RAW_IMU, | |
SENSOR_OFFSETS = None , |
|||
ofs = None |
|||
) |
calculate magnetic field strength from raw magnetometer
Definition at line 105 of file mavextra.py.
def pymavlink.mavextra.mag_field_df | ( | MAG, | |
ofs = None |
|||
) |
calculate magnetic field strength from raw magnetometer (dataflash version)
Definition at line 116 of file mavextra.py.
def pymavlink.mavextra.mag_field_motors | ( | RAW_IMU, | |
SENSOR_OFFSETS, | |||
ofs, | |||
SERVO_OUTPUT_RAW, | |||
motor_ofs | |||
) |
calculate magnetic field strength from raw magnetometer
Definition at line 147 of file mavextra.py.
def pymavlink.mavextra.mag_heading | ( | RAW_IMU, | |
ATTITUDE, | |||
declination = None , |
|||
SENSOR_OFFSETS = None , |
|||
ofs = None |
|||
) |
calculate heading from raw magnetometer
Definition at line 59 of file mavextra.py.
def pymavlink.mavextra.mag_heading_motors | ( | RAW_IMU, | |
ATTITUDE, | |||
declination, | |||
SENSOR_OFFSETS, | |||
ofs, | |||
SERVO_OUTPUT_RAW, | |||
motor_ofs | |||
) |
calculate heading from raw magnetometer
Definition at line 83 of file mavextra.py.
def pymavlink.mavextra.mag_inclination | ( | RAW_IMU, | |
ATTITUDE, | |||
declination = None |
|||
) |
give the magnitude of the discrepancy between observed and expected magnetic field
Definition at line 400 of file mavextra.py.
def pymavlink.mavextra.mag_pitch | ( | RAW_IMU, | |
inclination, | |||
declination | |||
) |
estimate pithc from mag
Definition at line 365 of file mavextra.py.
def pymavlink.mavextra.mag_roll | ( | RAW_IMU, | |
inclination, | |||
declination | |||
) |
estimate roll from mag
Definition at line 371 of file mavextra.py.
def pymavlink.mavextra.mag_rotation | ( | RAW_IMU, | |
inclination, | |||
declination | |||
) |
return an attitude rotation matrix that is consistent with the current mag vector
Definition at line 343 of file mavextra.py.
def pymavlink.mavextra.mag_yaw | ( | RAW_IMU, | |
inclination, | |||
declination | |||
) |
estimate yaw from mag
Definition at line 356 of file mavextra.py.
def pymavlink.mavextra.mix1 | ( | servo1, | |
servo2, | |||
mixtype = 1 , |
|||
gain = 0.5 |
|||
) |
de-mix a mixed servo output
Definition at line 748 of file mavextra.py.
def pymavlink.mavextra.mix2 | ( | servo1, | |
servo2, | |||
mixtype = 1 , |
|||
gain = 0.5 |
|||
) |
de-mix a mixed servo output
Definition at line 753 of file mavextra.py.
def pymavlink.mavextra.mixer | ( | servo1, | |
servo2, | |||
mixtype = 1 , |
|||
gain = 0.5 |
|||
) |
mix two servos
Definition at line 725 of file mavextra.py.
def pymavlink.mavextra.pitch_estimate | ( | RAW_IMU, | |
GPS_RAW_INT = None , |
|||
ATTITUDE = None , |
|||
SENSOR_OFFSETS = None , |
|||
ofs = None , |
|||
mul = None , |
|||
smooth = 0.7 |
|||
) |
estimate pitch from accelerometer
Definition at line 316 of file mavextra.py.
def pymavlink.mavextra.pitch_rate | ( | ATTITUDE | ) |
return pitch rate in earth frame
Definition at line 615 of file mavextra.py.
def pymavlink.mavextra.pitch_sim | ( | SIMSTATE, | |
GPS_RAW | |||
) |
estimate pitch from SIMSTATE accels
Definition at line 454 of file mavextra.py.
def pymavlink.mavextra.PX4_update | ( | IMU, | |
ATT | |||
) |
implement full DCM using PX4 native SD log data
Definition at line 854 of file mavextra.py.
def pymavlink.mavextra.qpitch | ( | MSG | ) |
return quaternion pitch in degrees
Definition at line 1017 of file mavextra.py.
def pymavlink.mavextra.qpitch_p90 | ( | MSG | ) |
return quaternion roll in degrees for view at pitch 90
Definition at line 1044 of file mavextra.py.
def pymavlink.mavextra.qroll | ( | MSG | ) |
return quaternion roll in degrees
Definition at line 1011 of file mavextra.py.
def pymavlink.mavextra.qroll_p90 | ( | MSG | ) |
return quaternion roll in degrees for view at pitch 90
Definition at line 1040 of file mavextra.py.
def pymavlink.mavextra.quat_to_euler | ( | q | ) |
Get Euler angles from a quaternion :param q: quaternion [w, x, y , z] :returns: euler angles [roll, pitch, yaw]
Definition at line 978 of file mavextra.py.
def pymavlink.mavextra.qyaw | ( | MSG | ) |
return quaternion yaw in degrees
Definition at line 1023 of file mavextra.py.
def pymavlink.mavextra.qyaw_p90 | ( | MSG | ) |
return quaternion roll in degrees for view at pitch 90
Definition at line 1048 of file mavextra.py.
def pymavlink.mavextra.rate_of_turn | ( | speed, | |
bank | |||
) |
return expected rate of turn in degrees/s for given speed in m/s and bank angle in degrees
Definition at line 521 of file mavextra.py.
def pymavlink.mavextra.roll_estimate | ( | RAW_IMU, | |
GPS_RAW_INT = None , |
|||
ATTITUDE = None , |
|||
SENSOR_OFFSETS = None , |
|||
ofs = None , |
|||
mul = None , |
|||
smooth = 0.7 |
|||
) |
estimate roll from accelerometer
Definition at line 295 of file mavextra.py.
def pymavlink.mavextra.roll_rate | ( | ATTITUDE | ) |
return roll rate in earth frame
Definition at line 610 of file mavextra.py.
def pymavlink.mavextra.rotate_quat | ( | attitude, | |
roll, | |||
pitch, | |||
yaw | |||
) |
Returns rotated quaternion :param attitude: quaternion [w, x, y , z] :param roll: rotation in rad :param pitch: rotation in rad :param yaw: rotation in rad :returns: quaternion [w, x, y , z]
Definition at line 996 of file mavextra.py.
def pymavlink.mavextra.rotation | ( | ATTITUDE | ) |
return the current DCM rotation matrix
Definition at line 337 of file mavextra.py.
def pymavlink.mavextra.rotation2 | ( | AHRS2 | ) |
return the current DCM rotation matrix
Definition at line 891 of file mavextra.py.
def pymavlink.mavextra.rotation_df | ( | ATT | ) |
return the current DCM rotation matrix
Definition at line 885 of file mavextra.py.
def pymavlink.mavextra.rover_lat_accel | ( | VFR_HUD, | |
SERVO_OUTPUT_RAW | |||
) |
return lateral acceleration in m/s/s
Definition at line 701 of file mavextra.py.
def pymavlink.mavextra.rover_turn_circle | ( | SERVO_OUTPUT_RAW | ) |
return turning circle (diameter) in meters for steering_angle in degrees
Definition at line 674 of file mavextra.py.
def pymavlink.mavextra.rover_yaw_rate | ( | VFR_HUD, | |
SERVO_OUTPUT_RAW | |||
) |
return yaw rate in degrees/second given steering_angle and speed
Definition at line 687 of file mavextra.py.
def pymavlink.mavextra.sawtooth | ( | ATTITUDE, | |
amplitude = 2.0 , |
|||
period = 5.0 |
|||
) |
sawtooth pattern based on uptime
Definition at line 513 of file mavextra.py.
def pymavlink.mavextra.second_derivative_5 | ( | var, | |
key | |||
) |
5 point 2nd derivative
Definition at line 184 of file mavextra.py.
def pymavlink.mavextra.second_derivative_9 | ( | var, | |
key | |||
) |
9 point 2nd derivative
Definition at line 203 of file mavextra.py.
def pymavlink.mavextra.wingloading | ( | bank | ) |
return expected wing loading factor for a bank angle in radians
Definition at line 529 of file mavextra.py.
def pymavlink.mavextra.wrap_180 | ( | angle | ) |
Definition at line 758 of file mavextra.py.
def pymavlink.mavextra.wrap_360 | ( | angle | ) |
Definition at line 766 of file mavextra.py.
def pymavlink.mavextra.wrap_valid_longitude | ( | lon | ) |
wrap a longitude value around to always have a value in the range [-180, +180) i.e 0 => 0, 1 => 1, -1 => -1, 181 => -179, -181 => 179
Definition at line 933 of file mavextra.py.
def pymavlink.mavextra.yaw_rate | ( | ATTITUDE | ) |
return yaw rate in earth frame
Definition at line 620 of file mavextra.py.
|
private |
Definition at line 865 of file mavextra.py.
dictionary pymavlink.mavextra.average_data = {} |
Definition at line 170 of file mavextra.py.
pymavlink.mavextra.dcm_state = None |
Definition at line 817 of file mavextra.py.
dictionary pymavlink.mavextra.derivative_data = {} |
Definition at line 182 of file mavextra.py.
pymavlink.mavextra.ekf_home = None |
Definition at line 963 of file mavextra.py.
pymavlink.mavextra.first_fix = None |
Definition at line 499 of file mavextra.py.
dictionary pymavlink.mavextra.last_delta = {} |
Definition at line 247 of file mavextra.py.
dictionary pymavlink.mavextra.last_diff = {} |
Definition at line 234 of file mavextra.py.
dictionary pymavlink.mavextra.lowpass_data = {} |
Definition at line 223 of file mavextra.py.
pymavlink.mavextra.px4_state = None |
Definition at line 852 of file mavextra.py.
float pymavlink.mavextra.radius_of_earth = 6378100.0 |
Definition at line 931 of file mavextra.py.