px4-firmware/mavlink/share/pyshared/pymavlink/mavlink.py

4931 lines
266 KiB
Python

'''
MAVLink protocol implementation (auto-generated by mavgen.py)
Generated from: ardupilotmega.xml,common.xml
Note: this file has been auto-generated. DO NOT EDIT
'''
import struct, array, mavutil, time
WIRE_PROTOCOL_VERSION = "0.9"
class MAVLink_header(object):
'''MAVLink message header'''
def __init__(self, msgId, mlen=0, seq=0, srcSystem=0, srcComponent=0):
self.mlen = mlen
self.seq = seq
self.srcSystem = srcSystem
self.srcComponent = srcComponent
self.msgId = msgId
def pack(self):
return struct.pack('BBBBBB', 85, self.mlen, self.seq,
self.srcSystem, self.srcComponent, self.msgId)
class MAVLink_message(object):
'''base MAVLink message class'''
def __init__(self, msgId, name):
self._header = MAVLink_header(msgId)
self._payload = None
self._msgbuf = None
self._crc = None
self._fieldnames = []
self._type = name
def get_msgbuf(self):
return self._msgbuf
def get_header(self):
return self._header
def get_payload(self):
return self._payload
def get_crc(self):
return self._crc
def get_fieldnames(self):
return self._fieldnames
def get_type(self):
return self._type
def get_msgId(self):
return self._header.msgId
def get_srcSystem(self):
return self._header.srcSystem
def get_srcComponent(self):
return self._header.srcComponent
def get_seq(self):
return self._header.seq
def __str__(self):
ret = '%s {' % self._type
for a in self._fieldnames:
v = getattr(self, a)
ret += '%s : %s, ' % (a, v)
ret = ret[0:-2] + '}'
return ret
def pack(self, mav, crc_extra, payload):
self._payload = payload
self._header = MAVLink_header(self._header.msgId, len(payload), mav.seq,
mav.srcSystem, mav.srcComponent)
self._msgbuf = self._header.pack() + payload
crc = mavutil.x25crc(self._msgbuf[1:])
if False: # using CRC extra
crc.accumulate(chr(crc_extra))
self._crc = crc.crc
self._msgbuf += struct.pack('<H', self._crc)
return self._msgbuf
# enums
# MAV_MOUNT_MODE
MAV_MOUNT_MODE_RETRACT = 0 # Load and keep safe position (Roll,Pitch,Yaw) from EEPROM and stop
# stabilization
MAV_MOUNT_MODE_NEUTRAL = 1 # Load and keep neutral position (Roll,Pitch,Yaw) from EEPROM.
MAV_MOUNT_MODE_MAVLINK_TARGETING = 2 # Load neutral position and start MAVLink Roll,Pitch,Yaw control with
# stabilization
MAV_MOUNT_MODE_RC_TARGETING = 3 # Load neutral position and start RC Roll,Pitch,Yaw control with
# stabilization
MAV_MOUNT_MODE_GPS_POINT = 4 # Load neutral position and start to point to Lat,Lon,Alt
MAV_MOUNT_MODE_ENUM_END = 5 #
# MAV_CMD
MAV_CMD_NAV_WAYPOINT = 16 # Navigate to waypoint.
MAV_CMD_NAV_LOITER_UNLIM = 17 # Loiter around this waypoint an unlimited amount of time
MAV_CMD_NAV_LOITER_TURNS = 18 # Loiter around this waypoint for X turns
MAV_CMD_NAV_LOITER_TIME = 19 # Loiter around this waypoint for X seconds
MAV_CMD_NAV_RETURN_TO_LAUNCH = 20 # Return to launch location
MAV_CMD_NAV_LAND = 21 # Land at location
MAV_CMD_NAV_TAKEOFF = 22 # Takeoff from ground / hand
MAV_CMD_NAV_ROI = 80 # Sets the region of interest (ROI) for a sensor set or the
# vehicle itself. This can then be used by the
# vehicles control system to
# control the vehicle attitude and the
# attitude of various sensors such
# as cameras.
MAV_CMD_NAV_PATHPLANNING = 81 # Control autonomous path planning on the MAV.
MAV_CMD_NAV_LAST = 95 # NOP - This command is only used to mark the upper limit of the
# NAV/ACTION commands in the enumeration
MAV_CMD_CONDITION_DELAY = 112 # Delay mission state machine.
MAV_CMD_CONDITION_CHANGE_ALT = 113 # Ascend/descend at rate. Delay mission state machine until desired
# altitude reached.
MAV_CMD_CONDITION_DISTANCE = 114 # Delay mission state machine until within desired distance of next NAV
# point.
MAV_CMD_CONDITION_YAW = 115 # Reach a certain target angle.
MAV_CMD_CONDITION_LAST = 159 # NOP - This command is only used to mark the upper limit of the
# CONDITION commands in the enumeration
MAV_CMD_DO_SET_MODE = 176 # Set system mode.
MAV_CMD_DO_JUMP = 177 # Jump to the desired command in the mission list. Repeat this action
# only the specified number of times
MAV_CMD_DO_CHANGE_SPEED = 178 # Change speed and/or throttle set points.
MAV_CMD_DO_SET_HOME = 179 # Changes the home location either to the current location or a
# specified location.
MAV_CMD_DO_SET_PARAMETER = 180 # Set a system parameter. Caution! Use of this command requires
# knowledge of the numeric enumeration value
# of the parameter.
MAV_CMD_DO_SET_RELAY = 181 # Set a relay to a condition.
MAV_CMD_DO_REPEAT_RELAY = 182 # Cycle a relay on and off for a desired number of cyles with a desired
# period.
MAV_CMD_DO_SET_SERVO = 183 # Set a servo to a desired PWM value.
MAV_CMD_DO_REPEAT_SERVO = 184 # Cycle a between its nominal setting and a desired PWM for a desired
# number of cycles with a desired period.
MAV_CMD_DO_CONTROL_VIDEO = 200 # Control onboard camera capturing.
MAV_CMD_DO_SET_ROI = 201 # Sets the region of interest (ROI) for a sensor set or the
# vehicle itself. This can then be used by the
# vehicles control system
# to control the vehicle attitude and the
# attitude of various
# devices such as cameras.
MAV_CMD_DO_DIGICAM_CONFIGURE = 202 # Mission command to configure an on-board camera controller system.
MAV_CMD_DO_DIGICAM_CONTROL = 203 # Mission command to control an on-board camera controller system.
MAV_CMD_DO_MOUNT_CONFIGURE = 204 # Mission command to configure a camera or antenna mount
MAV_CMD_DO_MOUNT_CONTROL = 205 # Mission command to control a camera or antenna mount
MAV_CMD_DO_LAST = 240 # NOP - This command is only used to mark the upper limit of the DO
# commands in the enumeration
MAV_CMD_PREFLIGHT_CALIBRATION = 241 # Trigger calibration. This command will be only accepted if in pre-
# flight mode.
MAV_CMD_PREFLIGHT_STORAGE = 245 # Request storage of different parameter values and logs. This command
# will be only accepted if in pre-flight mode.
MAV_CMD_ENUM_END = 246 #
# FENCE_ACTION
FENCE_ACTION_NONE = 0 # Disable fenced mode
FENCE_ACTION_GUIDED = 1 # Switched to guided mode to return point (fence point 0)
FENCE_ACTION_ENUM_END = 2 #
# FENCE_BREACH
FENCE_BREACH_NONE = 0 # No last fence breach
FENCE_BREACH_MINALT = 1 # Breached minimum altitude
FENCE_BREACH_MAXALT = 2 # Breached minimum altitude
FENCE_BREACH_BOUNDARY = 3 # Breached fence boundary
FENCE_BREACH_ENUM_END = 4 #
# MAV_DATA_STREAM
MAV_DATA_STREAM_ALL = 0 # Enable all data streams
MAV_DATA_STREAM_RAW_SENSORS = 1 # Enable IMU_RAW, GPS_RAW, GPS_STATUS packets.
MAV_DATA_STREAM_EXTENDED_STATUS = 2 # Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS
MAV_DATA_STREAM_RC_CHANNELS = 3 # Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW
MAV_DATA_STREAM_RAW_CONTROLLER = 4 # Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT,
# NAV_CONTROLLER_OUTPUT.
MAV_DATA_STREAM_POSITION = 6 # Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.
MAV_DATA_STREAM_EXTRA1 = 10 # Dependent on the autopilot
MAV_DATA_STREAM_EXTRA2 = 11 # Dependent on the autopilot
MAV_DATA_STREAM_EXTRA3 = 12 # Dependent on the autopilot
MAV_DATA_STREAM_ENUM_END = 13 #
# MAV_ROI
MAV_ROI_NONE = 0 # No region of interest.
MAV_ROI_WPNEXT = 1 # Point toward next waypoint.
MAV_ROI_WPINDEX = 2 # Point toward given waypoint.
MAV_ROI_LOCATION = 3 # Point toward fixed location.
MAV_ROI_TARGET = 4 # Point toward of given id.
MAV_ROI_ENUM_END = 5 #
# message IDs
MAVLINK_MSG_ID_BAD_DATA = -1
MAVLINK_MSG_ID_SENSOR_OFFSETS = 150
MAVLINK_MSG_ID_SET_MAG_OFFSETS = 151
MAVLINK_MSG_ID_MEMINFO = 152
MAVLINK_MSG_ID_AP_ADC = 153
MAVLINK_MSG_ID_DIGICAM_CONFIGURE = 154
MAVLINK_MSG_ID_DIGICAM_CONTROL = 155
MAVLINK_MSG_ID_MOUNT_CONFIGURE = 156
MAVLINK_MSG_ID_MOUNT_CONTROL = 157
MAVLINK_MSG_ID_MOUNT_STATUS = 158
MAVLINK_MSG_ID_FENCE_POINT = 160
MAVLINK_MSG_ID_FENCE_FETCH_POINT = 161
MAVLINK_MSG_ID_FENCE_STATUS = 162
MAVLINK_MSG_ID_AHRS = 163
MAVLINK_MSG_ID_SIMSTATE = 164
MAVLINK_MSG_ID_HWSTATUS = 165
MAVLINK_MSG_ID_RADIO = 166
MAVLINK_MSG_ID_HEARTBEAT = 0
MAVLINK_MSG_ID_BOOT = 1
MAVLINK_MSG_ID_SYSTEM_TIME = 2
MAVLINK_MSG_ID_PING = 3
MAVLINK_MSG_ID_SYSTEM_TIME_UTC = 4
MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL = 5
MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK = 6
MAVLINK_MSG_ID_AUTH_KEY = 7
MAVLINK_MSG_ID_ACTION_ACK = 9
MAVLINK_MSG_ID_ACTION = 10
MAVLINK_MSG_ID_SET_MODE = 11
MAVLINK_MSG_ID_SET_NAV_MODE = 12
MAVLINK_MSG_ID_PARAM_REQUEST_READ = 20
MAVLINK_MSG_ID_PARAM_REQUEST_LIST = 21
MAVLINK_MSG_ID_PARAM_VALUE = 22
MAVLINK_MSG_ID_PARAM_SET = 23
MAVLINK_MSG_ID_GPS_RAW_INT = 25
MAVLINK_MSG_ID_SCALED_IMU = 26
MAVLINK_MSG_ID_GPS_STATUS = 27
MAVLINK_MSG_ID_RAW_IMU = 28
MAVLINK_MSG_ID_RAW_PRESSURE = 29
MAVLINK_MSG_ID_SCALED_PRESSURE = 38
MAVLINK_MSG_ID_ATTITUDE = 30
MAVLINK_MSG_ID_LOCAL_POSITION = 31
MAVLINK_MSG_ID_GLOBAL_POSITION = 33
MAVLINK_MSG_ID_GPS_RAW = 32
MAVLINK_MSG_ID_SYS_STATUS = 34
MAVLINK_MSG_ID_RC_CHANNELS_RAW = 35
MAVLINK_MSG_ID_RC_CHANNELS_SCALED = 36
MAVLINK_MSG_ID_SERVO_OUTPUT_RAW = 37
MAVLINK_MSG_ID_WAYPOINT = 39
MAVLINK_MSG_ID_WAYPOINT_REQUEST = 40
MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT = 41
MAVLINK_MSG_ID_WAYPOINT_CURRENT = 42
MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST = 43
MAVLINK_MSG_ID_WAYPOINT_COUNT = 44
MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL = 45
MAVLINK_MSG_ID_WAYPOINT_REACHED = 46
MAVLINK_MSG_ID_WAYPOINT_ACK = 47
MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN = 48
MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET = 49
MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET = 50
MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT = 51
MAVLINK_MSG_ID_CONTROL_STATUS = 52
MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA = 53
MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA = 54
MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST = 55
MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST = 56
MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT = 57
MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT = 58
MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT = 62
MAVLINK_MSG_ID_POSITION_TARGET = 63
MAVLINK_MSG_ID_STATE_CORRECTION = 64
MAVLINK_MSG_ID_SET_ALTITUDE = 65
MAVLINK_MSG_ID_REQUEST_DATA_STREAM = 66
MAVLINK_MSG_ID_HIL_STATE = 67
MAVLINK_MSG_ID_HIL_CONTROLS = 68
MAVLINK_MSG_ID_MANUAL_CONTROL = 69
MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE = 70
MAVLINK_MSG_ID_GLOBAL_POSITION_INT = 73
MAVLINK_MSG_ID_VFR_HUD = 74
MAVLINK_MSG_ID_COMMAND = 75
MAVLINK_MSG_ID_COMMAND_ACK = 76
MAVLINK_MSG_ID_OPTICAL_FLOW = 100
MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT = 140
MAVLINK_MSG_ID_DEBUG_VECT = 251
MAVLINK_MSG_ID_NAMED_VALUE_FLOAT = 252
MAVLINK_MSG_ID_NAMED_VALUE_INT = 253
MAVLINK_MSG_ID_STATUSTEXT = 254
MAVLINK_MSG_ID_DEBUG = 255
class MAVLink_sensor_offsets_message(MAVLink_message):
'''
Offsets and calibrations values for hardware sensors.
This makes it easier to debug the calibration process.
'''
def __init__(self, mag_ofs_x, mag_ofs_y, mag_ofs_z, mag_declination, raw_press, raw_temp, gyro_cal_x, gyro_cal_y, gyro_cal_z, accel_cal_x, accel_cal_y, accel_cal_z):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_SENSOR_OFFSETS, 'SENSOR_OFFSETS')
self._fieldnames = ['mag_ofs_x', 'mag_ofs_y', 'mag_ofs_z', 'mag_declination', 'raw_press', 'raw_temp', 'gyro_cal_x', 'gyro_cal_y', 'gyro_cal_z', 'accel_cal_x', 'accel_cal_y', 'accel_cal_z']
self.mag_ofs_x = mag_ofs_x
self.mag_ofs_y = mag_ofs_y
self.mag_ofs_z = mag_ofs_z
self.mag_declination = mag_declination
self.raw_press = raw_press
self.raw_temp = raw_temp
self.gyro_cal_x = gyro_cal_x
self.gyro_cal_y = gyro_cal_y
self.gyro_cal_z = gyro_cal_z
self.accel_cal_x = accel_cal_x
self.accel_cal_y = accel_cal_y
self.accel_cal_z = accel_cal_z
def pack(self, mav):
return MAVLink_message.pack(self, mav, 143, struct.pack('>hhhfiiffffff', self.mag_ofs_x, self.mag_ofs_y, self.mag_ofs_z, self.mag_declination, self.raw_press, self.raw_temp, self.gyro_cal_x, self.gyro_cal_y, self.gyro_cal_z, self.accel_cal_x, self.accel_cal_y, self.accel_cal_z))
class MAVLink_set_mag_offsets_message(MAVLink_message):
'''
set the magnetometer offsets
'''
def __init__(self, target_system, target_component, mag_ofs_x, mag_ofs_y, mag_ofs_z):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_SET_MAG_OFFSETS, 'SET_MAG_OFFSETS')
self._fieldnames = ['target_system', 'target_component', 'mag_ofs_x', 'mag_ofs_y', 'mag_ofs_z']
self.target_system = target_system
self.target_component = target_component
self.mag_ofs_x = mag_ofs_x
self.mag_ofs_y = mag_ofs_y
self.mag_ofs_z = mag_ofs_z
def pack(self, mav):
return MAVLink_message.pack(self, mav, 29, struct.pack('>BBhhh', self.target_system, self.target_component, self.mag_ofs_x, self.mag_ofs_y, self.mag_ofs_z))
class MAVLink_meminfo_message(MAVLink_message):
'''
state of APM memory
'''
def __init__(self, brkval, freemem):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_MEMINFO, 'MEMINFO')
self._fieldnames = ['brkval', 'freemem']
self.brkval = brkval
self.freemem = freemem
def pack(self, mav):
return MAVLink_message.pack(self, mav, 208, struct.pack('>HH', self.brkval, self.freemem))
class MAVLink_ap_adc_message(MAVLink_message):
'''
raw ADC output
'''
def __init__(self, adc1, adc2, adc3, adc4, adc5, adc6):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_AP_ADC, 'AP_ADC')
self._fieldnames = ['adc1', 'adc2', 'adc3', 'adc4', 'adc5', 'adc6']
self.adc1 = adc1
self.adc2 = adc2
self.adc3 = adc3
self.adc4 = adc4
self.adc5 = adc5
self.adc6 = adc6
def pack(self, mav):
return MAVLink_message.pack(self, mav, 188, struct.pack('>HHHHHH', self.adc1, self.adc2, self.adc3, self.adc4, self.adc5, self.adc6))
class MAVLink_digicam_configure_message(MAVLink_message):
'''
Configure on-board Camera Control System.
'''
def __init__(self, target_system, target_component, mode, shutter_speed, aperture, iso, exposure_type, command_id, engine_cut_off, extra_param, extra_value):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, 'DIGICAM_CONFIGURE')
self._fieldnames = ['target_system', 'target_component', 'mode', 'shutter_speed', 'aperture', 'iso', 'exposure_type', 'command_id', 'engine_cut_off', 'extra_param', 'extra_value']
self.target_system = target_system
self.target_component = target_component
self.mode = mode
self.shutter_speed = shutter_speed
self.aperture = aperture
self.iso = iso
self.exposure_type = exposure_type
self.command_id = command_id
self.engine_cut_off = engine_cut_off
self.extra_param = extra_param
self.extra_value = extra_value
def pack(self, mav):
return MAVLink_message.pack(self, mav, 118, struct.pack('>BBBHBBBBBBf', self.target_system, self.target_component, self.mode, self.shutter_speed, self.aperture, self.iso, self.exposure_type, self.command_id, self.engine_cut_off, self.extra_param, self.extra_value))
class MAVLink_digicam_control_message(MAVLink_message):
'''
Control on-board Camera Control System to take shots.
'''
def __init__(self, target_system, target_component, session, zoom_pos, zoom_step, focus_lock, shot, command_id, extra_param, extra_value):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_DIGICAM_CONTROL, 'DIGICAM_CONTROL')
self._fieldnames = ['target_system', 'target_component', 'session', 'zoom_pos', 'zoom_step', 'focus_lock', 'shot', 'command_id', 'extra_param', 'extra_value']
self.target_system = target_system
self.target_component = target_component
self.session = session
self.zoom_pos = zoom_pos
self.zoom_step = zoom_step
self.focus_lock = focus_lock
self.shot = shot
self.command_id = command_id
self.extra_param = extra_param
self.extra_value = extra_value
def pack(self, mav):
return MAVLink_message.pack(self, mav, 242, struct.pack('>BBBBbBBBBf', self.target_system, self.target_component, self.session, self.zoom_pos, self.zoom_step, self.focus_lock, self.shot, self.command_id, self.extra_param, self.extra_value))
class MAVLink_mount_configure_message(MAVLink_message):
'''
Message to configure a camera mount, directional antenna, etc.
'''
def __init__(self, target_system, target_component, mount_mode, stab_roll, stab_pitch, stab_yaw):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_MOUNT_CONFIGURE, 'MOUNT_CONFIGURE')
self._fieldnames = ['target_system', 'target_component', 'mount_mode', 'stab_roll', 'stab_pitch', 'stab_yaw']
self.target_system = target_system
self.target_component = target_component
self.mount_mode = mount_mode
self.stab_roll = stab_roll
self.stab_pitch = stab_pitch
self.stab_yaw = stab_yaw
def pack(self, mav):
return MAVLink_message.pack(self, mav, 19, struct.pack('>BBBBBB', self.target_system, self.target_component, self.mount_mode, self.stab_roll, self.stab_pitch, self.stab_yaw))
class MAVLink_mount_control_message(MAVLink_message):
'''
Message to control a camera mount, directional antenna, etc.
'''
def __init__(self, target_system, target_component, input_a, input_b, input_c, save_position):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_MOUNT_CONTROL, 'MOUNT_CONTROL')
self._fieldnames = ['target_system', 'target_component', 'input_a', 'input_b', 'input_c', 'save_position']
self.target_system = target_system
self.target_component = target_component
self.input_a = input_a
self.input_b = input_b
self.input_c = input_c
self.save_position = save_position
def pack(self, mav):
return MAVLink_message.pack(self, mav, 97, struct.pack('>BBiiiB', self.target_system, self.target_component, self.input_a, self.input_b, self.input_c, self.save_position))
class MAVLink_mount_status_message(MAVLink_message):
'''
Message with some status from APM to GCS about camera or
antenna mount
'''
def __init__(self, target_system, target_component, pointing_a, pointing_b, pointing_c):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_MOUNT_STATUS, 'MOUNT_STATUS')
self._fieldnames = ['target_system', 'target_component', 'pointing_a', 'pointing_b', 'pointing_c']
self.target_system = target_system
self.target_component = target_component
self.pointing_a = pointing_a
self.pointing_b = pointing_b
self.pointing_c = pointing_c
def pack(self, mav):
return MAVLink_message.pack(self, mav, 233, struct.pack('>BBiii', self.target_system, self.target_component, self.pointing_a, self.pointing_b, self.pointing_c))
class MAVLink_fence_point_message(MAVLink_message):
'''
A fence point. Used to set a point when from GCS
-> MAV. Also used to return a point from MAV -> GCS
'''
def __init__(self, target_system, target_component, idx, count, lat, lng):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_FENCE_POINT, 'FENCE_POINT')
self._fieldnames = ['target_system', 'target_component', 'idx', 'count', 'lat', 'lng']
self.target_system = target_system
self.target_component = target_component
self.idx = idx
self.count = count
self.lat = lat
self.lng = lng
def pack(self, mav):
return MAVLink_message.pack(self, mav, 18, struct.pack('>BBBBff', self.target_system, self.target_component, self.idx, self.count, self.lat, self.lng))
class MAVLink_fence_fetch_point_message(MAVLink_message):
'''
Request a current fence point from MAV
'''
def __init__(self, target_system, target_component, idx):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_FENCE_FETCH_POINT, 'FENCE_FETCH_POINT')
self._fieldnames = ['target_system', 'target_component', 'idx']
self.target_system = target_system
self.target_component = target_component
self.idx = idx
def pack(self, mav):
return MAVLink_message.pack(self, mav, 68, struct.pack('>BBB', self.target_system, self.target_component, self.idx))
class MAVLink_fence_status_message(MAVLink_message):
'''
Status of geo-fencing. Sent in extended status
stream when fencing enabled
'''
def __init__(self, breach_status, breach_count, breach_type, breach_time):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_FENCE_STATUS, 'FENCE_STATUS')
self._fieldnames = ['breach_status', 'breach_count', 'breach_type', 'breach_time']
self.breach_status = breach_status
self.breach_count = breach_count
self.breach_type = breach_type
self.breach_time = breach_time
def pack(self, mav):
return MAVLink_message.pack(self, mav, 136, struct.pack('>BHBI', self.breach_status, self.breach_count, self.breach_type, self.breach_time))
class MAVLink_ahrs_message(MAVLink_message):
'''
Status of DCM attitude estimator
'''
def __init__(self, omegaIx, omegaIy, omegaIz, accel_weight, renorm_val, error_rp, error_yaw):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_AHRS, 'AHRS')
self._fieldnames = ['omegaIx', 'omegaIy', 'omegaIz', 'accel_weight', 'renorm_val', 'error_rp', 'error_yaw']
self.omegaIx = omegaIx
self.omegaIy = omegaIy
self.omegaIz = omegaIz
self.accel_weight = accel_weight
self.renorm_val = renorm_val
self.error_rp = error_rp
self.error_yaw = error_yaw
def pack(self, mav):
return MAVLink_message.pack(self, mav, 127, struct.pack('>fffffff', self.omegaIx, self.omegaIy, self.omegaIz, self.accel_weight, self.renorm_val, self.error_rp, self.error_yaw))
class MAVLink_simstate_message(MAVLink_message):
'''
Status of simulation environment, if used
'''
def __init__(self, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_SIMSTATE, 'SIMSTATE')
self._fieldnames = ['roll', 'pitch', 'yaw', 'xacc', 'yacc', 'zacc', 'xgyro', 'ygyro', 'zgyro']
self.roll = roll
self.pitch = pitch
self.yaw = yaw
self.xacc = xacc
self.yacc = yacc
self.zacc = zacc
self.xgyro = xgyro
self.ygyro = ygyro
self.zgyro = zgyro
def pack(self, mav):
return MAVLink_message.pack(self, mav, 42, struct.pack('>fffffffff', self.roll, self.pitch, self.yaw, self.xacc, self.yacc, self.zacc, self.xgyro, self.ygyro, self.zgyro))
class MAVLink_hwstatus_message(MAVLink_message):
'''
Status of key hardware
'''
def __init__(self, Vcc, I2Cerr):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_HWSTATUS, 'HWSTATUS')
self._fieldnames = ['Vcc', 'I2Cerr']
self.Vcc = Vcc
self.I2Cerr = I2Cerr
def pack(self, mav):
return MAVLink_message.pack(self, mav, 21, struct.pack('>HB', self.Vcc, self.I2Cerr))
class MAVLink_radio_message(MAVLink_message):
'''
Status generated by radio
'''
def __init__(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_RADIO, 'RADIO')
self._fieldnames = ['rssi', 'remrssi', 'txbuf', 'noise', 'remnoise', 'rxerrors', 'fixed']
self.rssi = rssi
self.remrssi = remrssi
self.txbuf = txbuf
self.noise = noise
self.remnoise = remnoise
self.rxerrors = rxerrors
self.fixed = fixed
def pack(self, mav):
return MAVLink_message.pack(self, mav, 93, struct.pack('>BBBBBHH', self.rssi, self.remrssi, self.txbuf, self.noise, self.remnoise, self.rxerrors, self.fixed))
class MAVLink_heartbeat_message(MAVLink_message):
'''
The heartbeat message shows that a system is present and
responding. The type of the MAV and Autopilot hardware allow
the receiving system to treat further messages from this
system appropriate (e.g. by laying out the user interface
based on the autopilot).
'''
def __init__(self, type, autopilot, mavlink_version):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_HEARTBEAT, 'HEARTBEAT')
self._fieldnames = ['type', 'autopilot', 'mavlink_version']
self.type = type
self.autopilot = autopilot
self.mavlink_version = mavlink_version
def pack(self, mav):
return MAVLink_message.pack(self, mav, 72, struct.pack('>BBB', self.type, self.autopilot, self.mavlink_version))
class MAVLink_boot_message(MAVLink_message):
'''
The boot message indicates that a system is starting. The
onboard software version allows to keep track of onboard
soft/firmware revisions.
'''
def __init__(self, version):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_BOOT, 'BOOT')
self._fieldnames = ['version']
self.version = version
def pack(self, mav):
return MAVLink_message.pack(self, mav, 39, struct.pack('>I', self.version))
class MAVLink_system_time_message(MAVLink_message):
'''
The system time is the time of the master clock, typically the
computer clock of the main onboard computer.
'''
def __init__(self, time_usec):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_SYSTEM_TIME, 'SYSTEM_TIME')
self._fieldnames = ['time_usec']
self.time_usec = time_usec
def pack(self, mav):
return MAVLink_message.pack(self, mav, 190, struct.pack('>Q', self.time_usec))
class MAVLink_ping_message(MAVLink_message):
'''
A ping message either requesting or responding to a ping. This
allows to measure the system latencies, including serial port,
radio modem and UDP connections.
'''
def __init__(self, seq, target_system, target_component, time):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_PING, 'PING')
self._fieldnames = ['seq', 'target_system', 'target_component', 'time']
self.seq = seq
self.target_system = target_system
self.target_component = target_component
self.time = time
def pack(self, mav):
return MAVLink_message.pack(self, mav, 92, struct.pack('>IBBQ', self.seq, self.target_system, self.target_component, self.time))
class MAVLink_system_time_utc_message(MAVLink_message):
'''
UTC date and time from GPS module
'''
def __init__(self, utc_date, utc_time):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_SYSTEM_TIME_UTC, 'SYSTEM_TIME_UTC')
self._fieldnames = ['utc_date', 'utc_time']
self.utc_date = utc_date
self.utc_time = utc_time
def pack(self, mav):
return MAVLink_message.pack(self, mav, 191, struct.pack('>II', self.utc_date, self.utc_time))
class MAVLink_change_operator_control_message(MAVLink_message):
'''
Request to control this MAV
'''
def __init__(self, target_system, control_request, version, passkey):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, 'CHANGE_OPERATOR_CONTROL')
self._fieldnames = ['target_system', 'control_request', 'version', 'passkey']
self.target_system = target_system
self.control_request = control_request
self.version = version
self.passkey = passkey
def pack(self, mav):
return MAVLink_message.pack(self, mav, 217, struct.pack('>BBB25s', self.target_system, self.control_request, self.version, self.passkey))
class MAVLink_change_operator_control_ack_message(MAVLink_message):
'''
Accept / deny control of this MAV
'''
def __init__(self, gcs_system_id, control_request, ack):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, 'CHANGE_OPERATOR_CONTROL_ACK')
self._fieldnames = ['gcs_system_id', 'control_request', 'ack']
self.gcs_system_id = gcs_system_id
self.control_request = control_request
self.ack = ack
def pack(self, mav):
return MAVLink_message.pack(self, mav, 104, struct.pack('>BBB', self.gcs_system_id, self.control_request, self.ack))
class MAVLink_auth_key_message(MAVLink_message):
'''
Emit an encrypted signature / key identifying this system.
PLEASE NOTE: This protocol has been kept simple, so
transmitting the key requires an encrypted channel for true
safety.
'''
def __init__(self, key):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_AUTH_KEY, 'AUTH_KEY')
self._fieldnames = ['key']
self.key = key
def pack(self, mav):
return MAVLink_message.pack(self, mav, 119, struct.pack('>32s', self.key))
class MAVLink_action_ack_message(MAVLink_message):
'''
This message acknowledges an action. IMPORTANT: The
acknowledgement can be also negative, e.g. the MAV rejects a
reset message because it is in-flight. The action ids are
defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h
'''
def __init__(self, action, result):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_ACTION_ACK, 'ACTION_ACK')
self._fieldnames = ['action', 'result']
self.action = action
self.result = result
def pack(self, mav):
return MAVLink_message.pack(self, mav, 219, struct.pack('>BB', self.action, self.result))
class MAVLink_action_message(MAVLink_message):
'''
An action message allows to execute a certain onboard action.
These include liftoff, land, storing parameters too EEPROM,
shutddown, etc. The action ids are defined in ENUM MAV_ACTION
in mavlink/include/mavlink_types.h
'''
def __init__(self, target, target_component, action):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_ACTION, 'ACTION')
self._fieldnames = ['target', 'target_component', 'action']
self.target = target
self.target_component = target_component
self.action = action
def pack(self, mav):
return MAVLink_message.pack(self, mav, 60, struct.pack('>BBB', self.target, self.target_component, self.action))
class MAVLink_set_mode_message(MAVLink_message):
'''
Set the system mode, as defined by enum MAV_MODE in
mavlink/include/mavlink_types.h. There is no target component
id as the mode is by definition for the overall aircraft, not
only for one component.
'''
def __init__(self, target, mode):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_SET_MODE, 'SET_MODE')
self._fieldnames = ['target', 'mode']
self.target = target
self.mode = mode
def pack(self, mav):
return MAVLink_message.pack(self, mav, 186, struct.pack('>BB', self.target, self.mode))
class MAVLink_set_nav_mode_message(MAVLink_message):
'''
Set the system navigation mode, as defined by enum
MAV_NAV_MODE in mavlink/include/mavlink_types.h. The
navigation mode applies to the whole aircraft and thus all
components.
'''
def __init__(self, target, nav_mode):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_SET_NAV_MODE, 'SET_NAV_MODE')
self._fieldnames = ['target', 'nav_mode']
self.target = target
self.nav_mode = nav_mode
def pack(self, mav):
return MAVLink_message.pack(self, mav, 10, struct.pack('>BB', self.target, self.nav_mode))
class MAVLink_param_request_read_message(MAVLink_message):
'''
Request to read the onboard parameter with the param_id string
id. Onboard parameters are stored as key[const char*] ->
value[float]. This allows to send a parameter to any other
component (such as the GCS) without the need of previous
knowledge of possible parameter names. Thus the same GCS can
store different parameters for different autopilots. See also
http://qgroundcontrol.org/parameter_interface for a full
documentation of QGroundControl and IMU code.
'''
def __init__(self, target_system, target_component, param_id, param_index):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_PARAM_REQUEST_READ, 'PARAM_REQUEST_READ')
self._fieldnames = ['target_system', 'target_component', 'param_id', 'param_index']
self.target_system = target_system
self.target_component = target_component
self.param_id = param_id
self.param_index = param_index
def pack(self, mav):
return MAVLink_message.pack(self, mav, 89, struct.pack('>BB15sh', self.target_system, self.target_component, self.param_id, self.param_index))
class MAVLink_param_request_list_message(MAVLink_message):
'''
Request all parameters of this component. After his request,
all parameters are emitted.
'''
def __init__(self, target_system, target_component):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, 'PARAM_REQUEST_LIST')
self._fieldnames = ['target_system', 'target_component']
self.target_system = target_system
self.target_component = target_component
def pack(self, mav):
return MAVLink_message.pack(self, mav, 159, struct.pack('>BB', self.target_system, self.target_component))
class MAVLink_param_value_message(MAVLink_message):
'''
Emit the value of a onboard parameter. The inclusion of
param_count and param_index in the message allows the
recipient to keep track of received parameters and allows him
to re-request missing parameters after a loss or timeout.
'''
def __init__(self, param_id, param_value, param_count, param_index):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_PARAM_VALUE, 'PARAM_VALUE')
self._fieldnames = ['param_id', 'param_value', 'param_count', 'param_index']
self.param_id = param_id
self.param_value = param_value
self.param_count = param_count
self.param_index = param_index
def pack(self, mav):
return MAVLink_message.pack(self, mav, 162, struct.pack('>15sfHH', self.param_id, self.param_value, self.param_count, self.param_index))
class MAVLink_param_set_message(MAVLink_message):
'''
Set a parameter value TEMPORARILY to RAM. It will be reset to
default on system reboot. Send the ACTION
MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM contents
to EEPROM. IMPORTANT: The receiving component should
acknowledge the new parameter value by sending a param_value
message to all communication partners. This will also ensure
that multiple GCS all have an up-to-date list of all
parameters. If the sending GCS did not receive a PARAM_VALUE
message within its timeout time, it should re-send the
PARAM_SET message.
'''
def __init__(self, target_system, target_component, param_id, param_value):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_PARAM_SET, 'PARAM_SET')
self._fieldnames = ['target_system', 'target_component', 'param_id', 'param_value']
self.target_system = target_system
self.target_component = target_component
self.param_id = param_id
self.param_value = param_value
def pack(self, mav):
return MAVLink_message.pack(self, mav, 121, struct.pack('>BB15sf', self.target_system, self.target_component, self.param_id, self.param_value))
class MAVLink_gps_raw_int_message(MAVLink_message):
'''
The global position, as returned by the Global Positioning
System (GPS). This is NOT the global position estimate of the
sytem, but rather a RAW sensor value. See message
GLOBAL_POSITION for the global position estimate. Coordinate
frame is right-handed, Z-axis up (GPS frame)
'''
def __init__(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_GPS_RAW_INT, 'GPS_RAW_INT')
self._fieldnames = ['usec', 'fix_type', 'lat', 'lon', 'alt', 'eph', 'epv', 'v', 'hdg']
self.usec = usec
self.fix_type = fix_type
self.lat = lat
self.lon = lon
self.alt = alt
self.eph = eph
self.epv = epv
self.v = v
self.hdg = hdg
def pack(self, mav):
return MAVLink_message.pack(self, mav, 149, struct.pack('>QBiiiffff', self.usec, self.fix_type, self.lat, self.lon, self.alt, self.eph, self.epv, self.v, self.hdg))
class MAVLink_scaled_imu_message(MAVLink_message):
'''
The RAW IMU readings for the usual 9DOF sensor setup. This
message should contain the scaled values to the described
units
'''
def __init__(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_SCALED_IMU, 'SCALED_IMU')
self._fieldnames = ['usec', 'xacc', 'yacc', 'zacc', 'xgyro', 'ygyro', 'zgyro', 'xmag', 'ymag', 'zmag']
self.usec = usec
self.xacc = xacc
self.yacc = yacc
self.zacc = zacc
self.xgyro = xgyro
self.ygyro = ygyro
self.zgyro = zgyro
self.xmag = xmag
self.ymag = ymag
self.zmag = zmag
def pack(self, mav):
return MAVLink_message.pack(self, mav, 222, struct.pack('>Qhhhhhhhhh', self.usec, self.xacc, self.yacc, self.zacc, self.xgyro, self.ygyro, self.zgyro, self.xmag, self.ymag, self.zmag))
class MAVLink_gps_status_message(MAVLink_message):
'''
The positioning status, as reported by GPS. This message is
intended to display status information about each satellite
visible to the receiver. See message GLOBAL_POSITION for the
global position estimate. This message can contain information
for up to 20 satellites.
'''
def __init__(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_GPS_STATUS, 'GPS_STATUS')
self._fieldnames = ['satellites_visible', 'satellite_prn', 'satellite_used', 'satellite_elevation', 'satellite_azimuth', 'satellite_snr']
self.satellites_visible = satellites_visible
self.satellite_prn = satellite_prn
self.satellite_used = satellite_used
self.satellite_elevation = satellite_elevation
self.satellite_azimuth = satellite_azimuth
self.satellite_snr = satellite_snr
def pack(self, mav):
return MAVLink_message.pack(self, mav, 110, struct.pack('>B20s20s20s20s20s', self.satellites_visible, self.satellite_prn, self.satellite_used, self.satellite_elevation, self.satellite_azimuth, self.satellite_snr))
class MAVLink_raw_imu_message(MAVLink_message):
'''
The RAW IMU readings for the usual 9DOF sensor setup. This
message should always contain the true raw values without any
scaling to allow data capture and system debugging.
'''
def __init__(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_RAW_IMU, 'RAW_IMU')
self._fieldnames = ['usec', 'xacc', 'yacc', 'zacc', 'xgyro', 'ygyro', 'zgyro', 'xmag', 'ymag', 'zmag']
self.usec = usec
self.xacc = xacc
self.yacc = yacc
self.zacc = zacc
self.xgyro = xgyro
self.ygyro = ygyro
self.zgyro = zgyro
self.xmag = xmag
self.ymag = ymag
self.zmag = zmag
def pack(self, mav):
return MAVLink_message.pack(self, mav, 179, struct.pack('>Qhhhhhhhhh', self.usec, self.xacc, self.yacc, self.zacc, self.xgyro, self.ygyro, self.zgyro, self.xmag, self.ymag, self.zmag))
class MAVLink_raw_pressure_message(MAVLink_message):
'''
The RAW pressure readings for the typical setup of one
absolute pressure and one differential pressure sensor. The
sensor values should be the raw, UNSCALED ADC values.
'''
def __init__(self, usec, press_abs, press_diff1, press_diff2, temperature):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_RAW_PRESSURE, 'RAW_PRESSURE')
self._fieldnames = ['usec', 'press_abs', 'press_diff1', 'press_diff2', 'temperature']
self.usec = usec
self.press_abs = press_abs
self.press_diff1 = press_diff1
self.press_diff2 = press_diff2
self.temperature = temperature
def pack(self, mav):
return MAVLink_message.pack(self, mav, 136, struct.pack('>Qhhhh', self.usec, self.press_abs, self.press_diff1, self.press_diff2, self.temperature))
class MAVLink_scaled_pressure_message(MAVLink_message):
'''
The pressure readings for the typical setup of one absolute
and differential pressure sensor. The units are as specified
in each field.
'''
def __init__(self, usec, press_abs, press_diff, temperature):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_SCALED_PRESSURE, 'SCALED_PRESSURE')
self._fieldnames = ['usec', 'press_abs', 'press_diff', 'temperature']
self.usec = usec
self.press_abs = press_abs
self.press_diff = press_diff
self.temperature = temperature
def pack(self, mav):
return MAVLink_message.pack(self, mav, 229, struct.pack('>Qffh', self.usec, self.press_abs, self.press_diff, self.temperature))
class MAVLink_attitude_message(MAVLink_message):
'''
The attitude in the aeronautical frame (right-handed, Z-down,
X-front, Y-right).
'''
def __init__(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_ATTITUDE, 'ATTITUDE')
self._fieldnames = ['usec', 'roll', 'pitch', 'yaw', 'rollspeed', 'pitchspeed', 'yawspeed']
self.usec = usec
self.roll = roll
self.pitch = pitch
self.yaw = yaw
self.rollspeed = rollspeed
self.pitchspeed = pitchspeed
self.yawspeed = yawspeed
def pack(self, mav):
return MAVLink_message.pack(self, mav, 66, struct.pack('>Qffffff', self.usec, self.roll, self.pitch, self.yaw, self.rollspeed, self.pitchspeed, self.yawspeed))
class MAVLink_local_position_message(MAVLink_message):
'''
The filtered local position (e.g. fused computer vision and
accelerometers). Coordinate frame is right-handed, Z-axis down
(aeronautical frame)
'''
def __init__(self, usec, x, y, z, vx, vy, vz):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_LOCAL_POSITION, 'LOCAL_POSITION')
self._fieldnames = ['usec', 'x', 'y', 'z', 'vx', 'vy', 'vz']
self.usec = usec
self.x = x
self.y = y
self.z = z
self.vx = vx
self.vy = vy
self.vz = vz
def pack(self, mav):
return MAVLink_message.pack(self, mav, 126, struct.pack('>Qffffff', self.usec, self.x, self.y, self.z, self.vx, self.vy, self.vz))
class MAVLink_global_position_message(MAVLink_message):
'''
The filtered global position (e.g. fused GPS and
accelerometers). Coordinate frame is right-handed, Z-axis up
(GPS frame)
'''
def __init__(self, usec, lat, lon, alt, vx, vy, vz):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_GLOBAL_POSITION, 'GLOBAL_POSITION')
self._fieldnames = ['usec', 'lat', 'lon', 'alt', 'vx', 'vy', 'vz']
self.usec = usec
self.lat = lat
self.lon = lon
self.alt = alt
self.vx = vx
self.vy = vy
self.vz = vz
def pack(self, mav):
return MAVLink_message.pack(self, mav, 147, struct.pack('>Qffffff', self.usec, self.lat, self.lon, self.alt, self.vx, self.vy, self.vz))
class MAVLink_gps_raw_message(MAVLink_message):
'''
The global position, as returned by the Global Positioning
System (GPS). This is NOT the global position estimate of the
sytem, but rather a RAW sensor value. See message
GLOBAL_POSITION for the global position estimate. Coordinate
frame is right-handed, Z-axis up (GPS frame)
'''
def __init__(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_GPS_RAW, 'GPS_RAW')
self._fieldnames = ['usec', 'fix_type', 'lat', 'lon', 'alt', 'eph', 'epv', 'v', 'hdg']
self.usec = usec
self.fix_type = fix_type
self.lat = lat
self.lon = lon
self.alt = alt
self.eph = eph
self.epv = epv
self.v = v
self.hdg = hdg
def pack(self, mav):
return MAVLink_message.pack(self, mav, 185, struct.pack('>QBfffffff', self.usec, self.fix_type, self.lat, self.lon, self.alt, self.eph, self.epv, self.v, self.hdg))
class MAVLink_sys_status_message(MAVLink_message):
'''
The general system state. If the system is following the
MAVLink standard, the system state is mainly defined by three
orthogonal states/modes: The system mode, which is either
LOCKED (motors shut down and locked), MANUAL (system under RC
control), GUIDED (system with autonomous position control,
position setpoint controlled manually) or AUTO (system guided
by path/waypoint planner). The NAV_MODE defined the current
flight state: LIFTOFF (often an open-loop maneuver), LANDING,
WAYPOINTS or VECTOR. This represents the internal navigation
state machine. The system status shows wether the system is
currently active or not and if an emergency occured. During
the CRITICAL and EMERGENCY states the MAV is still considered
to be active, but should start emergency procedures
autonomously. After a failure occured it should first move
from active to critical to allow manual intervention and then
move to emergency after a certain timeout.
'''
def __init__(self, mode, nav_mode, status, load, vbat, battery_remaining, packet_drop):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_SYS_STATUS, 'SYS_STATUS')
self._fieldnames = ['mode', 'nav_mode', 'status', 'load', 'vbat', 'battery_remaining', 'packet_drop']
self.mode = mode
self.nav_mode = nav_mode
self.status = status
self.load = load
self.vbat = vbat
self.battery_remaining = battery_remaining
self.packet_drop = packet_drop
def pack(self, mav):
return MAVLink_message.pack(self, mav, 112, struct.pack('>BBBHHHH', self.mode, self.nav_mode, self.status, self.load, self.vbat, self.battery_remaining, self.packet_drop))
class MAVLink_rc_channels_raw_message(MAVLink_message):
'''
The RAW values of the RC channels received. The standard PPM
modulation is as follows: 1000 microseconds: 0%, 2000
microseconds: 100%. Individual receivers/transmitters might
violate this specification.
'''
def __init__(self, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_RC_CHANNELS_RAW, 'RC_CHANNELS_RAW')
self._fieldnames = ['chan1_raw', 'chan2_raw', 'chan3_raw', 'chan4_raw', 'chan5_raw', 'chan6_raw', 'chan7_raw', 'chan8_raw', 'rssi']
self.chan1_raw = chan1_raw
self.chan2_raw = chan2_raw
self.chan3_raw = chan3_raw
self.chan4_raw = chan4_raw
self.chan5_raw = chan5_raw
self.chan6_raw = chan6_raw
self.chan7_raw = chan7_raw
self.chan8_raw = chan8_raw
self.rssi = rssi
def pack(self, mav):
return MAVLink_message.pack(self, mav, 252, struct.pack('>HHHHHHHHB', self.chan1_raw, self.chan2_raw, self.chan3_raw, self.chan4_raw, self.chan5_raw, self.chan6_raw, self.chan7_raw, self.chan8_raw, self.rssi))
class MAVLink_rc_channels_scaled_message(MAVLink_message):
'''
The scaled values of the RC channels received. (-100%) -10000,
(0%) 0, (100%) 10000
'''
def __init__(self, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, 'RC_CHANNELS_SCALED')
self._fieldnames = ['chan1_scaled', 'chan2_scaled', 'chan3_scaled', 'chan4_scaled', 'chan5_scaled', 'chan6_scaled', 'chan7_scaled', 'chan8_scaled', 'rssi']
self.chan1_scaled = chan1_scaled
self.chan2_scaled = chan2_scaled
self.chan3_scaled = chan3_scaled
self.chan4_scaled = chan4_scaled
self.chan5_scaled = chan5_scaled
self.chan6_scaled = chan6_scaled
self.chan7_scaled = chan7_scaled
self.chan8_scaled = chan8_scaled
self.rssi = rssi
def pack(self, mav):
return MAVLink_message.pack(self, mav, 162, struct.pack('>hhhhhhhhB', self.chan1_scaled, self.chan2_scaled, self.chan3_scaled, self.chan4_scaled, self.chan5_scaled, self.chan6_scaled, self.chan7_scaled, self.chan8_scaled, self.rssi))
class MAVLink_servo_output_raw_message(MAVLink_message):
'''
The RAW values of the servo outputs (for RC input from the
remote, use the RC_CHANNELS messages). The standard PPM
modulation is as follows: 1000 microseconds: 0%, 2000
microseconds: 100%.
'''
def __init__(self, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, 'SERVO_OUTPUT_RAW')
self._fieldnames = ['servo1_raw', 'servo2_raw', 'servo3_raw', 'servo4_raw', 'servo5_raw', 'servo6_raw', 'servo7_raw', 'servo8_raw']
self.servo1_raw = servo1_raw
self.servo2_raw = servo2_raw
self.servo3_raw = servo3_raw
self.servo4_raw = servo4_raw
self.servo5_raw = servo5_raw
self.servo6_raw = servo6_raw
self.servo7_raw = servo7_raw
self.servo8_raw = servo8_raw
def pack(self, mav):
return MAVLink_message.pack(self, mav, 215, struct.pack('>HHHHHHHH', self.servo1_raw, self.servo2_raw, self.servo3_raw, self.servo4_raw, self.servo5_raw, self.servo6_raw, self.servo7_raw, self.servo8_raw))
class MAVLink_waypoint_message(MAVLink_message):
'''
Message encoding a waypoint. This message is emitted to
announce the presence of a waypoint and to set a waypoint
on the system. The waypoint can be either in x, y, z meters
(type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is
Z-down, right handed, global frame is Z-up, right handed
'''
def __init__(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_WAYPOINT, 'WAYPOINT')
self._fieldnames = ['target_system', 'target_component', 'seq', 'frame', 'command', 'current', 'autocontinue', 'param1', 'param2', 'param3', 'param4', 'x', 'y', 'z']
self.target_system = target_system
self.target_component = target_component
self.seq = seq
self.frame = frame
self.command = command
self.current = current
self.autocontinue = autocontinue
self.param1 = param1
self.param2 = param2
self.param3 = param3
self.param4 = param4
self.x = x
self.y = y
self.z = z
def pack(self, mav):
return MAVLink_message.pack(self, mav, 128, struct.pack('>BBHBBBBfffffff', self.target_system, self.target_component, self.seq, self.frame, self.command, self.current, self.autocontinue, self.param1, self.param2, self.param3, self.param4, self.x, self.y, self.z))
class MAVLink_waypoint_request_message(MAVLink_message):
'''
Request the information of the waypoint with the sequence
number seq. The response of the system to this message should
be a WAYPOINT message.
'''
def __init__(self, target_system, target_component, seq):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_WAYPOINT_REQUEST, 'WAYPOINT_REQUEST')
self._fieldnames = ['target_system', 'target_component', 'seq']
self.target_system = target_system
self.target_component = target_component
self.seq = seq
def pack(self, mav):
return MAVLink_message.pack(self, mav, 9, struct.pack('>BBH', self.target_system, self.target_component, self.seq))
class MAVLink_waypoint_set_current_message(MAVLink_message):
'''
Set the waypoint with sequence number seq as current waypoint.
This means that the MAV will continue to this waypoint on the
shortest path (not following the waypoints in-between).
'''
def __init__(self, target_system, target_component, seq):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT, 'WAYPOINT_SET_CURRENT')
self._fieldnames = ['target_system', 'target_component', 'seq']
self.target_system = target_system
self.target_component = target_component
self.seq = seq
def pack(self, mav):
return MAVLink_message.pack(self, mav, 106, struct.pack('>BBH', self.target_system, self.target_component, self.seq))
class MAVLink_waypoint_current_message(MAVLink_message):
'''
Message that announces the sequence number of the current
active waypoint. The MAV will fly towards this waypoint.
'''
def __init__(self, seq):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_WAYPOINT_CURRENT, 'WAYPOINT_CURRENT')
self._fieldnames = ['seq']
self.seq = seq
def pack(self, mav):
return MAVLink_message.pack(self, mav, 101, struct.pack('>H', self.seq))
class MAVLink_waypoint_request_list_message(MAVLink_message):
'''
Request the overall list of waypoints from the
system/component.
'''
def __init__(self, target_system, target_component):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST, 'WAYPOINT_REQUEST_LIST')
self._fieldnames = ['target_system', 'target_component']
self.target_system = target_system
self.target_component = target_component
def pack(self, mav):
return MAVLink_message.pack(self, mav, 213, struct.pack('>BB', self.target_system, self.target_component))
class MAVLink_waypoint_count_message(MAVLink_message):
'''
This message is emitted as response to WAYPOINT_REQUEST_LIST
by the MAV. The GCS can then request the individual waypoints
based on the knowledge of the total number of waypoints.
'''
def __init__(self, target_system, target_component, count):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_WAYPOINT_COUNT, 'WAYPOINT_COUNT')
self._fieldnames = ['target_system', 'target_component', 'count']
self.target_system = target_system
self.target_component = target_component
self.count = count
def pack(self, mav):
return MAVLink_message.pack(self, mav, 4, struct.pack('>BBH', self.target_system, self.target_component, self.count))
class MAVLink_waypoint_clear_all_message(MAVLink_message):
'''
Delete all waypoints at once.
'''
def __init__(self, target_system, target_component):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL, 'WAYPOINT_CLEAR_ALL')
self._fieldnames = ['target_system', 'target_component']
self.target_system = target_system
self.target_component = target_component
def pack(self, mav):
return MAVLink_message.pack(self, mav, 229, struct.pack('>BB', self.target_system, self.target_component))
class MAVLink_waypoint_reached_message(MAVLink_message):
'''
A certain waypoint has been reached. The system will either
hold this position (or circle on the orbit) or (if the
autocontinue on the WP was set) continue to the next waypoint.
'''
def __init__(self, seq):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_WAYPOINT_REACHED, 'WAYPOINT_REACHED')
self._fieldnames = ['seq']
self.seq = seq
def pack(self, mav):
return MAVLink_message.pack(self, mav, 21, struct.pack('>H', self.seq))
class MAVLink_waypoint_ack_message(MAVLink_message):
'''
Ack message during waypoint handling. The type field states if
this message is a positive ack (type=0) or if an error
happened (type=non-zero).
'''
def __init__(self, target_system, target_component, type):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_WAYPOINT_ACK, 'WAYPOINT_ACK')
self._fieldnames = ['target_system', 'target_component', 'type']
self.target_system = target_system
self.target_component = target_component
self.type = type
def pack(self, mav):
return MAVLink_message.pack(self, mav, 214, struct.pack('>BBB', self.target_system, self.target_component, self.type))
class MAVLink_gps_set_global_origin_message(MAVLink_message):
'''
As local waypoints exist, the global waypoint reference allows
to transform between the local coordinate frame and the global
(GPS) coordinate frame. This can be necessary when e.g. in-
and outdoor settings are connected and the MAV should move
from in- to outdoor.
'''
def __init__(self, target_system, target_component, latitude, longitude, altitude):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN, 'GPS_SET_GLOBAL_ORIGIN')
self._fieldnames = ['target_system', 'target_component', 'latitude', 'longitude', 'altitude']
self.target_system = target_system
self.target_component = target_component
self.latitude = latitude
self.longitude = longitude
self.altitude = altitude
def pack(self, mav):
return MAVLink_message.pack(self, mav, 215, struct.pack('>BBiii', self.target_system, self.target_component, self.latitude, self.longitude, self.altitude))
class MAVLink_gps_local_origin_set_message(MAVLink_message):
'''
Once the MAV sets a new GPS-Local correspondence, this message
announces the origin (0,0,0) position
'''
def __init__(self, latitude, longitude, altitude):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET, 'GPS_LOCAL_ORIGIN_SET')
self._fieldnames = ['latitude', 'longitude', 'altitude']
self.latitude = latitude
self.longitude = longitude
self.altitude = altitude
def pack(self, mav):
return MAVLink_message.pack(self, mav, 14, struct.pack('>iii', self.latitude, self.longitude, self.altitude))
class MAVLink_local_position_setpoint_set_message(MAVLink_message):
'''
Set the setpoint for a local position controller. This is the
position in local coordinates the MAV should fly to. This
message is sent by the path/waypoint planner to the onboard
position controller. As some MAVs have a degree of freedom in
yaw (e.g. all helicopters/quadrotors), the desired yaw angle
is part of the message.
'''
def __init__(self, target_system, target_component, x, y, z, yaw):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET, 'LOCAL_POSITION_SETPOINT_SET')
self._fieldnames = ['target_system', 'target_component', 'x', 'y', 'z', 'yaw']
self.target_system = target_system
self.target_component = target_component
self.x = x
self.y = y
self.z = z
self.yaw = yaw
def pack(self, mav):
return MAVLink_message.pack(self, mav, 206, struct.pack('>BBffff', self.target_system, self.target_component, self.x, self.y, self.z, self.yaw))
class MAVLink_local_position_setpoint_message(MAVLink_message):
'''
Transmit the current local setpoint of the controller to other
MAVs (collision avoidance) and to the GCS.
'''
def __init__(self, x, y, z, yaw):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, 'LOCAL_POSITION_SETPOINT')
self._fieldnames = ['x', 'y', 'z', 'yaw']
self.x = x
self.y = y
self.z = z
self.yaw = yaw
def pack(self, mav):
return MAVLink_message.pack(self, mav, 50, struct.pack('>ffff', self.x, self.y, self.z, self.yaw))
class MAVLink_control_status_message(MAVLink_message):
'''
'''
def __init__(self, position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_CONTROL_STATUS, 'CONTROL_STATUS')
self._fieldnames = ['position_fix', 'vision_fix', 'gps_fix', 'ahrs_health', 'control_att', 'control_pos_xy', 'control_pos_z', 'control_pos_yaw']
self.position_fix = position_fix
self.vision_fix = vision_fix
self.gps_fix = gps_fix
self.ahrs_health = ahrs_health
self.control_att = control_att
self.control_pos_xy = control_pos_xy
self.control_pos_z = control_pos_z
self.control_pos_yaw = control_pos_yaw
def pack(self, mav):
return MAVLink_message.pack(self, mav, 157, struct.pack('>BBBBBBBB', self.position_fix, self.vision_fix, self.gps_fix, self.ahrs_health, self.control_att, self.control_pos_xy, self.control_pos_z, self.control_pos_yaw))
class MAVLink_safety_set_allowed_area_message(MAVLink_message):
'''
Set a safety zone (volume), which is defined by two corners of
a cube. This message can be used to tell the MAV which
setpoints/waypoints to accept and which to reject. Safety
areas are often enforced by national or competition
regulations.
'''
def __init__(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, 'SAFETY_SET_ALLOWED_AREA')
self._fieldnames = ['target_system', 'target_component', 'frame', 'p1x', 'p1y', 'p1z', 'p2x', 'p2y', 'p2z']
self.target_system = target_system
self.target_component = target_component
self.frame = frame
self.p1x = p1x
self.p1y = p1y
self.p1z = p1z
self.p2x = p2x
self.p2y = p2y
self.p2z = p2z
def pack(self, mav):
return MAVLink_message.pack(self, mav, 126, struct.pack('>BBBffffff', self.target_system, self.target_component, self.frame, self.p1x, self.p1y, self.p1z, self.p2x, self.p2y, self.p2z))
class MAVLink_safety_allowed_area_message(MAVLink_message):
'''
Read out the safety zone the MAV currently assumes.
'''
def __init__(self, frame, p1x, p1y, p1z, p2x, p2y, p2z):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, 'SAFETY_ALLOWED_AREA')
self._fieldnames = ['frame', 'p1x', 'p1y', 'p1z', 'p2x', 'p2y', 'p2z']
self.frame = frame
self.p1x = p1x
self.p1y = p1y
self.p1z = p1z
self.p2x = p2x
self.p2y = p2y
self.p2z = p2z
def pack(self, mav):
return MAVLink_message.pack(self, mav, 108, struct.pack('>Bffffff', self.frame, self.p1x, self.p1y, self.p1z, self.p2x, self.p2y, self.p2z))
class MAVLink_set_roll_pitch_yaw_thrust_message(MAVLink_message):
'''
Set roll, pitch and yaw.
'''
def __init__(self, target_system, target_component, roll, pitch, yaw, thrust):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST, 'SET_ROLL_PITCH_YAW_THRUST')
self._fieldnames = ['target_system', 'target_component', 'roll', 'pitch', 'yaw', 'thrust']
self.target_system = target_system
self.target_component = target_component
self.roll = roll
self.pitch = pitch
self.yaw = yaw
self.thrust = thrust
def pack(self, mav):
return MAVLink_message.pack(self, mav, 213, struct.pack('>BBffff', self.target_system, self.target_component, self.roll, self.pitch, self.yaw, self.thrust))
class MAVLink_set_roll_pitch_yaw_speed_thrust_message(MAVLink_message):
'''
Set roll, pitch and yaw.
'''
def __init__(self, target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST, 'SET_ROLL_PITCH_YAW_SPEED_THRUST')
self._fieldnames = ['target_system', 'target_component', 'roll_speed', 'pitch_speed', 'yaw_speed', 'thrust']
self.target_system = target_system
self.target_component = target_component
self.roll_speed = roll_speed
self.pitch_speed = pitch_speed
self.yaw_speed = yaw_speed
self.thrust = thrust
def pack(self, mav):
return MAVLink_message.pack(self, mav, 95, struct.pack('>BBffff', self.target_system, self.target_component, self.roll_speed, self.pitch_speed, self.yaw_speed, self.thrust))
class MAVLink_roll_pitch_yaw_thrust_setpoint_message(MAVLink_message):
'''
Setpoint in roll, pitch, yaw currently active on the system.
'''
def __init__(self, time_us, roll, pitch, yaw, thrust):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, 'ROLL_PITCH_YAW_THRUST_SETPOINT')
self._fieldnames = ['time_us', 'roll', 'pitch', 'yaw', 'thrust']
self.time_us = time_us
self.roll = roll
self.pitch = pitch
self.yaw = yaw
self.thrust = thrust
def pack(self, mav):
return MAVLink_message.pack(self, mav, 5, struct.pack('>Qffff', self.time_us, self.roll, self.pitch, self.yaw, self.thrust))
class MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message(MAVLink_message):
'''
Setpoint in rollspeed, pitchspeed, yawspeed currently active
on the system.
'''
def __init__(self, time_us, roll_speed, pitch_speed, yaw_speed, thrust):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, 'ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT')
self._fieldnames = ['time_us', 'roll_speed', 'pitch_speed', 'yaw_speed', 'thrust']
self.time_us = time_us
self.roll_speed = roll_speed
self.pitch_speed = pitch_speed
self.yaw_speed = yaw_speed
self.thrust = thrust
def pack(self, mav):
return MAVLink_message.pack(self, mav, 127, struct.pack('>Qffff', self.time_us, self.roll_speed, self.pitch_speed, self.yaw_speed, self.thrust))
class MAVLink_nav_controller_output_message(MAVLink_message):
'''
Outputs of the APM navigation controller. The primary use of
this message is to check the response and signs of the
controller before actual flight and to assist with tuning
controller parameters
'''
def __init__(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, 'NAV_CONTROLLER_OUTPUT')
self._fieldnames = ['nav_roll', 'nav_pitch', 'nav_bearing', 'target_bearing', 'wp_dist', 'alt_error', 'aspd_error', 'xtrack_error']
self.nav_roll = nav_roll
self.nav_pitch = nav_pitch
self.nav_bearing = nav_bearing
self.target_bearing = target_bearing
self.wp_dist = wp_dist
self.alt_error = alt_error
self.aspd_error = aspd_error
self.xtrack_error = xtrack_error
def pack(self, mav):
return MAVLink_message.pack(self, mav, 57, struct.pack('>ffhhHfff', self.nav_roll, self.nav_pitch, self.nav_bearing, self.target_bearing, self.wp_dist, self.alt_error, self.aspd_error, self.xtrack_error))
class MAVLink_position_target_message(MAVLink_message):
'''
The goal position of the system. This position is the input to
any navigation or path planning algorithm and does NOT
represent the current controller setpoint.
'''
def __init__(self, x, y, z, yaw):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_POSITION_TARGET, 'POSITION_TARGET')
self._fieldnames = ['x', 'y', 'z', 'yaw']
self.x = x
self.y = y
self.z = z
self.yaw = yaw
def pack(self, mav):
return MAVLink_message.pack(self, mav, 126, struct.pack('>ffff', self.x, self.y, self.z, self.yaw))
class MAVLink_state_correction_message(MAVLink_message):
'''
Corrects the systems state by adding an error correction term
to the position and velocity, and by rotating the attitude by
a correction angle.
'''
def __init__(self, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_STATE_CORRECTION, 'STATE_CORRECTION')
self._fieldnames = ['xErr', 'yErr', 'zErr', 'rollErr', 'pitchErr', 'yawErr', 'vxErr', 'vyErr', 'vzErr']
self.xErr = xErr
self.yErr = yErr
self.zErr = zErr
self.rollErr = rollErr
self.pitchErr = pitchErr
self.yawErr = yawErr
self.vxErr = vxErr
self.vyErr = vyErr
self.vzErr = vzErr
def pack(self, mav):
return MAVLink_message.pack(self, mav, 130, struct.pack('>fffffffff', self.xErr, self.yErr, self.zErr, self.rollErr, self.pitchErr, self.yawErr, self.vxErr, self.vyErr, self.vzErr))
class MAVLink_set_altitude_message(MAVLink_message):
'''
'''
def __init__(self, target, mode):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_SET_ALTITUDE, 'SET_ALTITUDE')
self._fieldnames = ['target', 'mode']
self.target = target
self.mode = mode
def pack(self, mav):
return MAVLink_message.pack(self, mav, 119, struct.pack('>BI', self.target, self.mode))
class MAVLink_request_data_stream_message(MAVLink_message):
'''
'''
def __init__(self, target_system, target_component, req_stream_id, req_message_rate, start_stop):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, 'REQUEST_DATA_STREAM')
self._fieldnames = ['target_system', 'target_component', 'req_stream_id', 'req_message_rate', 'start_stop']
self.target_system = target_system
self.target_component = target_component
self.req_stream_id = req_stream_id
self.req_message_rate = req_message_rate
self.start_stop = start_stop
def pack(self, mav):
return MAVLink_message.pack(self, mav, 193, struct.pack('>BBBHB', self.target_system, self.target_component, self.req_stream_id, self.req_message_rate, self.start_stop))
class MAVLink_hil_state_message(MAVLink_message):
'''
This packet is useful for high throughput
applications such as hardware in the loop simulations.
'''
def __init__(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_HIL_STATE, 'HIL_STATE')
self._fieldnames = ['usec', 'roll', 'pitch', 'yaw', 'rollspeed', 'pitchspeed', 'yawspeed', 'lat', 'lon', 'alt', 'vx', 'vy', 'vz', 'xacc', 'yacc', 'zacc']
self.usec = usec
self.roll = roll
self.pitch = pitch
self.yaw = yaw
self.rollspeed = rollspeed
self.pitchspeed = pitchspeed
self.yawspeed = yawspeed
self.lat = lat
self.lon = lon
self.alt = alt
self.vx = vx
self.vy = vy
self.vz = vz
self.xacc = xacc
self.yacc = yacc
self.zacc = zacc
def pack(self, mav):
return MAVLink_message.pack(self, mav, 191, struct.pack('>Qffffffiiihhhhhh', self.usec, self.roll, self.pitch, self.yaw, self.rollspeed, self.pitchspeed, self.yawspeed, self.lat, self.lon, self.alt, self.vx, self.vy, self.vz, self.xacc, self.yacc, self.zacc))
class MAVLink_hil_controls_message(MAVLink_message):
'''
Hardware in the loop control outputs
'''
def __init__(self, time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_HIL_CONTROLS, 'HIL_CONTROLS')
self._fieldnames = ['time_us', 'roll_ailerons', 'pitch_elevator', 'yaw_rudder', 'throttle', 'mode', 'nav_mode']
self.time_us = time_us
self.roll_ailerons = roll_ailerons
self.pitch_elevator = pitch_elevator
self.yaw_rudder = yaw_rudder
self.throttle = throttle
self.mode = mode
self.nav_mode = nav_mode
def pack(self, mav):
return MAVLink_message.pack(self, mav, 236, struct.pack('>QffffBB', self.time_us, self.roll_ailerons, self.pitch_elevator, self.yaw_rudder, self.throttle, self.mode, self.nav_mode))
class MAVLink_manual_control_message(MAVLink_message):
'''
'''
def __init__(self, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_MANUAL_CONTROL, 'MANUAL_CONTROL')
self._fieldnames = ['target', 'roll', 'pitch', 'yaw', 'thrust', 'roll_manual', 'pitch_manual', 'yaw_manual', 'thrust_manual']
self.target = target
self.roll = roll
self.pitch = pitch
self.yaw = yaw
self.thrust = thrust
self.roll_manual = roll_manual
self.pitch_manual = pitch_manual
self.yaw_manual = yaw_manual
self.thrust_manual = thrust_manual
def pack(self, mav):
return MAVLink_message.pack(self, mav, 158, struct.pack('>BffffBBBB', self.target, self.roll, self.pitch, self.yaw, self.thrust, self.roll_manual, self.pitch_manual, self.yaw_manual, self.thrust_manual))
class MAVLink_rc_channels_override_message(MAVLink_message):
'''
The RAW values of the RC channels sent to the MAV to override
info received from the RC radio. A value of -1 means no change
to that channel. A value of 0 means control of that channel
should be released back to the RC radio. The standard PPM
modulation is as follows: 1000 microseconds: 0%, 2000
microseconds: 100%. Individual receivers/transmitters might
violate this specification.
'''
def __init__(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, 'RC_CHANNELS_OVERRIDE')
self._fieldnames = ['target_system', 'target_component', 'chan1_raw', 'chan2_raw', 'chan3_raw', 'chan4_raw', 'chan5_raw', 'chan6_raw', 'chan7_raw', 'chan8_raw']
self.target_system = target_system
self.target_component = target_component
self.chan1_raw = chan1_raw
self.chan2_raw = chan2_raw
self.chan3_raw = chan3_raw
self.chan4_raw = chan4_raw
self.chan5_raw = chan5_raw
self.chan6_raw = chan6_raw
self.chan7_raw = chan7_raw
self.chan8_raw = chan8_raw
def pack(self, mav):
return MAVLink_message.pack(self, mav, 143, struct.pack('>BBHHHHHHHH', self.target_system, self.target_component, self.chan1_raw, self.chan2_raw, self.chan3_raw, self.chan4_raw, self.chan5_raw, self.chan6_raw, self.chan7_raw, self.chan8_raw))
class MAVLink_global_position_int_message(MAVLink_message):
'''
The filtered global position (e.g. fused GPS and
accelerometers). The position is in GPS-frame (right-handed,
Z-up)
'''
def __init__(self, lat, lon, alt, vx, vy, vz):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, 'GLOBAL_POSITION_INT')
self._fieldnames = ['lat', 'lon', 'alt', 'vx', 'vy', 'vz']
self.lat = lat
self.lon = lon
self.alt = alt
self.vx = vx
self.vy = vy
self.vz = vz
def pack(self, mav):
return MAVLink_message.pack(self, mav, 104, struct.pack('>iiihhh', self.lat, self.lon, self.alt, self.vx, self.vy, self.vz))
class MAVLink_vfr_hud_message(MAVLink_message):
'''
Metrics typically displayed on a HUD for fixed wing aircraft
'''
def __init__(self, airspeed, groundspeed, heading, throttle, alt, climb):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_VFR_HUD, 'VFR_HUD')
self._fieldnames = ['airspeed', 'groundspeed', 'heading', 'throttle', 'alt', 'climb']
self.airspeed = airspeed
self.groundspeed = groundspeed
self.heading = heading
self.throttle = throttle
self.alt = alt
self.climb = climb
def pack(self, mav):
return MAVLink_message.pack(self, mav, 123, struct.pack('>ffhHff', self.airspeed, self.groundspeed, self.heading, self.throttle, self.alt, self.climb))
class MAVLink_command_message(MAVLink_message):
'''
Send a command with up to four parameters to the MAV
'''
def __init__(self, target_system, target_component, command, confirmation, param1, param2, param3, param4):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_COMMAND, 'COMMAND')
self._fieldnames = ['target_system', 'target_component', 'command', 'confirmation', 'param1', 'param2', 'param3', 'param4']
self.target_system = target_system
self.target_component = target_component
self.command = command
self.confirmation = confirmation
self.param1 = param1
self.param2 = param2
self.param3 = param3
self.param4 = param4
def pack(self, mav):
return MAVLink_message.pack(self, mav, 131, struct.pack('>BBBBffff', self.target_system, self.target_component, self.command, self.confirmation, self.param1, self.param2, self.param3, self.param4))
class MAVLink_command_ack_message(MAVLink_message):
'''
Report status of a command. Includes feedback wether the
command was executed
'''
def __init__(self, command, result):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_COMMAND_ACK, 'COMMAND_ACK')
self._fieldnames = ['command', 'result']
self.command = command
self.result = result
def pack(self, mav):
return MAVLink_message.pack(self, mav, 8, struct.pack('>ff', self.command, self.result))
class MAVLink_optical_flow_message(MAVLink_message):
'''
Optical flow from a flow sensor (e.g. optical mouse sensor)
'''
def __init__(self, time, sensor_id, flow_x, flow_y, quality, ground_distance):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_OPTICAL_FLOW, 'OPTICAL_FLOW')
self._fieldnames = ['time', 'sensor_id', 'flow_x', 'flow_y', 'quality', 'ground_distance']
self.time = time
self.sensor_id = sensor_id
self.flow_x = flow_x
self.flow_y = flow_y
self.quality = quality
self.ground_distance = ground_distance
def pack(self, mav):
return MAVLink_message.pack(self, mav, 174, struct.pack('>QBhhBf', self.time, self.sensor_id, self.flow_x, self.flow_y, self.quality, self.ground_distance))
class MAVLink_object_detection_event_message(MAVLink_message):
'''
Object has been detected
'''
def __init__(self, time, object_id, type, name, quality, bearing, distance):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT, 'OBJECT_DETECTION_EVENT')
self._fieldnames = ['time', 'object_id', 'type', 'name', 'quality', 'bearing', 'distance']
self.time = time
self.object_id = object_id
self.type = type
self.name = name
self.quality = quality
self.bearing = bearing
self.distance = distance
def pack(self, mav):
return MAVLink_message.pack(self, mav, 155, struct.pack('>IHB20sBff', self.time, self.object_id, self.type, self.name, self.quality, self.bearing, self.distance))
class MAVLink_debug_vect_message(MAVLink_message):
'''
'''
def __init__(self, name, usec, x, y, z):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_DEBUG_VECT, 'DEBUG_VECT')
self._fieldnames = ['name', 'usec', 'x', 'y', 'z']
self.name = name
self.usec = usec
self.x = x
self.y = y
self.z = z
def pack(self, mav):
return MAVLink_message.pack(self, mav, 178, struct.pack('>10sQfff', self.name, self.usec, self.x, self.y, self.z))
class MAVLink_named_value_float_message(MAVLink_message):
'''
Send a key-value pair as float. The use of this message is
discouraged for normal packets, but a quite efficient way for
testing new messages and getting experimental debug output.
'''
def __init__(self, name, value):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, 'NAMED_VALUE_FLOAT')
self._fieldnames = ['name', 'value']
self.name = name
self.value = value
def pack(self, mav):
return MAVLink_message.pack(self, mav, 224, struct.pack('>10sf', self.name, self.value))
class MAVLink_named_value_int_message(MAVLink_message):
'''
Send a key-value pair as integer. The use of this message is
discouraged for normal packets, but a quite efficient way for
testing new messages and getting experimental debug output.
'''
def __init__(self, name, value):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_NAMED_VALUE_INT, 'NAMED_VALUE_INT')
self._fieldnames = ['name', 'value']
self.name = name
self.value = value
def pack(self, mav):
return MAVLink_message.pack(self, mav, 60, struct.pack('>10si', self.name, self.value))
class MAVLink_statustext_message(MAVLink_message):
'''
Status text message. These messages are printed in yellow in
the COMM console of QGroundControl. WARNING: They consume
quite some bandwidth, so use only for important status and
error messages. If implemented wisely, these messages are
buffered on the MCU and sent only at a limited rate (e.g. 10
Hz).
'''
def __init__(self, severity, text):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_STATUSTEXT, 'STATUSTEXT')
self._fieldnames = ['severity', 'text']
self.severity = severity
self.text = text
def pack(self, mav):
return MAVLink_message.pack(self, mav, 106, struct.pack('>B50s', self.severity, self.text))
class MAVLink_debug_message(MAVLink_message):
'''
Send a debug value. The index is used to discriminate between
values. These values show up in the plot of QGroundControl as
DEBUG N.
'''
def __init__(self, ind, value):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_DEBUG, 'DEBUG')
self._fieldnames = ['ind', 'value']
self.ind = ind
self.value = value
def pack(self, mav):
return MAVLink_message.pack(self, mav, 7, struct.pack('>Bf', self.ind, self.value))
mavlink_map = {
MAVLINK_MSG_ID_SENSOR_OFFSETS : ( '>hhhfiiffffff', MAVLink_sensor_offsets_message, [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11], 143 ),
MAVLINK_MSG_ID_SET_MAG_OFFSETS : ( '>BBhhh', MAVLink_set_mag_offsets_message, [0, 1, 2, 3, 4], 29 ),
MAVLINK_MSG_ID_MEMINFO : ( '>HH', MAVLink_meminfo_message, [0, 1], 208 ),
MAVLINK_MSG_ID_AP_ADC : ( '>HHHHHH', MAVLink_ap_adc_message, [0, 1, 2, 3, 4, 5], 188 ),
MAVLINK_MSG_ID_DIGICAM_CONFIGURE : ( '>BBBHBBBBBBf', MAVLink_digicam_configure_message, [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10], 118 ),
MAVLINK_MSG_ID_DIGICAM_CONTROL : ( '>BBBBbBBBBf', MAVLink_digicam_control_message, [0, 1, 2, 3, 4, 5, 6, 7, 8, 9], 242 ),
MAVLINK_MSG_ID_MOUNT_CONFIGURE : ( '>BBBBBB', MAVLink_mount_configure_message, [0, 1, 2, 3, 4, 5], 19 ),
MAVLINK_MSG_ID_MOUNT_CONTROL : ( '>BBiiiB', MAVLink_mount_control_message, [0, 1, 2, 3, 4, 5], 97 ),
MAVLINK_MSG_ID_MOUNT_STATUS : ( '>BBiii', MAVLink_mount_status_message, [0, 1, 2, 3, 4], 233 ),
MAVLINK_MSG_ID_FENCE_POINT : ( '>BBBBff', MAVLink_fence_point_message, [0, 1, 2, 3, 4, 5], 18 ),
MAVLINK_MSG_ID_FENCE_FETCH_POINT : ( '>BBB', MAVLink_fence_fetch_point_message, [0, 1, 2], 68 ),
MAVLINK_MSG_ID_FENCE_STATUS : ( '>BHBI', MAVLink_fence_status_message, [0, 1, 2, 3], 136 ),
MAVLINK_MSG_ID_AHRS : ( '>fffffff', MAVLink_ahrs_message, [0, 1, 2, 3, 4, 5, 6], 127 ),
MAVLINK_MSG_ID_SIMSTATE : ( '>fffffffff', MAVLink_simstate_message, [0, 1, 2, 3, 4, 5, 6, 7, 8], 42 ),
MAVLINK_MSG_ID_HWSTATUS : ( '>HB', MAVLink_hwstatus_message, [0, 1], 21 ),
MAVLINK_MSG_ID_RADIO : ( '>BBBBBHH', MAVLink_radio_message, [0, 1, 2, 3, 4, 5, 6], 93 ),
MAVLINK_MSG_ID_HEARTBEAT : ( '>BBB', MAVLink_heartbeat_message, [0, 1, 2], 72 ),
MAVLINK_MSG_ID_BOOT : ( '>I', MAVLink_boot_message, [0], 39 ),
MAVLINK_MSG_ID_SYSTEM_TIME : ( '>Q', MAVLink_system_time_message, [0], 190 ),
MAVLINK_MSG_ID_PING : ( '>IBBQ', MAVLink_ping_message, [0, 1, 2, 3], 92 ),
MAVLINK_MSG_ID_SYSTEM_TIME_UTC : ( '>II', MAVLink_system_time_utc_message, [0, 1], 191 ),
MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL : ( '>BBB25s', MAVLink_change_operator_control_message, [0, 1, 2, 3], 217 ),
MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK : ( '>BBB', MAVLink_change_operator_control_ack_message, [0, 1, 2], 104 ),
MAVLINK_MSG_ID_AUTH_KEY : ( '>32s', MAVLink_auth_key_message, [0], 119 ),
MAVLINK_MSG_ID_ACTION_ACK : ( '>BB', MAVLink_action_ack_message, [0, 1], 219 ),
MAVLINK_MSG_ID_ACTION : ( '>BBB', MAVLink_action_message, [0, 1, 2], 60 ),
MAVLINK_MSG_ID_SET_MODE : ( '>BB', MAVLink_set_mode_message, [0, 1], 186 ),
MAVLINK_MSG_ID_SET_NAV_MODE : ( '>BB', MAVLink_set_nav_mode_message, [0, 1], 10 ),
MAVLINK_MSG_ID_PARAM_REQUEST_READ : ( '>BB15sh', MAVLink_param_request_read_message, [0, 1, 2, 3], 89 ),
MAVLINK_MSG_ID_PARAM_REQUEST_LIST : ( '>BB', MAVLink_param_request_list_message, [0, 1], 159 ),
MAVLINK_MSG_ID_PARAM_VALUE : ( '>15sfHH', MAVLink_param_value_message, [0, 1, 2, 3], 162 ),
MAVLINK_MSG_ID_PARAM_SET : ( '>BB15sf', MAVLink_param_set_message, [0, 1, 2, 3], 121 ),
MAVLINK_MSG_ID_GPS_RAW_INT : ( '>QBiiiffff', MAVLink_gps_raw_int_message, [0, 1, 2, 3, 4, 5, 6, 7, 8], 149 ),
MAVLINK_MSG_ID_SCALED_IMU : ( '>Qhhhhhhhhh', MAVLink_scaled_imu_message, [0, 1, 2, 3, 4, 5, 6, 7, 8, 9], 222 ),
MAVLINK_MSG_ID_GPS_STATUS : ( '>B20s20s20s20s20s', MAVLink_gps_status_message, [0, 1, 2, 3, 4, 5], 110 ),
MAVLINK_MSG_ID_RAW_IMU : ( '>Qhhhhhhhhh', MAVLink_raw_imu_message, [0, 1, 2, 3, 4, 5, 6, 7, 8, 9], 179 ),
MAVLINK_MSG_ID_RAW_PRESSURE : ( '>Qhhhh', MAVLink_raw_pressure_message, [0, 1, 2, 3, 4], 136 ),
MAVLINK_MSG_ID_SCALED_PRESSURE : ( '>Qffh', MAVLink_scaled_pressure_message, [0, 1, 2, 3], 229 ),
MAVLINK_MSG_ID_ATTITUDE : ( '>Qffffff', MAVLink_attitude_message, [0, 1, 2, 3, 4, 5, 6], 66 ),
MAVLINK_MSG_ID_LOCAL_POSITION : ( '>Qffffff', MAVLink_local_position_message, [0, 1, 2, 3, 4, 5, 6], 126 ),
MAVLINK_MSG_ID_GLOBAL_POSITION : ( '>Qffffff', MAVLink_global_position_message, [0, 1, 2, 3, 4, 5, 6], 147 ),
MAVLINK_MSG_ID_GPS_RAW : ( '>QBfffffff', MAVLink_gps_raw_message, [0, 1, 2, 3, 4, 5, 6, 7, 8], 185 ),
MAVLINK_MSG_ID_SYS_STATUS : ( '>BBBHHHH', MAVLink_sys_status_message, [0, 1, 2, 3, 4, 5, 6], 112 ),
MAVLINK_MSG_ID_RC_CHANNELS_RAW : ( '>HHHHHHHHB', MAVLink_rc_channels_raw_message, [0, 1, 2, 3, 4, 5, 6, 7, 8], 252 ),
MAVLINK_MSG_ID_RC_CHANNELS_SCALED : ( '>hhhhhhhhB', MAVLink_rc_channels_scaled_message, [0, 1, 2, 3, 4, 5, 6, 7, 8], 162 ),
MAVLINK_MSG_ID_SERVO_OUTPUT_RAW : ( '>HHHHHHHH', MAVLink_servo_output_raw_message, [0, 1, 2, 3, 4, 5, 6, 7], 215 ),
MAVLINK_MSG_ID_WAYPOINT : ( '>BBHBBBBfffffff', MAVLink_waypoint_message, [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13], 128 ),
MAVLINK_MSG_ID_WAYPOINT_REQUEST : ( '>BBH', MAVLink_waypoint_request_message, [0, 1, 2], 9 ),
MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT : ( '>BBH', MAVLink_waypoint_set_current_message, [0, 1, 2], 106 ),
MAVLINK_MSG_ID_WAYPOINT_CURRENT : ( '>H', MAVLink_waypoint_current_message, [0], 101 ),
MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST : ( '>BB', MAVLink_waypoint_request_list_message, [0, 1], 213 ),
MAVLINK_MSG_ID_WAYPOINT_COUNT : ( '>BBH', MAVLink_waypoint_count_message, [0, 1, 2], 4 ),
MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL : ( '>BB', MAVLink_waypoint_clear_all_message, [0, 1], 229 ),
MAVLINK_MSG_ID_WAYPOINT_REACHED : ( '>H', MAVLink_waypoint_reached_message, [0], 21 ),
MAVLINK_MSG_ID_WAYPOINT_ACK : ( '>BBB', MAVLink_waypoint_ack_message, [0, 1, 2], 214 ),
MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN : ( '>BBiii', MAVLink_gps_set_global_origin_message, [0, 1, 2, 3, 4], 215 ),
MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET : ( '>iii', MAVLink_gps_local_origin_set_message, [0, 1, 2], 14 ),
MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET : ( '>BBffff', MAVLink_local_position_setpoint_set_message, [0, 1, 2, 3, 4, 5], 206 ),
MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT : ( '>ffff', MAVLink_local_position_setpoint_message, [0, 1, 2, 3], 50 ),
MAVLINK_MSG_ID_CONTROL_STATUS : ( '>BBBBBBBB', MAVLink_control_status_message, [0, 1, 2, 3, 4, 5, 6, 7], 157 ),
MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA : ( '>BBBffffff', MAVLink_safety_set_allowed_area_message, [0, 1, 2, 3, 4, 5, 6, 7, 8], 126 ),
MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA : ( '>Bffffff', MAVLink_safety_allowed_area_message, [0, 1, 2, 3, 4, 5, 6], 108 ),
MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST : ( '>BBffff', MAVLink_set_roll_pitch_yaw_thrust_message, [0, 1, 2, 3, 4, 5], 213 ),
MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST : ( '>BBffff', MAVLink_set_roll_pitch_yaw_speed_thrust_message, [0, 1, 2, 3, 4, 5], 95 ),
MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT : ( '>Qffff', MAVLink_roll_pitch_yaw_thrust_setpoint_message, [0, 1, 2, 3, 4], 5 ),
MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT : ( '>Qffff', MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message, [0, 1, 2, 3, 4], 127 ),
MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT : ( '>ffhhHfff', MAVLink_nav_controller_output_message, [0, 1, 2, 3, 4, 5, 6, 7], 57 ),
MAVLINK_MSG_ID_POSITION_TARGET : ( '>ffff', MAVLink_position_target_message, [0, 1, 2, 3], 126 ),
MAVLINK_MSG_ID_STATE_CORRECTION : ( '>fffffffff', MAVLink_state_correction_message, [0, 1, 2, 3, 4, 5, 6, 7, 8], 130 ),
MAVLINK_MSG_ID_SET_ALTITUDE : ( '>BI', MAVLink_set_altitude_message, [0, 1], 119 ),
MAVLINK_MSG_ID_REQUEST_DATA_STREAM : ( '>BBBHB', MAVLink_request_data_stream_message, [0, 1, 2, 3, 4], 193 ),
MAVLINK_MSG_ID_HIL_STATE : ( '>Qffffffiiihhhhhh', MAVLink_hil_state_message, [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15], 191 ),
MAVLINK_MSG_ID_HIL_CONTROLS : ( '>QffffBB', MAVLink_hil_controls_message, [0, 1, 2, 3, 4, 5, 6], 236 ),
MAVLINK_MSG_ID_MANUAL_CONTROL : ( '>BffffBBBB', MAVLink_manual_control_message, [0, 1, 2, 3, 4, 5, 6, 7, 8], 158 ),
MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE : ( '>BBHHHHHHHH', MAVLink_rc_channels_override_message, [0, 1, 2, 3, 4, 5, 6, 7, 8, 9], 143 ),
MAVLINK_MSG_ID_GLOBAL_POSITION_INT : ( '>iiihhh', MAVLink_global_position_int_message, [0, 1, 2, 3, 4, 5], 104 ),
MAVLINK_MSG_ID_VFR_HUD : ( '>ffhHff', MAVLink_vfr_hud_message, [0, 1, 2, 3, 4, 5], 123 ),
MAVLINK_MSG_ID_COMMAND : ( '>BBBBffff', MAVLink_command_message, [0, 1, 2, 3, 4, 5, 6, 7], 131 ),
MAVLINK_MSG_ID_COMMAND_ACK : ( '>ff', MAVLink_command_ack_message, [0, 1], 8 ),
MAVLINK_MSG_ID_OPTICAL_FLOW : ( '>QBhhBf', MAVLink_optical_flow_message, [0, 1, 2, 3, 4, 5], 174 ),
MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT : ( '>IHB20sBff', MAVLink_object_detection_event_message, [0, 1, 2, 3, 4, 5, 6], 155 ),
MAVLINK_MSG_ID_DEBUG_VECT : ( '>10sQfff', MAVLink_debug_vect_message, [0, 1, 2, 3, 4], 178 ),
MAVLINK_MSG_ID_NAMED_VALUE_FLOAT : ( '>10sf', MAVLink_named_value_float_message, [0, 1], 224 ),
MAVLINK_MSG_ID_NAMED_VALUE_INT : ( '>10si', MAVLink_named_value_int_message, [0, 1], 60 ),
MAVLINK_MSG_ID_STATUSTEXT : ( '>B50s', MAVLink_statustext_message, [0, 1], 106 ),
MAVLINK_MSG_ID_DEBUG : ( '>Bf', MAVLink_debug_message, [0, 1], 7 ),
}
class MAVError(Exception):
'''MAVLink error class'''
def __init__(self, msg):
Exception.__init__(self, msg)
self.message = msg
class MAVString(str):
'''NUL terminated string'''
def __init__(self, s):
str.__init__(self)
def __str__(self):
i = self.find(chr(0))
if i == -1:
return self[:]
return self[0:i]
class MAVLink_bad_data(MAVLink_message):
'''
a piece of bad data in a mavlink stream
'''
def __init__(self, data, reason):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_BAD_DATA, 'BAD_DATA')
self._fieldnames = ['data', 'reason']
self.data = data
self.reason = reason
self._msgbuf = data
class MAVLink(object):
'''MAVLink protocol handling class'''
def __init__(self, file, srcSystem=0, srcComponent=0):
self.seq = 0
self.file = file
self.srcSystem = srcSystem
self.srcComponent = srcComponent
self.callback = None
self.callback_args = None
self.callback_kwargs = None
self.buf = array.array('B')
self.expected_length = 6
self.have_prefix_error = False
self.robust_parsing = False
self.protocol_marker = 85
self.little_endian = False
self.crc_extra = False
self.sort_fields = False
self.total_packets_sent = 0
self.total_bytes_sent = 0
self.total_packets_received = 0
self.total_bytes_received = 0
self.total_receive_errors = 0
self.startup_time = time.time()
def set_callback(self, callback, *args, **kwargs):
self.callback = callback
self.callback_args = args
self.callback_kwargs = kwargs
def send(self, mavmsg):
'''send a MAVLink message'''
buf = mavmsg.pack(self)
self.file.write(buf)
self.seq = (self.seq + 1) % 255
self.total_packets_sent += 1
self.total_bytes_sent += len(buf)
def bytes_needed(self):
'''return number of bytes needed for next parsing stage'''
ret = self.expected_length - len(self.buf)
if ret <= 0:
return 1
return ret
def parse_char(self, c):
'''input some data bytes, possibly returning a new message'''
if isinstance(c, str):
self.buf.fromstring(c)
else:
self.buf.extend(c)
self.total_bytes_received += len(c)
if len(self.buf) >= 1 and self.buf[0] != 85:
magic = self.buf[0]
self.buf = self.buf[1:]
if self.robust_parsing:
m = MAVLink_bad_data(chr(magic), "Bad prefix")
if self.callback:
self.callback(m, *self.callback_args, **self.callback_kwargs)
self.expected_length = 6
self.total_receive_errors += 1
return m
if self.have_prefix_error:
return None
self.have_prefix_error = True
self.total_receive_errors += 1
raise MAVError("invalid MAVLink prefix '%s'" % magic)
self.have_prefix_error = False
if len(self.buf) >= 2:
(magic, self.expected_length) = struct.unpack('BB', self.buf[0:2])
self.expected_length += 8
if self.expected_length >= 8 and len(self.buf) >= self.expected_length:
mbuf = self.buf[0:self.expected_length]
self.buf = self.buf[self.expected_length:]
self.expected_length = 6
if self.robust_parsing:
try:
m = self.decode(mbuf)
self.total_packets_received += 1
except MAVError as reason:
m = MAVLink_bad_data(mbuf, reason.message)
self.total_receive_errors += 1
else:
m = self.decode(mbuf)
self.total_packets_received += 1
if self.callback:
self.callback(m, *self.callback_args, **self.callback_kwargs)
return m
return None
def parse_buffer(self, s):
'''input some data bytes, possibly returning a list of new messages'''
m = self.parse_char(s)
if m is None:
return None
ret = [m]
while True:
m = self.parse_char("")
if m is None:
return ret
ret.append(m)
return ret
def decode(self, msgbuf):
'''decode a buffer as a MAVLink message'''
# decode the header
try:
magic, mlen, seq, srcSystem, srcComponent, msgId = struct.unpack('cBBBBB', msgbuf[:6])
except struct.error as emsg:
raise MAVError('Unable to unpack MAVLink header: %s' % emsg)
if ord(magic) != 85:
raise MAVError("invalid MAVLink prefix '%s'" % magic)
if mlen != len(msgbuf)-8:
raise MAVError('invalid MAVLink message length. Got %u expected %u, msgId=%u' % (len(msgbuf)-8, mlen, msgId))
if not msgId in mavlink_map:
raise MAVError('unknown MAVLink message ID %u' % msgId)
# decode the payload
(fmt, type, order_map, crc_extra) = mavlink_map[msgId]
# decode the checksum
try:
crc, = struct.unpack('<H', msgbuf[-2:])
except struct.error as emsg:
raise MAVError('Unable to unpack MAVLink CRC: %s' % emsg)
crc2 = mavutil.x25crc(msgbuf[1:-2])
if False: # using CRC extra
crc2.accumulate(chr(crc_extra))
if crc != crc2.crc:
raise MAVError('invalid MAVLink CRC in msgID %u 0x%04x should be 0x%04x' % (msgId, crc, crc2.crc))
try:
t = struct.unpack(fmt, msgbuf[6:-2])
except struct.error as emsg:
raise MAVError('Unable to unpack MAVLink payload type=%s fmt=%s payloadLength=%u: %s' % (
type, fmt, len(msgbuf[6:-2]), emsg))
tlist = list(t)
# handle sorted fields
if False:
t = tlist[:]
for i in range(0, len(tlist)):
tlist[i] = t[order_map[i]]
# terminate any strings
for i in range(0, len(tlist)):
if isinstance(tlist[i], str):
tlist[i] = MAVString(tlist[i])
t = tuple(tlist)
# construct the message object
try:
m = type(*t)
except Exception as emsg:
raise MAVError('Unable to instantiate MAVLink message of type %s : %s' % (type, emsg))
m._msgbuf = msgbuf
m._payload = msgbuf[6:-2]
m._crc = crc
m._header = MAVLink_header(msgId, mlen, seq, srcSystem, srcComponent)
return m
def sensor_offsets_encode(self, mag_ofs_x, mag_ofs_y, mag_ofs_z, mag_declination, raw_press, raw_temp, gyro_cal_x, gyro_cal_y, gyro_cal_z, accel_cal_x, accel_cal_y, accel_cal_z):
'''
Offsets and calibrations values for hardware sensors. This
makes it easier to debug the calibration process.
mag_ofs_x : magnetometer X offset (int16_t)
mag_ofs_y : magnetometer Y offset (int16_t)
mag_ofs_z : magnetometer Z offset (int16_t)
mag_declination : magnetic declination (radians) (float)
raw_press : raw pressure from barometer (int32_t)
raw_temp : raw temperature from barometer (int32_t)
gyro_cal_x : gyro X calibration (float)
gyro_cal_y : gyro Y calibration (float)
gyro_cal_z : gyro Z calibration (float)
accel_cal_x : accel X calibration (float)
accel_cal_y : accel Y calibration (float)
accel_cal_z : accel Z calibration (float)
'''
msg = MAVLink_sensor_offsets_message(mag_ofs_x, mag_ofs_y, mag_ofs_z, mag_declination, raw_press, raw_temp, gyro_cal_x, gyro_cal_y, gyro_cal_z, accel_cal_x, accel_cal_y, accel_cal_z)
msg.pack(self)
return msg
def sensor_offsets_send(self, mag_ofs_x, mag_ofs_y, mag_ofs_z, mag_declination, raw_press, raw_temp, gyro_cal_x, gyro_cal_y, gyro_cal_z, accel_cal_x, accel_cal_y, accel_cal_z):
'''
Offsets and calibrations values for hardware sensors. This
makes it easier to debug the calibration process.
mag_ofs_x : magnetometer X offset (int16_t)
mag_ofs_y : magnetometer Y offset (int16_t)
mag_ofs_z : magnetometer Z offset (int16_t)
mag_declination : magnetic declination (radians) (float)
raw_press : raw pressure from barometer (int32_t)
raw_temp : raw temperature from barometer (int32_t)
gyro_cal_x : gyro X calibration (float)
gyro_cal_y : gyro Y calibration (float)
gyro_cal_z : gyro Z calibration (float)
accel_cal_x : accel X calibration (float)
accel_cal_y : accel Y calibration (float)
accel_cal_z : accel Z calibration (float)
'''
return self.send(self.sensor_offsets_encode(mag_ofs_x, mag_ofs_y, mag_ofs_z, mag_declination, raw_press, raw_temp, gyro_cal_x, gyro_cal_y, gyro_cal_z, accel_cal_x, accel_cal_y, accel_cal_z))
def set_mag_offsets_encode(self, target_system, target_component, mag_ofs_x, mag_ofs_y, mag_ofs_z):
'''
set the magnetometer offsets
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
mag_ofs_x : magnetometer X offset (int16_t)
mag_ofs_y : magnetometer Y offset (int16_t)
mag_ofs_z : magnetometer Z offset (int16_t)
'''
msg = MAVLink_set_mag_offsets_message(target_system, target_component, mag_ofs_x, mag_ofs_y, mag_ofs_z)
msg.pack(self)
return msg
def set_mag_offsets_send(self, target_system, target_component, mag_ofs_x, mag_ofs_y, mag_ofs_z):
'''
set the magnetometer offsets
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
mag_ofs_x : magnetometer X offset (int16_t)
mag_ofs_y : magnetometer Y offset (int16_t)
mag_ofs_z : magnetometer Z offset (int16_t)
'''
return self.send(self.set_mag_offsets_encode(target_system, target_component, mag_ofs_x, mag_ofs_y, mag_ofs_z))
def meminfo_encode(self, brkval, freemem):
'''
state of APM memory
brkval : heap top (uint16_t)
freemem : free memory (uint16_t)
'''
msg = MAVLink_meminfo_message(brkval, freemem)
msg.pack(self)
return msg
def meminfo_send(self, brkval, freemem):
'''
state of APM memory
brkval : heap top (uint16_t)
freemem : free memory (uint16_t)
'''
return self.send(self.meminfo_encode(brkval, freemem))
def ap_adc_encode(self, adc1, adc2, adc3, adc4, adc5, adc6):
'''
raw ADC output
adc1 : ADC output 1 (uint16_t)
adc2 : ADC output 2 (uint16_t)
adc3 : ADC output 3 (uint16_t)
adc4 : ADC output 4 (uint16_t)
adc5 : ADC output 5 (uint16_t)
adc6 : ADC output 6 (uint16_t)
'''
msg = MAVLink_ap_adc_message(adc1, adc2, adc3, adc4, adc5, adc6)
msg.pack(self)
return msg
def ap_adc_send(self, adc1, adc2, adc3, adc4, adc5, adc6):
'''
raw ADC output
adc1 : ADC output 1 (uint16_t)
adc2 : ADC output 2 (uint16_t)
adc3 : ADC output 3 (uint16_t)
adc4 : ADC output 4 (uint16_t)
adc5 : ADC output 5 (uint16_t)
adc6 : ADC output 6 (uint16_t)
'''
return self.send(self.ap_adc_encode(adc1, adc2, adc3, adc4, adc5, adc6))
def digicam_configure_encode(self, target_system, target_component, mode, shutter_speed, aperture, iso, exposure_type, command_id, engine_cut_off, extra_param, extra_value):
'''
Configure on-board Camera Control System.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
mode : Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore) (uint8_t)
shutter_speed : Divisor number //e.g. 1000 means 1/1000 (0 means ignore) (uint16_t)
aperture : F stop number x 10 //e.g. 28 means 2.8 (0 means ignore) (uint8_t)
iso : ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore) (uint8_t)
exposure_type : Exposure type enumeration from 1 to N (0 means ignore) (uint8_t)
command_id : Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once (uint8_t)
engine_cut_off : Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off) (uint8_t)
extra_param : Extra parameters enumeration (0 means ignore) (uint8_t)
extra_value : Correspondent value to given extra_param (float)
'''
msg = MAVLink_digicam_configure_message(target_system, target_component, mode, shutter_speed, aperture, iso, exposure_type, command_id, engine_cut_off, extra_param, extra_value)
msg.pack(self)
return msg
def digicam_configure_send(self, target_system, target_component, mode, shutter_speed, aperture, iso, exposure_type, command_id, engine_cut_off, extra_param, extra_value):
'''
Configure on-board Camera Control System.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
mode : Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore) (uint8_t)
shutter_speed : Divisor number //e.g. 1000 means 1/1000 (0 means ignore) (uint16_t)
aperture : F stop number x 10 //e.g. 28 means 2.8 (0 means ignore) (uint8_t)
iso : ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore) (uint8_t)
exposure_type : Exposure type enumeration from 1 to N (0 means ignore) (uint8_t)
command_id : Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once (uint8_t)
engine_cut_off : Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off) (uint8_t)
extra_param : Extra parameters enumeration (0 means ignore) (uint8_t)
extra_value : Correspondent value to given extra_param (float)
'''
return self.send(self.digicam_configure_encode(target_system, target_component, mode, shutter_speed, aperture, iso, exposure_type, command_id, engine_cut_off, extra_param, extra_value))
def digicam_control_encode(self, target_system, target_component, session, zoom_pos, zoom_step, focus_lock, shot, command_id, extra_param, extra_value):
'''
Control on-board Camera Control System to take shots.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
session : 0: stop, 1: start or keep it up //Session control e.g. show/hide lens (uint8_t)
zoom_pos : 1 to N //Zoom's absolute position (0 means ignore) (uint8_t)
zoom_step : -100 to 100 //Zooming step value to offset zoom from the current position (int8_t)
focus_lock : 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus (uint8_t)
shot : 0: ignore, 1: shot or start filming (uint8_t)
command_id : Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once (uint8_t)
extra_param : Extra parameters enumeration (0 means ignore) (uint8_t)
extra_value : Correspondent value to given extra_param (float)
'''
msg = MAVLink_digicam_control_message(target_system, target_component, session, zoom_pos, zoom_step, focus_lock, shot, command_id, extra_param, extra_value)
msg.pack(self)
return msg
def digicam_control_send(self, target_system, target_component, session, zoom_pos, zoom_step, focus_lock, shot, command_id, extra_param, extra_value):
'''
Control on-board Camera Control System to take shots.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
session : 0: stop, 1: start or keep it up //Session control e.g. show/hide lens (uint8_t)
zoom_pos : 1 to N //Zoom's absolute position (0 means ignore) (uint8_t)
zoom_step : -100 to 100 //Zooming step value to offset zoom from the current position (int8_t)
focus_lock : 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus (uint8_t)
shot : 0: ignore, 1: shot or start filming (uint8_t)
command_id : Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once (uint8_t)
extra_param : Extra parameters enumeration (0 means ignore) (uint8_t)
extra_value : Correspondent value to given extra_param (float)
'''
return self.send(self.digicam_control_encode(target_system, target_component, session, zoom_pos, zoom_step, focus_lock, shot, command_id, extra_param, extra_value))
def mount_configure_encode(self, target_system, target_component, mount_mode, stab_roll, stab_pitch, stab_yaw):
'''
Message to configure a camera mount, directional antenna, etc.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
mount_mode : mount operating mode (see MAV_MOUNT_MODE enum) (uint8_t)
stab_roll : (1 = yes, 0 = no) (uint8_t)
stab_pitch : (1 = yes, 0 = no) (uint8_t)
stab_yaw : (1 = yes, 0 = no) (uint8_t)
'''
msg = MAVLink_mount_configure_message(target_system, target_component, mount_mode, stab_roll, stab_pitch, stab_yaw)
msg.pack(self)
return msg
def mount_configure_send(self, target_system, target_component, mount_mode, stab_roll, stab_pitch, stab_yaw):
'''
Message to configure a camera mount, directional antenna, etc.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
mount_mode : mount operating mode (see MAV_MOUNT_MODE enum) (uint8_t)
stab_roll : (1 = yes, 0 = no) (uint8_t)
stab_pitch : (1 = yes, 0 = no) (uint8_t)
stab_yaw : (1 = yes, 0 = no) (uint8_t)
'''
return self.send(self.mount_configure_encode(target_system, target_component, mount_mode, stab_roll, stab_pitch, stab_yaw))
def mount_control_encode(self, target_system, target_component, input_a, input_b, input_c, save_position):
'''
Message to control a camera mount, directional antenna, etc.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
input_a : pitch(deg*100) or lat, depending on mount mode (int32_t)
input_b : roll(deg*100) or lon depending on mount mode (int32_t)
input_c : yaw(deg*100) or alt (in cm) depending on mount mode (int32_t)
save_position : if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING) (uint8_t)
'''
msg = MAVLink_mount_control_message(target_system, target_component, input_a, input_b, input_c, save_position)
msg.pack(self)
return msg
def mount_control_send(self, target_system, target_component, input_a, input_b, input_c, save_position):
'''
Message to control a camera mount, directional antenna, etc.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
input_a : pitch(deg*100) or lat, depending on mount mode (int32_t)
input_b : roll(deg*100) or lon depending on mount mode (int32_t)
input_c : yaw(deg*100) or alt (in cm) depending on mount mode (int32_t)
save_position : if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING) (uint8_t)
'''
return self.send(self.mount_control_encode(target_system, target_component, input_a, input_b, input_c, save_position))
def mount_status_encode(self, target_system, target_component, pointing_a, pointing_b, pointing_c):
'''
Message with some status from APM to GCS about camera or antenna mount
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
pointing_a : pitch(deg*100) or lat, depending on mount mode (int32_t)
pointing_b : roll(deg*100) or lon depending on mount mode (int32_t)
pointing_c : yaw(deg*100) or alt (in cm) depending on mount mode (int32_t)
'''
msg = MAVLink_mount_status_message(target_system, target_component, pointing_a, pointing_b, pointing_c)
msg.pack(self)
return msg
def mount_status_send(self, target_system, target_component, pointing_a, pointing_b, pointing_c):
'''
Message with some status from APM to GCS about camera or antenna mount
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
pointing_a : pitch(deg*100) or lat, depending on mount mode (int32_t)
pointing_b : roll(deg*100) or lon depending on mount mode (int32_t)
pointing_c : yaw(deg*100) or alt (in cm) depending on mount mode (int32_t)
'''
return self.send(self.mount_status_encode(target_system, target_component, pointing_a, pointing_b, pointing_c))
def fence_point_encode(self, target_system, target_component, idx, count, lat, lng):
'''
A fence point. Used to set a point when from GCS -> MAV.
Also used to return a point from MAV -> GCS
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
idx : point index (first point is 1, 0 is for return point) (uint8_t)
count : total number of points (for sanity checking) (uint8_t)
lat : Latitude of point (float)
lng : Longitude of point (float)
'''
msg = MAVLink_fence_point_message(target_system, target_component, idx, count, lat, lng)
msg.pack(self)
return msg
def fence_point_send(self, target_system, target_component, idx, count, lat, lng):
'''
A fence point. Used to set a point when from GCS -> MAV.
Also used to return a point from MAV -> GCS
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
idx : point index (first point is 1, 0 is for return point) (uint8_t)
count : total number of points (for sanity checking) (uint8_t)
lat : Latitude of point (float)
lng : Longitude of point (float)
'''
return self.send(self.fence_point_encode(target_system, target_component, idx, count, lat, lng))
def fence_fetch_point_encode(self, target_system, target_component, idx):
'''
Request a current fence point from MAV
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
idx : point index (first point is 1, 0 is for return point) (uint8_t)
'''
msg = MAVLink_fence_fetch_point_message(target_system, target_component, idx)
msg.pack(self)
return msg
def fence_fetch_point_send(self, target_system, target_component, idx):
'''
Request a current fence point from MAV
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
idx : point index (first point is 1, 0 is for return point) (uint8_t)
'''
return self.send(self.fence_fetch_point_encode(target_system, target_component, idx))
def fence_status_encode(self, breach_status, breach_count, breach_type, breach_time):
'''
Status of geo-fencing. Sent in extended status stream when
fencing enabled
breach_status : 0 if currently inside fence, 1 if outside (uint8_t)
breach_count : number of fence breaches (uint16_t)
breach_type : last breach type (see FENCE_BREACH_* enum) (uint8_t)
breach_time : time of last breach in milliseconds since boot (uint32_t)
'''
msg = MAVLink_fence_status_message(breach_status, breach_count, breach_type, breach_time)
msg.pack(self)
return msg
def fence_status_send(self, breach_status, breach_count, breach_type, breach_time):
'''
Status of geo-fencing. Sent in extended status stream when
fencing enabled
breach_status : 0 if currently inside fence, 1 if outside (uint8_t)
breach_count : number of fence breaches (uint16_t)
breach_type : last breach type (see FENCE_BREACH_* enum) (uint8_t)
breach_time : time of last breach in milliseconds since boot (uint32_t)
'''
return self.send(self.fence_status_encode(breach_status, breach_count, breach_type, breach_time))
def ahrs_encode(self, omegaIx, omegaIy, omegaIz, accel_weight, renorm_val, error_rp, error_yaw):
'''
Status of DCM attitude estimator
omegaIx : X gyro drift estimate rad/s (float)
omegaIy : Y gyro drift estimate rad/s (float)
omegaIz : Z gyro drift estimate rad/s (float)
accel_weight : average accel_weight (float)
renorm_val : average renormalisation value (float)
error_rp : average error_roll_pitch value (float)
error_yaw : average error_yaw value (float)
'''
msg = MAVLink_ahrs_message(omegaIx, omegaIy, omegaIz, accel_weight, renorm_val, error_rp, error_yaw)
msg.pack(self)
return msg
def ahrs_send(self, omegaIx, omegaIy, omegaIz, accel_weight, renorm_val, error_rp, error_yaw):
'''
Status of DCM attitude estimator
omegaIx : X gyro drift estimate rad/s (float)
omegaIy : Y gyro drift estimate rad/s (float)
omegaIz : Z gyro drift estimate rad/s (float)
accel_weight : average accel_weight (float)
renorm_val : average renormalisation value (float)
error_rp : average error_roll_pitch value (float)
error_yaw : average error_yaw value (float)
'''
return self.send(self.ahrs_encode(omegaIx, omegaIy, omegaIz, accel_weight, renorm_val, error_rp, error_yaw))
def simstate_encode(self, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro):
'''
Status of simulation environment, if used
roll : Roll angle (rad) (float)
pitch : Pitch angle (rad) (float)
yaw : Yaw angle (rad) (float)
xacc : X acceleration m/s/s (float)
yacc : Y acceleration m/s/s (float)
zacc : Z acceleration m/s/s (float)
xgyro : Angular speed around X axis rad/s (float)
ygyro : Angular speed around Y axis rad/s (float)
zgyro : Angular speed around Z axis rad/s (float)
'''
msg = MAVLink_simstate_message(roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro)
msg.pack(self)
return msg
def simstate_send(self, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro):
'''
Status of simulation environment, if used
roll : Roll angle (rad) (float)
pitch : Pitch angle (rad) (float)
yaw : Yaw angle (rad) (float)
xacc : X acceleration m/s/s (float)
yacc : Y acceleration m/s/s (float)
zacc : Z acceleration m/s/s (float)
xgyro : Angular speed around X axis rad/s (float)
ygyro : Angular speed around Y axis rad/s (float)
zgyro : Angular speed around Z axis rad/s (float)
'''
return self.send(self.simstate_encode(roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro))
def hwstatus_encode(self, Vcc, I2Cerr):
'''
Status of key hardware
Vcc : board voltage (mV) (uint16_t)
I2Cerr : I2C error count (uint8_t)
'''
msg = MAVLink_hwstatus_message(Vcc, I2Cerr)
msg.pack(self)
return msg
def hwstatus_send(self, Vcc, I2Cerr):
'''
Status of key hardware
Vcc : board voltage (mV) (uint16_t)
I2Cerr : I2C error count (uint8_t)
'''
return self.send(self.hwstatus_encode(Vcc, I2Cerr))
def radio_encode(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed):
'''
Status generated by radio
rssi : local signal strength (uint8_t)
remrssi : remote signal strength (uint8_t)
txbuf : how full the tx buffer is as a percentage (uint8_t)
noise : background noise level (uint8_t)
remnoise : remote background noise level (uint8_t)
rxerrors : receive errors (uint16_t)
fixed : count of error corrected packets (uint16_t)
'''
msg = MAVLink_radio_message(rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed)
msg.pack(self)
return msg
def radio_send(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed):
'''
Status generated by radio
rssi : local signal strength (uint8_t)
remrssi : remote signal strength (uint8_t)
txbuf : how full the tx buffer is as a percentage (uint8_t)
noise : background noise level (uint8_t)
remnoise : remote background noise level (uint8_t)
rxerrors : receive errors (uint16_t)
fixed : count of error corrected packets (uint16_t)
'''
return self.send(self.radio_encode(rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed))
def heartbeat_encode(self, type, autopilot, mavlink_version=2):
'''
The heartbeat message shows that a system is present and responding.
The type of the MAV and Autopilot hardware allow the
receiving system to treat further messages from this
system appropriate (e.g. by laying out the user
interface based on the autopilot).
type : Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) (uint8_t)
autopilot : Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM (uint8_t)
mavlink_version : MAVLink version (uint8_t)
'''
msg = MAVLink_heartbeat_message(type, autopilot, mavlink_version)
msg.pack(self)
return msg
def heartbeat_send(self, type, autopilot, mavlink_version=2):
'''
The heartbeat message shows that a system is present and responding.
The type of the MAV and Autopilot hardware allow the
receiving system to treat further messages from this
system appropriate (e.g. by laying out the user
interface based on the autopilot).
type : Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) (uint8_t)
autopilot : Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM (uint8_t)
mavlink_version : MAVLink version (uint8_t)
'''
return self.send(self.heartbeat_encode(type, autopilot, mavlink_version))
def boot_encode(self, version):
'''
The boot message indicates that a system is starting. The onboard
software version allows to keep track of onboard
soft/firmware revisions.
version : The onboard software version (uint32_t)
'''
msg = MAVLink_boot_message(version)
msg.pack(self)
return msg
def boot_send(self, version):
'''
The boot message indicates that a system is starting. The onboard
software version allows to keep track of onboard
soft/firmware revisions.
version : The onboard software version (uint32_t)
'''
return self.send(self.boot_encode(version))
def system_time_encode(self, time_usec):
'''
The system time is the time of the master clock, typically the
computer clock of the main onboard computer.
time_usec : Timestamp of the master clock in microseconds since UNIX epoch. (uint64_t)
'''
msg = MAVLink_system_time_message(time_usec)
msg.pack(self)
return msg
def system_time_send(self, time_usec):
'''
The system time is the time of the master clock, typically the
computer clock of the main onboard computer.
time_usec : Timestamp of the master clock in microseconds since UNIX epoch. (uint64_t)
'''
return self.send(self.system_time_encode(time_usec))
def ping_encode(self, seq, target_system, target_component, time):
'''
A ping message either requesting or responding to a ping. This allows
to measure the system latencies, including serial
port, radio modem and UDP connections.
seq : PING sequence (uint32_t)
target_system : 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t)
target_component : 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t)
time : Unix timestamp in microseconds (uint64_t)
'''
msg = MAVLink_ping_message(seq, target_system, target_component, time)
msg.pack(self)
return msg
def ping_send(self, seq, target_system, target_component, time):
'''
A ping message either requesting or responding to a ping. This allows
to measure the system latencies, including serial
port, radio modem and UDP connections.
seq : PING sequence (uint32_t)
target_system : 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t)
target_component : 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t)
time : Unix timestamp in microseconds (uint64_t)
'''
return self.send(self.ping_encode(seq, target_system, target_component, time))
def system_time_utc_encode(self, utc_date, utc_time):
'''
UTC date and time from GPS module
utc_date : GPS UTC date ddmmyy (uint32_t)
utc_time : GPS UTC time hhmmss (uint32_t)
'''
msg = MAVLink_system_time_utc_message(utc_date, utc_time)
msg.pack(self)
return msg
def system_time_utc_send(self, utc_date, utc_time):
'''
UTC date and time from GPS module
utc_date : GPS UTC date ddmmyy (uint32_t)
utc_time : GPS UTC time hhmmss (uint32_t)
'''
return self.send(self.system_time_utc_encode(utc_date, utc_time))
def change_operator_control_encode(self, target_system, control_request, version, passkey):
'''
Request to control this MAV
target_system : System the GCS requests control for (uint8_t)
control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t)
version : 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. (uint8_t)
passkey : Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" (char)
'''
msg = MAVLink_change_operator_control_message(target_system, control_request, version, passkey)
msg.pack(self)
return msg
def change_operator_control_send(self, target_system, control_request, version, passkey):
'''
Request to control this MAV
target_system : System the GCS requests control for (uint8_t)
control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t)
version : 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. (uint8_t)
passkey : Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" (char)
'''
return self.send(self.change_operator_control_encode(target_system, control_request, version, passkey))
def change_operator_control_ack_encode(self, gcs_system_id, control_request, ack):
'''
Accept / deny control of this MAV
gcs_system_id : ID of the GCS this message (uint8_t)
control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t)
ack : 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control (uint8_t)
'''
msg = MAVLink_change_operator_control_ack_message(gcs_system_id, control_request, ack)
msg.pack(self)
return msg
def change_operator_control_ack_send(self, gcs_system_id, control_request, ack):
'''
Accept / deny control of this MAV
gcs_system_id : ID of the GCS this message (uint8_t)
control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t)
ack : 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control (uint8_t)
'''
return self.send(self.change_operator_control_ack_encode(gcs_system_id, control_request, ack))
def auth_key_encode(self, key):
'''
Emit an encrypted signature / key identifying this system. PLEASE
NOTE: This protocol has been kept simple, so
transmitting the key requires an encrypted channel for
true safety.
key : key (char)
'''
msg = MAVLink_auth_key_message(key)
msg.pack(self)
return msg
def auth_key_send(self, key):
'''
Emit an encrypted signature / key identifying this system. PLEASE
NOTE: This protocol has been kept simple, so
transmitting the key requires an encrypted channel for
true safety.
key : key (char)
'''
return self.send(self.auth_key_encode(key))
def action_ack_encode(self, action, result):
'''
This message acknowledges an action. IMPORTANT: The acknowledgement
can be also negative, e.g. the MAV rejects a reset
message because it is in-flight. The action ids are
defined in ENUM MAV_ACTION in
mavlink/include/mavlink_types.h
action : The action id (uint8_t)
result : 0: Action DENIED, 1: Action executed (uint8_t)
'''
msg = MAVLink_action_ack_message(action, result)
msg.pack(self)
return msg
def action_ack_send(self, action, result):
'''
This message acknowledges an action. IMPORTANT: The acknowledgement
can be also negative, e.g. the MAV rejects a reset
message because it is in-flight. The action ids are
defined in ENUM MAV_ACTION in
mavlink/include/mavlink_types.h
action : The action id (uint8_t)
result : 0: Action DENIED, 1: Action executed (uint8_t)
'''
return self.send(self.action_ack_encode(action, result))
def action_encode(self, target, target_component, action):
'''
An action message allows to execute a certain onboard action. These
include liftoff, land, storing parameters too EEPROM,
shutddown, etc. The action ids are defined in ENUM
MAV_ACTION in mavlink/include/mavlink_types.h
target : The system executing the action (uint8_t)
target_component : The component executing the action (uint8_t)
action : The action id (uint8_t)
'''
msg = MAVLink_action_message(target, target_component, action)
msg.pack(self)
return msg
def action_send(self, target, target_component, action):
'''
An action message allows to execute a certain onboard action. These
include liftoff, land, storing parameters too EEPROM,
shutddown, etc. The action ids are defined in ENUM
MAV_ACTION in mavlink/include/mavlink_types.h
target : The system executing the action (uint8_t)
target_component : The component executing the action (uint8_t)
action : The action id (uint8_t)
'''
return self.send(self.action_encode(target, target_component, action))
def set_mode_encode(self, target, mode):
'''
Set the system mode, as defined by enum MAV_MODE in
mavlink/include/mavlink_types.h. There is no target
component id as the mode is by definition for the
overall aircraft, not only for one component.
target : The system setting the mode (uint8_t)
mode : The new mode (uint8_t)
'''
msg = MAVLink_set_mode_message(target, mode)
msg.pack(self)
return msg
def set_mode_send(self, target, mode):
'''
Set the system mode, as defined by enum MAV_MODE in
mavlink/include/mavlink_types.h. There is no target
component id as the mode is by definition for the
overall aircraft, not only for one component.
target : The system setting the mode (uint8_t)
mode : The new mode (uint8_t)
'''
return self.send(self.set_mode_encode(target, mode))
def set_nav_mode_encode(self, target, nav_mode):
'''
Set the system navigation mode, as defined by enum MAV_NAV_MODE in
mavlink/include/mavlink_types.h. The navigation mode
applies to the whole aircraft and thus all components.
target : The system setting the mode (uint8_t)
nav_mode : The new navigation mode (uint8_t)
'''
msg = MAVLink_set_nav_mode_message(target, nav_mode)
msg.pack(self)
return msg
def set_nav_mode_send(self, target, nav_mode):
'''
Set the system navigation mode, as defined by enum MAV_NAV_MODE in
mavlink/include/mavlink_types.h. The navigation mode
applies to the whole aircraft and thus all components.
target : The system setting the mode (uint8_t)
nav_mode : The new navigation mode (uint8_t)
'''
return self.send(self.set_nav_mode_encode(target, nav_mode))
def param_request_read_encode(self, target_system, target_component, param_id, param_index):
'''
Request to read the onboard parameter with the param_id string id.
Onboard parameters are stored as key[const char*] ->
value[float]. This allows to send a parameter to any
other component (such as the GCS) without the need of
previous knowledge of possible parameter names. Thus
the same GCS can store different parameters for
different autopilots. See also
http://qgroundcontrol.org/parameter_interface for a
full documentation of QGroundControl and IMU code.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
param_id : Onboard parameter id (int8_t)
param_index : Parameter index. Send -1 to use the param ID field as identifier (int16_t)
'''
msg = MAVLink_param_request_read_message(target_system, target_component, param_id, param_index)
msg.pack(self)
return msg
def param_request_read_send(self, target_system, target_component, param_id, param_index):
'''
Request to read the onboard parameter with the param_id string id.
Onboard parameters are stored as key[const char*] ->
value[float]. This allows to send a parameter to any
other component (such as the GCS) without the need of
previous knowledge of possible parameter names. Thus
the same GCS can store different parameters for
different autopilots. See also
http://qgroundcontrol.org/parameter_interface for a
full documentation of QGroundControl and IMU code.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
param_id : Onboard parameter id (int8_t)
param_index : Parameter index. Send -1 to use the param ID field as identifier (int16_t)
'''
return self.send(self.param_request_read_encode(target_system, target_component, param_id, param_index))
def param_request_list_encode(self, target_system, target_component):
'''
Request all parameters of this component. After his request, all
parameters are emitted.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
'''
msg = MAVLink_param_request_list_message(target_system, target_component)
msg.pack(self)
return msg
def param_request_list_send(self, target_system, target_component):
'''
Request all parameters of this component. After his request, all
parameters are emitted.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
'''
return self.send(self.param_request_list_encode(target_system, target_component))
def param_value_encode(self, param_id, param_value, param_count, param_index):
'''
Emit the value of a onboard parameter. The inclusion of param_count
and param_index in the message allows the recipient to
keep track of received parameters and allows him to
re-request missing parameters after a loss or timeout.
param_id : Onboard parameter id (int8_t)
param_value : Onboard parameter value (float)
param_count : Total number of onboard parameters (uint16_t)
param_index : Index of this onboard parameter (uint16_t)
'''
msg = MAVLink_param_value_message(param_id, param_value, param_count, param_index)
msg.pack(self)
return msg
def param_value_send(self, param_id, param_value, param_count, param_index):
'''
Emit the value of a onboard parameter. The inclusion of param_count
and param_index in the message allows the recipient to
keep track of received parameters and allows him to
re-request missing parameters after a loss or timeout.
param_id : Onboard parameter id (int8_t)
param_value : Onboard parameter value (float)
param_count : Total number of onboard parameters (uint16_t)
param_index : Index of this onboard parameter (uint16_t)
'''
return self.send(self.param_value_encode(param_id, param_value, param_count, param_index))
def param_set_encode(self, target_system, target_component, param_id, param_value):
'''
Set a parameter value TEMPORARILY to RAM. It will be reset to default
on system reboot. Send the ACTION
MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM
contents to EEPROM. IMPORTANT: The receiving component
should acknowledge the new parameter value by sending
a param_value message to all communication partners.
This will also ensure that multiple GCS all have an
up-to-date list of all parameters. If the sending GCS
did not receive a PARAM_VALUE message within its
timeout time, it should re-send the PARAM_SET message.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
param_id : Onboard parameter id (int8_t)
param_value : Onboard parameter value (float)
'''
msg = MAVLink_param_set_message(target_system, target_component, param_id, param_value)
msg.pack(self)
return msg
def param_set_send(self, target_system, target_component, param_id, param_value):
'''
Set a parameter value TEMPORARILY to RAM. It will be reset to default
on system reboot. Send the ACTION
MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM
contents to EEPROM. IMPORTANT: The receiving component
should acknowledge the new parameter value by sending
a param_value message to all communication partners.
This will also ensure that multiple GCS all have an
up-to-date list of all parameters. If the sending GCS
did not receive a PARAM_VALUE message within its
timeout time, it should re-send the PARAM_SET message.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
param_id : Onboard parameter id (int8_t)
param_value : Onboard parameter value (float)
'''
return self.send(self.param_set_encode(target_system, target_component, param_id, param_value))
def gps_raw_int_encode(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg):
'''
The global position, as returned by the Global Positioning System
(GPS). This is NOT the global position estimate of the
sytem, but rather a RAW sensor value. See message
GLOBAL_POSITION for the global position estimate.
Coordinate frame is right-handed, Z-axis up (GPS
frame)
usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t)
lat : Latitude in 1E7 degrees (int32_t)
lon : Longitude in 1E7 degrees (int32_t)
alt : Altitude in 1E3 meters (millimeters) (int32_t)
eph : GPS HDOP (float)
epv : GPS VDOP (float)
v : GPS ground speed (m/s) (float)
hdg : Compass heading in degrees, 0..360 degrees (float)
'''
msg = MAVLink_gps_raw_int_message(usec, fix_type, lat, lon, alt, eph, epv, v, hdg)
msg.pack(self)
return msg
def gps_raw_int_send(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg):
'''
The global position, as returned by the Global Positioning System
(GPS). This is NOT the global position estimate of the
sytem, but rather a RAW sensor value. See message
GLOBAL_POSITION for the global position estimate.
Coordinate frame is right-handed, Z-axis up (GPS
frame)
usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t)
lat : Latitude in 1E7 degrees (int32_t)
lon : Longitude in 1E7 degrees (int32_t)
alt : Altitude in 1E3 meters (millimeters) (int32_t)
eph : GPS HDOP (float)
epv : GPS VDOP (float)
v : GPS ground speed (m/s) (float)
hdg : Compass heading in degrees, 0..360 degrees (float)
'''
return self.send(self.gps_raw_int_encode(usec, fix_type, lat, lon, alt, eph, epv, v, hdg))
def scaled_imu_encode(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag):
'''
The RAW IMU readings for the usual 9DOF sensor setup. This message
should contain the scaled values to the described
units
usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
xacc : X acceleration (mg) (int16_t)
yacc : Y acceleration (mg) (int16_t)
zacc : Z acceleration (mg) (int16_t)
xgyro : Angular speed around X axis (millirad /sec) (int16_t)
ygyro : Angular speed around Y axis (millirad /sec) (int16_t)
zgyro : Angular speed around Z axis (millirad /sec) (int16_t)
xmag : X Magnetic field (milli tesla) (int16_t)
ymag : Y Magnetic field (milli tesla) (int16_t)
zmag : Z Magnetic field (milli tesla) (int16_t)
'''
msg = MAVLink_scaled_imu_message(usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)
msg.pack(self)
return msg
def scaled_imu_send(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag):
'''
The RAW IMU readings for the usual 9DOF sensor setup. This message
should contain the scaled values to the described
units
usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
xacc : X acceleration (mg) (int16_t)
yacc : Y acceleration (mg) (int16_t)
zacc : Z acceleration (mg) (int16_t)
xgyro : Angular speed around X axis (millirad /sec) (int16_t)
ygyro : Angular speed around Y axis (millirad /sec) (int16_t)
zgyro : Angular speed around Z axis (millirad /sec) (int16_t)
xmag : X Magnetic field (milli tesla) (int16_t)
ymag : Y Magnetic field (milli tesla) (int16_t)
zmag : Z Magnetic field (milli tesla) (int16_t)
'''
return self.send(self.scaled_imu_encode(usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag))
def gps_status_encode(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr):
'''
The positioning status, as reported by GPS. This message is intended
to display status information about each satellite
visible to the receiver. See message GLOBAL_POSITION
for the global position estimate. This message can
contain information for up to 20 satellites.
satellites_visible : Number of satellites visible (uint8_t)
satellite_prn : Global satellite ID (int8_t)
satellite_used : 0: Satellite not used, 1: used for localization (int8_t)
satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (int8_t)
satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (int8_t)
satellite_snr : Signal to noise ratio of satellite (int8_t)
'''
msg = MAVLink_gps_status_message(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr)
msg.pack(self)
return msg
def gps_status_send(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr):
'''
The positioning status, as reported by GPS. This message is intended
to display status information about each satellite
visible to the receiver. See message GLOBAL_POSITION
for the global position estimate. This message can
contain information for up to 20 satellites.
satellites_visible : Number of satellites visible (uint8_t)
satellite_prn : Global satellite ID (int8_t)
satellite_used : 0: Satellite not used, 1: used for localization (int8_t)
satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (int8_t)
satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (int8_t)
satellite_snr : Signal to noise ratio of satellite (int8_t)
'''
return self.send(self.gps_status_encode(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr))
def raw_imu_encode(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag):
'''
The RAW IMU readings for the usual 9DOF sensor setup. This message
should always contain the true raw values without any
scaling to allow data capture and system debugging.
usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
xacc : X acceleration (raw) (int16_t)
yacc : Y acceleration (raw) (int16_t)
zacc : Z acceleration (raw) (int16_t)
xgyro : Angular speed around X axis (raw) (int16_t)
ygyro : Angular speed around Y axis (raw) (int16_t)
zgyro : Angular speed around Z axis (raw) (int16_t)
xmag : X Magnetic field (raw) (int16_t)
ymag : Y Magnetic field (raw) (int16_t)
zmag : Z Magnetic field (raw) (int16_t)
'''
msg = MAVLink_raw_imu_message(usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)
msg.pack(self)
return msg
def raw_imu_send(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag):
'''
The RAW IMU readings for the usual 9DOF sensor setup. This message
should always contain the true raw values without any
scaling to allow data capture and system debugging.
usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
xacc : X acceleration (raw) (int16_t)
yacc : Y acceleration (raw) (int16_t)
zacc : Z acceleration (raw) (int16_t)
xgyro : Angular speed around X axis (raw) (int16_t)
ygyro : Angular speed around Y axis (raw) (int16_t)
zgyro : Angular speed around Z axis (raw) (int16_t)
xmag : X Magnetic field (raw) (int16_t)
ymag : Y Magnetic field (raw) (int16_t)
zmag : Z Magnetic field (raw) (int16_t)
'''
return self.send(self.raw_imu_encode(usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag))
def raw_pressure_encode(self, usec, press_abs, press_diff1, press_diff2, temperature):
'''
The RAW pressure readings for the typical setup of one absolute
pressure and one differential pressure sensor. The
sensor values should be the raw, UNSCALED ADC values.
usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
press_abs : Absolute pressure (raw) (int16_t)
press_diff1 : Differential pressure 1 (raw) (int16_t)
press_diff2 : Differential pressure 2 (raw) (int16_t)
temperature : Raw Temperature measurement (raw) (int16_t)
'''
msg = MAVLink_raw_pressure_message(usec, press_abs, press_diff1, press_diff2, temperature)
msg.pack(self)
return msg
def raw_pressure_send(self, usec, press_abs, press_diff1, press_diff2, temperature):
'''
The RAW pressure readings for the typical setup of one absolute
pressure and one differential pressure sensor. The
sensor values should be the raw, UNSCALED ADC values.
usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
press_abs : Absolute pressure (raw) (int16_t)
press_diff1 : Differential pressure 1 (raw) (int16_t)
press_diff2 : Differential pressure 2 (raw) (int16_t)
temperature : Raw Temperature measurement (raw) (int16_t)
'''
return self.send(self.raw_pressure_encode(usec, press_abs, press_diff1, press_diff2, temperature))
def scaled_pressure_encode(self, usec, press_abs, press_diff, temperature):
'''
The pressure readings for the typical setup of one absolute and
differential pressure sensor. The units are as
specified in each field.
usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
press_abs : Absolute pressure (hectopascal) (float)
press_diff : Differential pressure 1 (hectopascal) (float)
temperature : Temperature measurement (0.01 degrees celsius) (int16_t)
'''
msg = MAVLink_scaled_pressure_message(usec, press_abs, press_diff, temperature)
msg.pack(self)
return msg
def scaled_pressure_send(self, usec, press_abs, press_diff, temperature):
'''
The pressure readings for the typical setup of one absolute and
differential pressure sensor. The units are as
specified in each field.
usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
press_abs : Absolute pressure (hectopascal) (float)
press_diff : Differential pressure 1 (hectopascal) (float)
temperature : Temperature measurement (0.01 degrees celsius) (int16_t)
'''
return self.send(self.scaled_pressure_encode(usec, press_abs, press_diff, temperature))
def attitude_encode(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed):
'''
The attitude in the aeronautical frame (right-handed, Z-down, X-front,
Y-right).
usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
roll : Roll angle (rad) (float)
pitch : Pitch angle (rad) (float)
yaw : Yaw angle (rad) (float)
rollspeed : Roll angular speed (rad/s) (float)
pitchspeed : Pitch angular speed (rad/s) (float)
yawspeed : Yaw angular speed (rad/s) (float)
'''
msg = MAVLink_attitude_message(usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed)
msg.pack(self)
return msg
def attitude_send(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed):
'''
The attitude in the aeronautical frame (right-handed, Z-down, X-front,
Y-right).
usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
roll : Roll angle (rad) (float)
pitch : Pitch angle (rad) (float)
yaw : Yaw angle (rad) (float)
rollspeed : Roll angular speed (rad/s) (float)
pitchspeed : Pitch angular speed (rad/s) (float)
yawspeed : Yaw angular speed (rad/s) (float)
'''
return self.send(self.attitude_encode(usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed))
def local_position_encode(self, usec, x, y, z, vx, vy, vz):
'''
The filtered local position (e.g. fused computer vision and
accelerometers). Coordinate frame is right-handed,
Z-axis down (aeronautical frame)
usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
x : X Position (float)
y : Y Position (float)
z : Z Position (float)
vx : X Speed (float)
vy : Y Speed (float)
vz : Z Speed (float)
'''
msg = MAVLink_local_position_message(usec, x, y, z, vx, vy, vz)
msg.pack(self)
return msg
def local_position_send(self, usec, x, y, z, vx, vy, vz):
'''
The filtered local position (e.g. fused computer vision and
accelerometers). Coordinate frame is right-handed,
Z-axis down (aeronautical frame)
usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
x : X Position (float)
y : Y Position (float)
z : Z Position (float)
vx : X Speed (float)
vy : Y Speed (float)
vz : Z Speed (float)
'''
return self.send(self.local_position_encode(usec, x, y, z, vx, vy, vz))
def global_position_encode(self, usec, lat, lon, alt, vx, vy, vz):
'''
The filtered global position (e.g. fused GPS and accelerometers).
Coordinate frame is right-handed, Z-axis up (GPS
frame)
usec : Timestamp (microseconds since unix epoch) (uint64_t)
lat : Latitude, in degrees (float)
lon : Longitude, in degrees (float)
alt : Absolute altitude, in meters (float)
vx : X Speed (in Latitude direction, positive: going north) (float)
vy : Y Speed (in Longitude direction, positive: going east) (float)
vz : Z Speed (in Altitude direction, positive: going up) (float)
'''
msg = MAVLink_global_position_message(usec, lat, lon, alt, vx, vy, vz)
msg.pack(self)
return msg
def global_position_send(self, usec, lat, lon, alt, vx, vy, vz):
'''
The filtered global position (e.g. fused GPS and accelerometers).
Coordinate frame is right-handed, Z-axis up (GPS
frame)
usec : Timestamp (microseconds since unix epoch) (uint64_t)
lat : Latitude, in degrees (float)
lon : Longitude, in degrees (float)
alt : Absolute altitude, in meters (float)
vx : X Speed (in Latitude direction, positive: going north) (float)
vy : Y Speed (in Longitude direction, positive: going east) (float)
vz : Z Speed (in Altitude direction, positive: going up) (float)
'''
return self.send(self.global_position_encode(usec, lat, lon, alt, vx, vy, vz))
def gps_raw_encode(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg):
'''
The global position, as returned by the Global Positioning System
(GPS). This is NOT the global position estimate of the
sytem, but rather a RAW sensor value. See message
GLOBAL_POSITION for the global position estimate.
Coordinate frame is right-handed, Z-axis up (GPS
frame)
usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t)
lat : Latitude in degrees (float)
lon : Longitude in degrees (float)
alt : Altitude in meters (float)
eph : GPS HDOP (float)
epv : GPS VDOP (float)
v : GPS ground speed (float)
hdg : Compass heading in degrees, 0..360 degrees (float)
'''
msg = MAVLink_gps_raw_message(usec, fix_type, lat, lon, alt, eph, epv, v, hdg)
msg.pack(self)
return msg
def gps_raw_send(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg):
'''
The global position, as returned by the Global Positioning System
(GPS). This is NOT the global position estimate of the
sytem, but rather a RAW sensor value. See message
GLOBAL_POSITION for the global position estimate.
Coordinate frame is right-handed, Z-axis up (GPS
frame)
usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t)
lat : Latitude in degrees (float)
lon : Longitude in degrees (float)
alt : Altitude in meters (float)
eph : GPS HDOP (float)
epv : GPS VDOP (float)
v : GPS ground speed (float)
hdg : Compass heading in degrees, 0..360 degrees (float)
'''
return self.send(self.gps_raw_encode(usec, fix_type, lat, lon, alt, eph, epv, v, hdg))
def sys_status_encode(self, mode, nav_mode, status, load, vbat, battery_remaining, packet_drop):
'''
The general system state. If the system is following the MAVLink
standard, the system state is mainly defined by three
orthogonal states/modes: The system mode, which is
either LOCKED (motors shut down and locked), MANUAL
(system under RC control), GUIDED (system with
autonomous position control, position setpoint
controlled manually) or AUTO (system guided by
path/waypoint planner). The NAV_MODE defined the
current flight state: LIFTOFF (often an open-loop
maneuver), LANDING, WAYPOINTS or VECTOR. This
represents the internal navigation state machine. The
system status shows wether the system is currently
active or not and if an emergency occured. During the
CRITICAL and EMERGENCY states the MAV is still
considered to be active, but should start emergency
procedures autonomously. After a failure occured it
should first move from active to critical to allow
manual intervention and then move to emergency after a
certain timeout.
mode : System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h (uint8_t)
nav_mode : Navigation mode, see MAV_NAV_MODE ENUM (uint8_t)
status : System status flag, see MAV_STATUS ENUM (uint8_t)
load : Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 (uint16_t)
vbat : Battery voltage, in millivolts (1 = 1 millivolt) (uint16_t)
battery_remaining : Remaining battery energy: (0%: 0, 100%: 1000) (uint16_t)
packet_drop : Dropped packets (packets that were corrupted on reception on the MAV) (uint16_t)
'''
msg = MAVLink_sys_status_message(mode, nav_mode, status, load, vbat, battery_remaining, packet_drop)
msg.pack(self)
return msg
def sys_status_send(self, mode, nav_mode, status, load, vbat, battery_remaining, packet_drop):
'''
The general system state. If the system is following the MAVLink
standard, the system state is mainly defined by three
orthogonal states/modes: The system mode, which is
either LOCKED (motors shut down and locked), MANUAL
(system under RC control), GUIDED (system with
autonomous position control, position setpoint
controlled manually) or AUTO (system guided by
path/waypoint planner). The NAV_MODE defined the
current flight state: LIFTOFF (often an open-loop
maneuver), LANDING, WAYPOINTS or VECTOR. This
represents the internal navigation state machine. The
system status shows wether the system is currently
active or not and if an emergency occured. During the
CRITICAL and EMERGENCY states the MAV is still
considered to be active, but should start emergency
procedures autonomously. After a failure occured it
should first move from active to critical to allow
manual intervention and then move to emergency after a
certain timeout.
mode : System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h (uint8_t)
nav_mode : Navigation mode, see MAV_NAV_MODE ENUM (uint8_t)
status : System status flag, see MAV_STATUS ENUM (uint8_t)
load : Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 (uint16_t)
vbat : Battery voltage, in millivolts (1 = 1 millivolt) (uint16_t)
battery_remaining : Remaining battery energy: (0%: 0, 100%: 1000) (uint16_t)
packet_drop : Dropped packets (packets that were corrupted on reception on the MAV) (uint16_t)
'''
return self.send(self.sys_status_encode(mode, nav_mode, status, load, vbat, battery_remaining, packet_drop))
def rc_channels_raw_encode(self, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi):
'''
The RAW values of the RC channels received. The standard PPM
modulation is as follows: 1000 microseconds: 0%, 2000
microseconds: 100%. Individual receivers/transmitters
might violate this specification.
chan1_raw : RC channel 1 value, in microseconds (uint16_t)
chan2_raw : RC channel 2 value, in microseconds (uint16_t)
chan3_raw : RC channel 3 value, in microseconds (uint16_t)
chan4_raw : RC channel 4 value, in microseconds (uint16_t)
chan5_raw : RC channel 5 value, in microseconds (uint16_t)
chan6_raw : RC channel 6 value, in microseconds (uint16_t)
chan7_raw : RC channel 7 value, in microseconds (uint16_t)
chan8_raw : RC channel 8 value, in microseconds (uint16_t)
rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t)
'''
msg = MAVLink_rc_channels_raw_message(chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi)
msg.pack(self)
return msg
def rc_channels_raw_send(self, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi):
'''
The RAW values of the RC channels received. The standard PPM
modulation is as follows: 1000 microseconds: 0%, 2000
microseconds: 100%. Individual receivers/transmitters
might violate this specification.
chan1_raw : RC channel 1 value, in microseconds (uint16_t)
chan2_raw : RC channel 2 value, in microseconds (uint16_t)
chan3_raw : RC channel 3 value, in microseconds (uint16_t)
chan4_raw : RC channel 4 value, in microseconds (uint16_t)
chan5_raw : RC channel 5 value, in microseconds (uint16_t)
chan6_raw : RC channel 6 value, in microseconds (uint16_t)
chan7_raw : RC channel 7 value, in microseconds (uint16_t)
chan8_raw : RC channel 8 value, in microseconds (uint16_t)
rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t)
'''
return self.send(self.rc_channels_raw_encode(chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi))
def rc_channels_scaled_encode(self, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi):
'''
The scaled values of the RC channels received. (-100%) -10000, (0%) 0,
(100%) 10000
chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t)
chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t)
chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t)
chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t)
chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t)
chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t)
chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t)
chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t)
rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t)
'''
msg = MAVLink_rc_channels_scaled_message(chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi)
msg.pack(self)
return msg
def rc_channels_scaled_send(self, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi):
'''
The scaled values of the RC channels received. (-100%) -10000, (0%) 0,
(100%) 10000
chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t)
chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t)
chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t)
chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t)
chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t)
chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t)
chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t)
chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t)
rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t)
'''
return self.send(self.rc_channels_scaled_encode(chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi))
def servo_output_raw_encode(self, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw):
'''
The RAW values of the servo outputs (for RC input from the remote, use
the RC_CHANNELS messages). The standard PPM modulation
is as follows: 1000 microseconds: 0%, 2000
microseconds: 100%.
servo1_raw : Servo output 1 value, in microseconds (uint16_t)
servo2_raw : Servo output 2 value, in microseconds (uint16_t)
servo3_raw : Servo output 3 value, in microseconds (uint16_t)
servo4_raw : Servo output 4 value, in microseconds (uint16_t)
servo5_raw : Servo output 5 value, in microseconds (uint16_t)
servo6_raw : Servo output 6 value, in microseconds (uint16_t)
servo7_raw : Servo output 7 value, in microseconds (uint16_t)
servo8_raw : Servo output 8 value, in microseconds (uint16_t)
'''
msg = MAVLink_servo_output_raw_message(servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw)
msg.pack(self)
return msg
def servo_output_raw_send(self, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw):
'''
The RAW values of the servo outputs (for RC input from the remote, use
the RC_CHANNELS messages). The standard PPM modulation
is as follows: 1000 microseconds: 0%, 2000
microseconds: 100%.
servo1_raw : Servo output 1 value, in microseconds (uint16_t)
servo2_raw : Servo output 2 value, in microseconds (uint16_t)
servo3_raw : Servo output 3 value, in microseconds (uint16_t)
servo4_raw : Servo output 4 value, in microseconds (uint16_t)
servo5_raw : Servo output 5 value, in microseconds (uint16_t)
servo6_raw : Servo output 6 value, in microseconds (uint16_t)
servo7_raw : Servo output 7 value, in microseconds (uint16_t)
servo8_raw : Servo output 8 value, in microseconds (uint16_t)
'''
return self.send(self.servo_output_raw_encode(servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw))
def waypoint_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z):
'''
Message encoding a waypoint. This message is emitted to announce
the presence of a waypoint and to set a waypoint on
the system. The waypoint can be either in x, y, z
meters (type: LOCAL) or x:lat, y:lon, z:altitude.
Local frame is Z-down, right handed, global frame is
Z-up, right handed
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
seq : Sequence (uint16_t)
frame : The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h (uint8_t)
command : The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs (uint8_t)
current : false:0, true:1 (uint8_t)
autocontinue : autocontinue to next wp (uint8_t)
param1 : PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters (float)
param2 : PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds (float)
param3 : PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. (float)
param4 : PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH (float)
x : PARAM5 / local: x position, global: latitude (float)
y : PARAM6 / y position: global: longitude (float)
z : PARAM7 / z position: global: altitude (float)
'''
msg = MAVLink_waypoint_message(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)
msg.pack(self)
return msg
def waypoint_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z):
'''
Message encoding a waypoint. This message is emitted to announce
the presence of a waypoint and to set a waypoint on
the system. The waypoint can be either in x, y, z
meters (type: LOCAL) or x:lat, y:lon, z:altitude.
Local frame is Z-down, right handed, global frame is
Z-up, right handed
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
seq : Sequence (uint16_t)
frame : The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h (uint8_t)
command : The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs (uint8_t)
current : false:0, true:1 (uint8_t)
autocontinue : autocontinue to next wp (uint8_t)
param1 : PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters (float)
param2 : PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds (float)
param3 : PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. (float)
param4 : PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH (float)
x : PARAM5 / local: x position, global: latitude (float)
y : PARAM6 / y position: global: longitude (float)
z : PARAM7 / z position: global: altitude (float)
'''
return self.send(self.waypoint_encode(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z))
def waypoint_request_encode(self, target_system, target_component, seq):
'''
Request the information of the waypoint with the sequence number seq.
The response of the system to this message should be a
WAYPOINT message.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
seq : Sequence (uint16_t)
'''
msg = MAVLink_waypoint_request_message(target_system, target_component, seq)
msg.pack(self)
return msg
def waypoint_request_send(self, target_system, target_component, seq):
'''
Request the information of the waypoint with the sequence number seq.
The response of the system to this message should be a
WAYPOINT message.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
seq : Sequence (uint16_t)
'''
return self.send(self.waypoint_request_encode(target_system, target_component, seq))
def waypoint_set_current_encode(self, target_system, target_component, seq):
'''
Set the waypoint with sequence number seq as current waypoint. This
means that the MAV will continue to this waypoint on
the shortest path (not following the waypoints in-
between).
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
seq : Sequence (uint16_t)
'''
msg = MAVLink_waypoint_set_current_message(target_system, target_component, seq)
msg.pack(self)
return msg
def waypoint_set_current_send(self, target_system, target_component, seq):
'''
Set the waypoint with sequence number seq as current waypoint. This
means that the MAV will continue to this waypoint on
the shortest path (not following the waypoints in-
between).
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
seq : Sequence (uint16_t)
'''
return self.send(self.waypoint_set_current_encode(target_system, target_component, seq))
def waypoint_current_encode(self, seq):
'''
Message that announces the sequence number of the current active
waypoint. The MAV will fly towards this waypoint.
seq : Sequence (uint16_t)
'''
msg = MAVLink_waypoint_current_message(seq)
msg.pack(self)
return msg
def waypoint_current_send(self, seq):
'''
Message that announces the sequence number of the current active
waypoint. The MAV will fly towards this waypoint.
seq : Sequence (uint16_t)
'''
return self.send(self.waypoint_current_encode(seq))
def waypoint_request_list_encode(self, target_system, target_component):
'''
Request the overall list of waypoints from the system/component.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
'''
msg = MAVLink_waypoint_request_list_message(target_system, target_component)
msg.pack(self)
return msg
def waypoint_request_list_send(self, target_system, target_component):
'''
Request the overall list of waypoints from the system/component.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
'''
return self.send(self.waypoint_request_list_encode(target_system, target_component))
def waypoint_count_encode(self, target_system, target_component, count):
'''
This message is emitted as response to WAYPOINT_REQUEST_LIST by the
MAV. The GCS can then request the individual waypoints
based on the knowledge of the total number of
waypoints.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
count : Number of Waypoints in the Sequence (uint16_t)
'''
msg = MAVLink_waypoint_count_message(target_system, target_component, count)
msg.pack(self)
return msg
def waypoint_count_send(self, target_system, target_component, count):
'''
This message is emitted as response to WAYPOINT_REQUEST_LIST by the
MAV. The GCS can then request the individual waypoints
based on the knowledge of the total number of
waypoints.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
count : Number of Waypoints in the Sequence (uint16_t)
'''
return self.send(self.waypoint_count_encode(target_system, target_component, count))
def waypoint_clear_all_encode(self, target_system, target_component):
'''
Delete all waypoints at once.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
'''
msg = MAVLink_waypoint_clear_all_message(target_system, target_component)
msg.pack(self)
return msg
def waypoint_clear_all_send(self, target_system, target_component):
'''
Delete all waypoints at once.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
'''
return self.send(self.waypoint_clear_all_encode(target_system, target_component))
def waypoint_reached_encode(self, seq):
'''
A certain waypoint has been reached. The system will either hold this
position (or circle on the orbit) or (if the
autocontinue on the WP was set) continue to the next
waypoint.
seq : Sequence (uint16_t)
'''
msg = MAVLink_waypoint_reached_message(seq)
msg.pack(self)
return msg
def waypoint_reached_send(self, seq):
'''
A certain waypoint has been reached. The system will either hold this
position (or circle on the orbit) or (if the
autocontinue on the WP was set) continue to the next
waypoint.
seq : Sequence (uint16_t)
'''
return self.send(self.waypoint_reached_encode(seq))
def waypoint_ack_encode(self, target_system, target_component, type):
'''
Ack message during waypoint handling. The type field states if this
message is a positive ack (type=0) or if an error
happened (type=non-zero).
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
type : 0: OK, 1: Error (uint8_t)
'''
msg = MAVLink_waypoint_ack_message(target_system, target_component, type)
msg.pack(self)
return msg
def waypoint_ack_send(self, target_system, target_component, type):
'''
Ack message during waypoint handling. The type field states if this
message is a positive ack (type=0) or if an error
happened (type=non-zero).
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
type : 0: OK, 1: Error (uint8_t)
'''
return self.send(self.waypoint_ack_encode(target_system, target_component, type))
def gps_set_global_origin_encode(self, target_system, target_component, latitude, longitude, altitude):
'''
As local waypoints exist, the global waypoint reference allows to
transform between the local coordinate frame and the
global (GPS) coordinate frame. This can be necessary
when e.g. in- and outdoor settings are connected and
the MAV should move from in- to outdoor.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
latitude : global position * 1E7 (int32_t)
longitude : global position * 1E7 (int32_t)
altitude : global position * 1000 (int32_t)
'''
msg = MAVLink_gps_set_global_origin_message(target_system, target_component, latitude, longitude, altitude)
msg.pack(self)
return msg
def gps_set_global_origin_send(self, target_system, target_component, latitude, longitude, altitude):
'''
As local waypoints exist, the global waypoint reference allows to
transform between the local coordinate frame and the
global (GPS) coordinate frame. This can be necessary
when e.g. in- and outdoor settings are connected and
the MAV should move from in- to outdoor.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
latitude : global position * 1E7 (int32_t)
longitude : global position * 1E7 (int32_t)
altitude : global position * 1000 (int32_t)
'''
return self.send(self.gps_set_global_origin_encode(target_system, target_component, latitude, longitude, altitude))
def gps_local_origin_set_encode(self, latitude, longitude, altitude):
'''
Once the MAV sets a new GPS-Local correspondence, this message
announces the origin (0,0,0) position
latitude : Latitude (WGS84), expressed as * 1E7 (int32_t)
longitude : Longitude (WGS84), expressed as * 1E7 (int32_t)
altitude : Altitude(WGS84), expressed as * 1000 (int32_t)
'''
msg = MAVLink_gps_local_origin_set_message(latitude, longitude, altitude)
msg.pack(self)
return msg
def gps_local_origin_set_send(self, latitude, longitude, altitude):
'''
Once the MAV sets a new GPS-Local correspondence, this message
announces the origin (0,0,0) position
latitude : Latitude (WGS84), expressed as * 1E7 (int32_t)
longitude : Longitude (WGS84), expressed as * 1E7 (int32_t)
altitude : Altitude(WGS84), expressed as * 1000 (int32_t)
'''
return self.send(self.gps_local_origin_set_encode(latitude, longitude, altitude))
def local_position_setpoint_set_encode(self, target_system, target_component, x, y, z, yaw):
'''
Set the setpoint for a local position controller. This is the position
in local coordinates the MAV should fly to. This
message is sent by the path/waypoint planner to the
onboard position controller. As some MAVs have a
degree of freedom in yaw (e.g. all
helicopters/quadrotors), the desired yaw angle is part
of the message.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
x : x position (float)
y : y position (float)
z : z position (float)
yaw : Desired yaw angle (float)
'''
msg = MAVLink_local_position_setpoint_set_message(target_system, target_component, x, y, z, yaw)
msg.pack(self)
return msg
def local_position_setpoint_set_send(self, target_system, target_component, x, y, z, yaw):
'''
Set the setpoint for a local position controller. This is the position
in local coordinates the MAV should fly to. This
message is sent by the path/waypoint planner to the
onboard position controller. As some MAVs have a
degree of freedom in yaw (e.g. all
helicopters/quadrotors), the desired yaw angle is part
of the message.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
x : x position (float)
y : y position (float)
z : z position (float)
yaw : Desired yaw angle (float)
'''
return self.send(self.local_position_setpoint_set_encode(target_system, target_component, x, y, z, yaw))
def local_position_setpoint_encode(self, x, y, z, yaw):
'''
Transmit the current local setpoint of the controller to other MAVs
(collision avoidance) and to the GCS.
x : x position (float)
y : y position (float)
z : z position (float)
yaw : Desired yaw angle (float)
'''
msg = MAVLink_local_position_setpoint_message(x, y, z, yaw)
msg.pack(self)
return msg
def local_position_setpoint_send(self, x, y, z, yaw):
'''
Transmit the current local setpoint of the controller to other MAVs
(collision avoidance) and to the GCS.
x : x position (float)
y : y position (float)
z : z position (float)
yaw : Desired yaw angle (float)
'''
return self.send(self.local_position_setpoint_encode(x, y, z, yaw))
def control_status_encode(self, position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw):
'''
position_fix : Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix (uint8_t)
vision_fix : Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix (uint8_t)
gps_fix : GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix (uint8_t)
ahrs_health : Attitude estimation health: 0: poor, 255: excellent (uint8_t)
control_att : 0: Attitude control disabled, 1: enabled (uint8_t)
control_pos_xy : 0: X, Y position control disabled, 1: enabled (uint8_t)
control_pos_z : 0: Z position control disabled, 1: enabled (uint8_t)
control_pos_yaw : 0: Yaw angle control disabled, 1: enabled (uint8_t)
'''
msg = MAVLink_control_status_message(position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw)
msg.pack(self)
return msg
def control_status_send(self, position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw):
'''
position_fix : Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix (uint8_t)
vision_fix : Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix (uint8_t)
gps_fix : GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix (uint8_t)
ahrs_health : Attitude estimation health: 0: poor, 255: excellent (uint8_t)
control_att : 0: Attitude control disabled, 1: enabled (uint8_t)
control_pos_xy : 0: X, Y position control disabled, 1: enabled (uint8_t)
control_pos_z : 0: Z position control disabled, 1: enabled (uint8_t)
control_pos_yaw : 0: Yaw angle control disabled, 1: enabled (uint8_t)
'''
return self.send(self.control_status_encode(position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw))
def safety_set_allowed_area_encode(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z):
'''
Set a safety zone (volume), which is defined by two corners of a cube.
This message can be used to tell the MAV which
setpoints/waypoints to accept and which to reject.
Safety areas are often enforced by national or
competition regulations.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t)
p1x : x position 1 / Latitude 1 (float)
p1y : y position 1 / Longitude 1 (float)
p1z : z position 1 / Altitude 1 (float)
p2x : x position 2 / Latitude 2 (float)
p2y : y position 2 / Longitude 2 (float)
p2z : z position 2 / Altitude 2 (float)
'''
msg = MAVLink_safety_set_allowed_area_message(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z)
msg.pack(self)
return msg
def safety_set_allowed_area_send(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z):
'''
Set a safety zone (volume), which is defined by two corners of a cube.
This message can be used to tell the MAV which
setpoints/waypoints to accept and which to reject.
Safety areas are often enforced by national or
competition regulations.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t)
p1x : x position 1 / Latitude 1 (float)
p1y : y position 1 / Longitude 1 (float)
p1z : z position 1 / Altitude 1 (float)
p2x : x position 2 / Latitude 2 (float)
p2y : y position 2 / Longitude 2 (float)
p2z : z position 2 / Altitude 2 (float)
'''
return self.send(self.safety_set_allowed_area_encode(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z))
def safety_allowed_area_encode(self, frame, p1x, p1y, p1z, p2x, p2y, p2z):
'''
Read out the safety zone the MAV currently assumes.
frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t)
p1x : x position 1 / Latitude 1 (float)
p1y : y position 1 / Longitude 1 (float)
p1z : z position 1 / Altitude 1 (float)
p2x : x position 2 / Latitude 2 (float)
p2y : y position 2 / Longitude 2 (float)
p2z : z position 2 / Altitude 2 (float)
'''
msg = MAVLink_safety_allowed_area_message(frame, p1x, p1y, p1z, p2x, p2y, p2z)
msg.pack(self)
return msg
def safety_allowed_area_send(self, frame, p1x, p1y, p1z, p2x, p2y, p2z):
'''
Read out the safety zone the MAV currently assumes.
frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t)
p1x : x position 1 / Latitude 1 (float)
p1y : y position 1 / Longitude 1 (float)
p1z : z position 1 / Altitude 1 (float)
p2x : x position 2 / Latitude 2 (float)
p2y : y position 2 / Longitude 2 (float)
p2z : z position 2 / Altitude 2 (float)
'''
return self.send(self.safety_allowed_area_encode(frame, p1x, p1y, p1z, p2x, p2y, p2z))
def set_roll_pitch_yaw_thrust_encode(self, target_system, target_component, roll, pitch, yaw, thrust):
'''
Set roll, pitch and yaw.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
roll : Desired roll angle in radians (float)
pitch : Desired pitch angle in radians (float)
yaw : Desired yaw angle in radians (float)
thrust : Collective thrust, normalized to 0 .. 1 (float)
'''
msg = MAVLink_set_roll_pitch_yaw_thrust_message(target_system, target_component, roll, pitch, yaw, thrust)
msg.pack(self)
return msg
def set_roll_pitch_yaw_thrust_send(self, target_system, target_component, roll, pitch, yaw, thrust):
'''
Set roll, pitch and yaw.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
roll : Desired roll angle in radians (float)
pitch : Desired pitch angle in radians (float)
yaw : Desired yaw angle in radians (float)
thrust : Collective thrust, normalized to 0 .. 1 (float)
'''
return self.send(self.set_roll_pitch_yaw_thrust_encode(target_system, target_component, roll, pitch, yaw, thrust))
def set_roll_pitch_yaw_speed_thrust_encode(self, target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust):
'''
Set roll, pitch and yaw.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
roll_speed : Desired roll angular speed in rad/s (float)
pitch_speed : Desired pitch angular speed in rad/s (float)
yaw_speed : Desired yaw angular speed in rad/s (float)
thrust : Collective thrust, normalized to 0 .. 1 (float)
'''
msg = MAVLink_set_roll_pitch_yaw_speed_thrust_message(target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust)
msg.pack(self)
return msg
def set_roll_pitch_yaw_speed_thrust_send(self, target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust):
'''
Set roll, pitch and yaw.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
roll_speed : Desired roll angular speed in rad/s (float)
pitch_speed : Desired pitch angular speed in rad/s (float)
yaw_speed : Desired yaw angular speed in rad/s (float)
thrust : Collective thrust, normalized to 0 .. 1 (float)
'''
return self.send(self.set_roll_pitch_yaw_speed_thrust_encode(target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust))
def roll_pitch_yaw_thrust_setpoint_encode(self, time_us, roll, pitch, yaw, thrust):
'''
Setpoint in roll, pitch, yaw currently active on the system.
time_us : Timestamp in micro seconds since unix epoch (uint64_t)
roll : Desired roll angle in radians (float)
pitch : Desired pitch angle in radians (float)
yaw : Desired yaw angle in radians (float)
thrust : Collective thrust, normalized to 0 .. 1 (float)
'''
msg = MAVLink_roll_pitch_yaw_thrust_setpoint_message(time_us, roll, pitch, yaw, thrust)
msg.pack(self)
return msg
def roll_pitch_yaw_thrust_setpoint_send(self, time_us, roll, pitch, yaw, thrust):
'''
Setpoint in roll, pitch, yaw currently active on the system.
time_us : Timestamp in micro seconds since unix epoch (uint64_t)
roll : Desired roll angle in radians (float)
pitch : Desired pitch angle in radians (float)
yaw : Desired yaw angle in radians (float)
thrust : Collective thrust, normalized to 0 .. 1 (float)
'''
return self.send(self.roll_pitch_yaw_thrust_setpoint_encode(time_us, roll, pitch, yaw, thrust))
def roll_pitch_yaw_speed_thrust_setpoint_encode(self, time_us, roll_speed, pitch_speed, yaw_speed, thrust):
'''
Setpoint in rollspeed, pitchspeed, yawspeed currently active on the
system.
time_us : Timestamp in micro seconds since unix epoch (uint64_t)
roll_speed : Desired roll angular speed in rad/s (float)
pitch_speed : Desired pitch angular speed in rad/s (float)
yaw_speed : Desired yaw angular speed in rad/s (float)
thrust : Collective thrust, normalized to 0 .. 1 (float)
'''
msg = MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message(time_us, roll_speed, pitch_speed, yaw_speed, thrust)
msg.pack(self)
return msg
def roll_pitch_yaw_speed_thrust_setpoint_send(self, time_us, roll_speed, pitch_speed, yaw_speed, thrust):
'''
Setpoint in rollspeed, pitchspeed, yawspeed currently active on the
system.
time_us : Timestamp in micro seconds since unix epoch (uint64_t)
roll_speed : Desired roll angular speed in rad/s (float)
pitch_speed : Desired pitch angular speed in rad/s (float)
yaw_speed : Desired yaw angular speed in rad/s (float)
thrust : Collective thrust, normalized to 0 .. 1 (float)
'''
return self.send(self.roll_pitch_yaw_speed_thrust_setpoint_encode(time_us, roll_speed, pitch_speed, yaw_speed, thrust))
def nav_controller_output_encode(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error):
'''
Outputs of the APM navigation controller. The primary use of this
message is to check the response and signs of the
controller before actual flight and to assist with
tuning controller parameters
nav_roll : Current desired roll in degrees (float)
nav_pitch : Current desired pitch in degrees (float)
nav_bearing : Current desired heading in degrees (int16_t)
target_bearing : Bearing to current waypoint/target in degrees (int16_t)
wp_dist : Distance to active waypoint in meters (uint16_t)
alt_error : Current altitude error in meters (float)
aspd_error : Current airspeed error in meters/second (float)
xtrack_error : Current crosstrack error on x-y plane in meters (float)
'''
msg = MAVLink_nav_controller_output_message(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error)
msg.pack(self)
return msg
def nav_controller_output_send(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error):
'''
Outputs of the APM navigation controller. The primary use of this
message is to check the response and signs of the
controller before actual flight and to assist with
tuning controller parameters
nav_roll : Current desired roll in degrees (float)
nav_pitch : Current desired pitch in degrees (float)
nav_bearing : Current desired heading in degrees (int16_t)
target_bearing : Bearing to current waypoint/target in degrees (int16_t)
wp_dist : Distance to active waypoint in meters (uint16_t)
alt_error : Current altitude error in meters (float)
aspd_error : Current airspeed error in meters/second (float)
xtrack_error : Current crosstrack error on x-y plane in meters (float)
'''
return self.send(self.nav_controller_output_encode(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error))
def position_target_encode(self, x, y, z, yaw):
'''
The goal position of the system. This position is the input to any
navigation or path planning algorithm and does NOT
represent the current controller setpoint.
x : x position (float)
y : y position (float)
z : z position (float)
yaw : yaw orientation in radians, 0 = NORTH (float)
'''
msg = MAVLink_position_target_message(x, y, z, yaw)
msg.pack(self)
return msg
def position_target_send(self, x, y, z, yaw):
'''
The goal position of the system. This position is the input to any
navigation or path planning algorithm and does NOT
represent the current controller setpoint.
x : x position (float)
y : y position (float)
z : z position (float)
yaw : yaw orientation in radians, 0 = NORTH (float)
'''
return self.send(self.position_target_encode(x, y, z, yaw))
def state_correction_encode(self, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr):
'''
Corrects the systems state by adding an error correction term to the
position and velocity, and by rotating the attitude by
a correction angle.
xErr : x position error (float)
yErr : y position error (float)
zErr : z position error (float)
rollErr : roll error (radians) (float)
pitchErr : pitch error (radians) (float)
yawErr : yaw error (radians) (float)
vxErr : x velocity (float)
vyErr : y velocity (float)
vzErr : z velocity (float)
'''
msg = MAVLink_state_correction_message(xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr)
msg.pack(self)
return msg
def state_correction_send(self, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr):
'''
Corrects the systems state by adding an error correction term to the
position and velocity, and by rotating the attitude by
a correction angle.
xErr : x position error (float)
yErr : y position error (float)
zErr : z position error (float)
rollErr : roll error (radians) (float)
pitchErr : pitch error (radians) (float)
yawErr : yaw error (radians) (float)
vxErr : x velocity (float)
vyErr : y velocity (float)
vzErr : z velocity (float)
'''
return self.send(self.state_correction_encode(xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr))
def set_altitude_encode(self, target, mode):
'''
target : The system setting the altitude (uint8_t)
mode : The new altitude in meters (uint32_t)
'''
msg = MAVLink_set_altitude_message(target, mode)
msg.pack(self)
return msg
def set_altitude_send(self, target, mode):
'''
target : The system setting the altitude (uint8_t)
mode : The new altitude in meters (uint32_t)
'''
return self.send(self.set_altitude_encode(target, mode))
def request_data_stream_encode(self, target_system, target_component, req_stream_id, req_message_rate, start_stop):
'''
target_system : The target requested to send the message stream. (uint8_t)
target_component : The target requested to send the message stream. (uint8_t)
req_stream_id : The ID of the requested message type (uint8_t)
req_message_rate : Update rate in Hertz (uint16_t)
start_stop : 1 to start sending, 0 to stop sending. (uint8_t)
'''
msg = MAVLink_request_data_stream_message(target_system, target_component, req_stream_id, req_message_rate, start_stop)
msg.pack(self)
return msg
def request_data_stream_send(self, target_system, target_component, req_stream_id, req_message_rate, start_stop):
'''
target_system : The target requested to send the message stream. (uint8_t)
target_component : The target requested to send the message stream. (uint8_t)
req_stream_id : The ID of the requested message type (uint8_t)
req_message_rate : Update rate in Hertz (uint16_t)
start_stop : 1 to start sending, 0 to stop sending. (uint8_t)
'''
return self.send(self.request_data_stream_encode(target_system, target_component, req_stream_id, req_message_rate, start_stop))
def hil_state_encode(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc):
'''
This packet is useful for high throughput applications
such as hardware in the loop simulations.
usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
roll : Roll angle (rad) (float)
pitch : Pitch angle (rad) (float)
yaw : Yaw angle (rad) (float)
rollspeed : Roll angular speed (rad/s) (float)
pitchspeed : Pitch angular speed (rad/s) (float)
yawspeed : Yaw angular speed (rad/s) (float)
lat : Latitude, expressed as * 1E7 (int32_t)
lon : Longitude, expressed as * 1E7 (int32_t)
alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t)
vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t)
vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t)
vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t)
xacc : X acceleration (mg) (int16_t)
yacc : Y acceleration (mg) (int16_t)
zacc : Z acceleration (mg) (int16_t)
'''
msg = MAVLink_hil_state_message(usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc)
msg.pack(self)
return msg
def hil_state_send(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc):
'''
This packet is useful for high throughput applications
such as hardware in the loop simulations.
usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
roll : Roll angle (rad) (float)
pitch : Pitch angle (rad) (float)
yaw : Yaw angle (rad) (float)
rollspeed : Roll angular speed (rad/s) (float)
pitchspeed : Pitch angular speed (rad/s) (float)
yawspeed : Yaw angular speed (rad/s) (float)
lat : Latitude, expressed as * 1E7 (int32_t)
lon : Longitude, expressed as * 1E7 (int32_t)
alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t)
vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t)
vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t)
vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t)
xacc : X acceleration (mg) (int16_t)
yacc : Y acceleration (mg) (int16_t)
zacc : Z acceleration (mg) (int16_t)
'''
return self.send(self.hil_state_encode(usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc))
def hil_controls_encode(self, time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode):
'''
Hardware in the loop control outputs
time_us : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
roll_ailerons : Control output -3 .. 1 (float)
pitch_elevator : Control output -1 .. 1 (float)
yaw_rudder : Control output -1 .. 1 (float)
throttle : Throttle 0 .. 1 (float)
mode : System mode (MAV_MODE) (uint8_t)
nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t)
'''
msg = MAVLink_hil_controls_message(time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode)
msg.pack(self)
return msg
def hil_controls_send(self, time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode):
'''
Hardware in the loop control outputs
time_us : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
roll_ailerons : Control output -3 .. 1 (float)
pitch_elevator : Control output -1 .. 1 (float)
yaw_rudder : Control output -1 .. 1 (float)
throttle : Throttle 0 .. 1 (float)
mode : System mode (MAV_MODE) (uint8_t)
nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t)
'''
return self.send(self.hil_controls_encode(time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode))
def manual_control_encode(self, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual):
'''
target : The system to be controlled (uint8_t)
roll : roll (float)
pitch : pitch (float)
yaw : yaw (float)
thrust : thrust (float)
roll_manual : roll control enabled auto:0, manual:1 (uint8_t)
pitch_manual : pitch auto:0, manual:1 (uint8_t)
yaw_manual : yaw auto:0, manual:1 (uint8_t)
thrust_manual : thrust auto:0, manual:1 (uint8_t)
'''
msg = MAVLink_manual_control_message(target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual)
msg.pack(self)
return msg
def manual_control_send(self, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual):
'''
target : The system to be controlled (uint8_t)
roll : roll (float)
pitch : pitch (float)
yaw : yaw (float)
thrust : thrust (float)
roll_manual : roll control enabled auto:0, manual:1 (uint8_t)
pitch_manual : pitch auto:0, manual:1 (uint8_t)
yaw_manual : yaw auto:0, manual:1 (uint8_t)
thrust_manual : thrust auto:0, manual:1 (uint8_t)
'''
return self.send(self.manual_control_encode(target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual))
def rc_channels_override_encode(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw):
'''
The RAW values of the RC channels sent to the MAV to override info
received from the RC radio. A value of -1 means no
change to that channel. A value of 0 means control of
that channel should be released back to the RC radio.
The standard PPM modulation is as follows: 1000
microseconds: 0%, 2000 microseconds: 100%. Individual
receivers/transmitters might violate this
specification.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
chan1_raw : RC channel 1 value, in microseconds (uint16_t)
chan2_raw : RC channel 2 value, in microseconds (uint16_t)
chan3_raw : RC channel 3 value, in microseconds (uint16_t)
chan4_raw : RC channel 4 value, in microseconds (uint16_t)
chan5_raw : RC channel 5 value, in microseconds (uint16_t)
chan6_raw : RC channel 6 value, in microseconds (uint16_t)
chan7_raw : RC channel 7 value, in microseconds (uint16_t)
chan8_raw : RC channel 8 value, in microseconds (uint16_t)
'''
msg = MAVLink_rc_channels_override_message(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw)
msg.pack(self)
return msg
def rc_channels_override_send(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw):
'''
The RAW values of the RC channels sent to the MAV to override info
received from the RC radio. A value of -1 means no
change to that channel. A value of 0 means control of
that channel should be released back to the RC radio.
The standard PPM modulation is as follows: 1000
microseconds: 0%, 2000 microseconds: 100%. Individual
receivers/transmitters might violate this
specification.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
chan1_raw : RC channel 1 value, in microseconds (uint16_t)
chan2_raw : RC channel 2 value, in microseconds (uint16_t)
chan3_raw : RC channel 3 value, in microseconds (uint16_t)
chan4_raw : RC channel 4 value, in microseconds (uint16_t)
chan5_raw : RC channel 5 value, in microseconds (uint16_t)
chan6_raw : RC channel 6 value, in microseconds (uint16_t)
chan7_raw : RC channel 7 value, in microseconds (uint16_t)
chan8_raw : RC channel 8 value, in microseconds (uint16_t)
'''
return self.send(self.rc_channels_override_encode(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw))
def global_position_int_encode(self, lat, lon, alt, vx, vy, vz):
'''
The filtered global position (e.g. fused GPS and accelerometers). The
position is in GPS-frame (right-handed, Z-up)
lat : Latitude, expressed as * 1E7 (int32_t)
lon : Longitude, expressed as * 1E7 (int32_t)
alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t)
vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t)
vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t)
vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t)
'''
msg = MAVLink_global_position_int_message(lat, lon, alt, vx, vy, vz)
msg.pack(self)
return msg
def global_position_int_send(self, lat, lon, alt, vx, vy, vz):
'''
The filtered global position (e.g. fused GPS and accelerometers). The
position is in GPS-frame (right-handed, Z-up)
lat : Latitude, expressed as * 1E7 (int32_t)
lon : Longitude, expressed as * 1E7 (int32_t)
alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t)
vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t)
vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t)
vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t)
'''
return self.send(self.global_position_int_encode(lat, lon, alt, vx, vy, vz))
def vfr_hud_encode(self, airspeed, groundspeed, heading, throttle, alt, climb):
'''
Metrics typically displayed on a HUD for fixed wing aircraft
airspeed : Current airspeed in m/s (float)
groundspeed : Current ground speed in m/s (float)
heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t)
throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t)
alt : Current altitude (MSL), in meters (float)
climb : Current climb rate in meters/second (float)
'''
msg = MAVLink_vfr_hud_message(airspeed, groundspeed, heading, throttle, alt, climb)
msg.pack(self)
return msg
def vfr_hud_send(self, airspeed, groundspeed, heading, throttle, alt, climb):
'''
Metrics typically displayed on a HUD for fixed wing aircraft
airspeed : Current airspeed in m/s (float)
groundspeed : Current ground speed in m/s (float)
heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t)
throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t)
alt : Current altitude (MSL), in meters (float)
climb : Current climb rate in meters/second (float)
'''
return self.send(self.vfr_hud_encode(airspeed, groundspeed, heading, throttle, alt, climb))
def command_encode(self, target_system, target_component, command, confirmation, param1, param2, param3, param4):
'''
Send a command with up to four parameters to the MAV
target_system : System which should execute the command (uint8_t)
target_component : Component which should execute the command, 0 for all components (uint8_t)
command : Command ID, as defined by MAV_CMD enum. (uint8_t)
confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t)
param1 : Parameter 1, as defined by MAV_CMD enum. (float)
param2 : Parameter 2, as defined by MAV_CMD enum. (float)
param3 : Parameter 3, as defined by MAV_CMD enum. (float)
param4 : Parameter 4, as defined by MAV_CMD enum. (float)
'''
msg = MAVLink_command_message(target_system, target_component, command, confirmation, param1, param2, param3, param4)
msg.pack(self)
return msg
def command_send(self, target_system, target_component, command, confirmation, param1, param2, param3, param4):
'''
Send a command with up to four parameters to the MAV
target_system : System which should execute the command (uint8_t)
target_component : Component which should execute the command, 0 for all components (uint8_t)
command : Command ID, as defined by MAV_CMD enum. (uint8_t)
confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t)
param1 : Parameter 1, as defined by MAV_CMD enum. (float)
param2 : Parameter 2, as defined by MAV_CMD enum. (float)
param3 : Parameter 3, as defined by MAV_CMD enum. (float)
param4 : Parameter 4, as defined by MAV_CMD enum. (float)
'''
return self.send(self.command_encode(target_system, target_component, command, confirmation, param1, param2, param3, param4))
def command_ack_encode(self, command, result):
'''
Report status of a command. Includes feedback wether the command was
executed
command : Current airspeed in m/s (float)
result : 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION (float)
'''
msg = MAVLink_command_ack_message(command, result)
msg.pack(self)
return msg
def command_ack_send(self, command, result):
'''
Report status of a command. Includes feedback wether the command was
executed
command : Current airspeed in m/s (float)
result : 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION (float)
'''
return self.send(self.command_ack_encode(command, result))
def optical_flow_encode(self, time, sensor_id, flow_x, flow_y, quality, ground_distance):
'''
Optical flow from a flow sensor (e.g. optical mouse sensor)
time : Timestamp (UNIX) (uint64_t)
sensor_id : Sensor ID (uint8_t)
flow_x : Flow in pixels in x-sensor direction (int16_t)
flow_y : Flow in pixels in y-sensor direction (int16_t)
quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t)
ground_distance : Ground distance in meters (float)
'''
msg = MAVLink_optical_flow_message(time, sensor_id, flow_x, flow_y, quality, ground_distance)
msg.pack(self)
return msg
def optical_flow_send(self, time, sensor_id, flow_x, flow_y, quality, ground_distance):
'''
Optical flow from a flow sensor (e.g. optical mouse sensor)
time : Timestamp (UNIX) (uint64_t)
sensor_id : Sensor ID (uint8_t)
flow_x : Flow in pixels in x-sensor direction (int16_t)
flow_y : Flow in pixels in y-sensor direction (int16_t)
quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t)
ground_distance : Ground distance in meters (float)
'''
return self.send(self.optical_flow_encode(time, sensor_id, flow_x, flow_y, quality, ground_distance))
def object_detection_event_encode(self, time, object_id, type, name, quality, bearing, distance):
'''
Object has been detected
time : Timestamp in milliseconds since system boot (uint32_t)
object_id : Object ID (uint16_t)
type : Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal (uint8_t)
name : Name of the object as defined by the detector (char)
quality : Detection quality / confidence. 0: bad, 255: maximum confidence (uint8_t)
bearing : Angle of the object with respect to the body frame in NED coordinates in radians. 0: front (float)
distance : Ground distance in meters (float)
'''
msg = MAVLink_object_detection_event_message(time, object_id, type, name, quality, bearing, distance)
msg.pack(self)
return msg
def object_detection_event_send(self, time, object_id, type, name, quality, bearing, distance):
'''
Object has been detected
time : Timestamp in milliseconds since system boot (uint32_t)
object_id : Object ID (uint16_t)
type : Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal (uint8_t)
name : Name of the object as defined by the detector (char)
quality : Detection quality / confidence. 0: bad, 255: maximum confidence (uint8_t)
bearing : Angle of the object with respect to the body frame in NED coordinates in radians. 0: front (float)
distance : Ground distance in meters (float)
'''
return self.send(self.object_detection_event_encode(time, object_id, type, name, quality, bearing, distance))
def debug_vect_encode(self, name, usec, x, y, z):
'''
name : Name (char)
usec : Timestamp (uint64_t)
x : x (float)
y : y (float)
z : z (float)
'''
msg = MAVLink_debug_vect_message(name, usec, x, y, z)
msg.pack(self)
return msg
def debug_vect_send(self, name, usec, x, y, z):
'''
name : Name (char)
usec : Timestamp (uint64_t)
x : x (float)
y : y (float)
z : z (float)
'''
return self.send(self.debug_vect_encode(name, usec, x, y, z))
def named_value_float_encode(self, name, value):
'''
Send a key-value pair as float. The use of this message is discouraged
for normal packets, but a quite efficient way for
testing new messages and getting experimental debug
output.
name : Name of the debug variable (char)
value : Floating point value (float)
'''
msg = MAVLink_named_value_float_message(name, value)
msg.pack(self)
return msg
def named_value_float_send(self, name, value):
'''
Send a key-value pair as float. The use of this message is discouraged
for normal packets, but a quite efficient way for
testing new messages and getting experimental debug
output.
name : Name of the debug variable (char)
value : Floating point value (float)
'''
return self.send(self.named_value_float_encode(name, value))
def named_value_int_encode(self, name, value):
'''
Send a key-value pair as integer. The use of this message is
discouraged for normal packets, but a quite efficient
way for testing new messages and getting experimental
debug output.
name : Name of the debug variable (char)
value : Signed integer value (int32_t)
'''
msg = MAVLink_named_value_int_message(name, value)
msg.pack(self)
return msg
def named_value_int_send(self, name, value):
'''
Send a key-value pair as integer. The use of this message is
discouraged for normal packets, but a quite efficient
way for testing new messages and getting experimental
debug output.
name : Name of the debug variable (char)
value : Signed integer value (int32_t)
'''
return self.send(self.named_value_int_encode(name, value))
def statustext_encode(self, severity, text):
'''
Status text message. These messages are printed in yellow in the COMM
console of QGroundControl. WARNING: They consume quite
some bandwidth, so use only for important status and
error messages. If implemented wisely, these messages
are buffered on the MCU and sent only at a limited
rate (e.g. 10 Hz).
severity : Severity of status, 0 = info message, 255 = critical fault (uint8_t)
text : Status text message, without null termination character (int8_t)
'''
msg = MAVLink_statustext_message(severity, text)
msg.pack(self)
return msg
def statustext_send(self, severity, text):
'''
Status text message. These messages are printed in yellow in the COMM
console of QGroundControl. WARNING: They consume quite
some bandwidth, so use only for important status and
error messages. If implemented wisely, these messages
are buffered on the MCU and sent only at a limited
rate (e.g. 10 Hz).
severity : Severity of status, 0 = info message, 255 = critical fault (uint8_t)
text : Status text message, without null termination character (int8_t)
'''
return self.send(self.statustext_encode(severity, text))
def debug_encode(self, ind, value):
'''
Send a debug value. The index is used to discriminate between values.
These values show up in the plot of QGroundControl as
DEBUG N.
ind : index of debug variable (uint8_t)
value : DEBUG value (float)
'''
msg = MAVLink_debug_message(ind, value)
msg.pack(self)
return msg
def debug_send(self, ind, value):
'''
Send a debug value. The index is used to discriminate between values.
These values show up in the plot of QGroundControl as
DEBUG N.
ind : index of debug variable (uint8_t)
value : DEBUG value (float)
'''
return self.send(self.debug_encode(ind, value))