aboutsummaryrefslogtreecommitdiff
path: root/mavlink/share/pyshared/pymavlink
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-07-14 10:38:34 +0200
committerLorenz Meier <lm@inf.ethz.ch>2014-07-14 10:38:34 +0200
commit51a4ef5de1bc542ac4f7072d95250cd62ea73ed6 (patch)
treeb71db4faea6a0ac39e4fa28481421a2acc13a896 /mavlink/share/pyshared/pymavlink
parent5e0911046173e01a6c66b91d3e38212e093159d0 (diff)
parentddc8f1fa5f5b88549af5e4f5f46c751a5f3af3ce (diff)
downloadpx4-firmware-sbus2_sensors.tar.gz
px4-firmware-sbus2_sensors.tar.bz2
px4-firmware-sbus2_sensors.zip
merged upstream/master into sbus2_sensorssbus2_sensors
Diffstat (limited to 'mavlink/share/pyshared/pymavlink')
-rw-r--r--mavlink/share/pyshared/pymavlink/.gitignore13
-rw-r--r--mavlink/share/pyshared/pymavlink/APM_Mavtest/APM_Mavtest.pde55
-rw-r--r--mavlink/share/pyshared/pymavlink/README.txt4
-rw-r--r--mavlink/share/pyshared/pymavlink/examples/apmsetrate.py67
-rw-r--r--mavlink/share/pyshared/pymavlink/examples/bwtest.py58
-rw-r--r--mavlink/share/pyshared/pymavlink/examples/flightmodes.py52
-rw-r--r--mavlink/share/pyshared/pymavlink/examples/flighttime.py59
-rw-r--r--mavlink/share/pyshared/pymavlink/examples/gpslock.py68
-rw-r--r--mavlink/share/pyshared/pymavlink/examples/magfit.py138
-rw-r--r--mavlink/share/pyshared/pymavlink/examples/magfit_delta.py145
-rw-r--r--mavlink/share/pyshared/pymavlink/examples/magfit_gps.py159
-rw-r--r--mavlink/share/pyshared/pymavlink/examples/magtest.py120
-rw-r--r--mavlink/share/pyshared/pymavlink/examples/mavgraph.py196
-rw-r--r--mavlink/share/pyshared/pymavlink/examples/mavlogdump.py67
-rw-r--r--mavlink/share/pyshared/pymavlink/examples/mavparms.py48
-rw-r--r--mavlink/share/pyshared/pymavlink/examples/mavtest.py41
-rw-r--r--mavlink/share/pyshared/pymavlink/examples/mavtester.py43
-rw-r--r--mavlink/share/pyshared/pymavlink/examples/mavtogpx.py83
-rw-r--r--mavlink/share/pyshared/pymavlink/examples/rotmat.py269
-rw-r--r--mavlink/share/pyshared/pymavlink/examples/sigloss.py57
-rw-r--r--mavlink/share/pyshared/pymavlink/examples/wptogpx.py69
-rw-r--r--mavlink/share/pyshared/pymavlink/fgFDM.py209
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/.gitignore1
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/checksum.h89
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/mavlink_helpers.h488
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/mavlink_types.h300
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/protocol.h319
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/mavlink.h27
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/mavlink_msg_test_types.h610
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/test.h53
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/testsuite.h120
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/version.h12
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/checksum.h89
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_helpers.h507
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_protobuf_manager.hpp377
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_types.h158
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/pixhawk/pixhawk.pb.h3663
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/protocol.h322
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/mavlink.h27
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/mavlink_msg_test_types.h610
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/test.h53
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/testsuite.h120
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/version.h12
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/src_v1.0/pixhawk/pixhawk.pb.cc5431
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/test/posix/.gitignore3
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/test/posix/testmav.c159
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/test/windows/stdafx.cpp8
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/test/windows/stdafx.h15
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/test/windows/targetver.h8
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/test/windows/testmav.cpp154
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/gen_MatrixPilot.py93
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/gen_all.py44
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/gen_all.sh12
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/mavgen.py82
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/mavgen_c.py581
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/mavgen_python.py455
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/mavparse.py372
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/mavtemplate.py121
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/mavtestgen.py142
-rw-r--r--mavlink/share/pyshared/pymavlink/mavextra.py154
-rw-r--r--mavlink/share/pyshared/pymavlink/mavlink.py4930
-rw-r--r--mavlink/share/pyshared/pymavlink/mavlinkv10.py5394
-rw-r--r--mavlink/share/pyshared/pymavlink/mavutil.py678
-rw-r--r--mavlink/share/pyshared/pymavlink/mavwp.py200
-rw-r--r--mavlink/share/pyshared/pymavlink/scanwin32.py236
-rw-r--r--mavlink/share/pyshared/pymavlink/tools/images/gtk-quit.gifbin1049 -> 0 bytes
-rw-r--r--mavlink/share/pyshared/pymavlink/tools/images/media-playback-pause.gifbin314 -> 0 bytes
-rw-r--r--mavlink/share/pyshared/pymavlink/tools/images/media-playback-start.gifbin308 -> 0 bytes
-rw-r--r--mavlink/share/pyshared/pymavlink/tools/images/media-playback-stop.gifbin305 -> 0 bytes
-rw-r--r--mavlink/share/pyshared/pymavlink/tools/images/media-seek-backward.gifbin319 -> 0 bytes
-rw-r--r--mavlink/share/pyshared/pymavlink/tools/images/media-seek-forward.gifbin322 -> 0 bytes
-rw-r--r--mavlink/share/pyshared/pymavlink/tools/images/player_end.gifbin555 -> 0 bytes
-rw-r--r--mavlink/share/pyshared/pymavlink/tools/mavplayback.py246
73 files changed, 0 insertions, 29495 deletions
diff --git a/mavlink/share/pyshared/pymavlink/.gitignore b/mavlink/share/pyshared/pymavlink/.gitignore
deleted file mode 100644
index 3d395ecda..000000000
--- a/mavlink/share/pyshared/pymavlink/.gitignore
+++ /dev/null
@@ -1,13 +0,0 @@
-apidocs/
-*.zip
-*.pyc
-send.sh
-generator/C/include/ardupilotmega
-generator/C/include/common
-generator/C/include/pixhawk
-generator/C/include/minimal
-generator/C/include/ualberta
-generator/C/include/slugs
-testmav0.9*
-testmav1.0*
-Debug/
diff --git a/mavlink/share/pyshared/pymavlink/APM_Mavtest/APM_Mavtest.pde b/mavlink/share/pyshared/pymavlink/APM_Mavtest/APM_Mavtest.pde
deleted file mode 100644
index b903b5c16..000000000
--- a/mavlink/share/pyshared/pymavlink/APM_Mavtest/APM_Mavtest.pde
+++ /dev/null
@@ -1,55 +0,0 @@
-/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
-
-/*
- send all possible mavlink messages
- Andrew Tridgell July 2011
-*/
-
-// AVR runtime
-#include <avr/io.h>
-#include <avr/eeprom.h>
-#include <avr/pgmspace.h>
-#include <math.h>
-
-// Libraries
-#include <FastSerial.h>
-#include <AP_Common.h>
-#include <GCS_MAVLink.h>
-#include "mavtest.h"
-
-FastSerialPort0(Serial); // FTDI/console
-FastSerialPort1(Serial1); // GPS port
-FastSerialPort3(Serial3); // Telemetry port
-
-#define SERIAL0_BAUD 115200
-#define SERIAL3_BAUD 115200
-
-void setup() {
- Serial.begin(SERIAL0_BAUD, 128, 128);
- Serial3.begin(SERIAL3_BAUD, 128, 128);
- mavlink_comm_0_port = &Serial;
- mavlink_comm_1_port = &Serial3;
-}
-
-
-
-void loop()
-{
- Serial.println("Starting MAVLink test generator\n");
- while (1) {
- mavlink_msg_heartbeat_send(
- MAVLINK_COMM_0,
- mavlink_system.type,
- MAV_AUTOPILOT_ARDUPILOTMEGA);
-
- mavlink_msg_heartbeat_send(
- MAVLINK_COMM_1,
- mavlink_system.type,
- MAV_AUTOPILOT_ARDUPILOTMEGA);
-
- mavtest_generate_outputs(MAVLINK_COMM_0);
- mavtest_generate_outputs(MAVLINK_COMM_1);
- delay(500);
- }
-}
-
diff --git a/mavlink/share/pyshared/pymavlink/README.txt b/mavlink/share/pyshared/pymavlink/README.txt
deleted file mode 100644
index 386013e11..000000000
--- a/mavlink/share/pyshared/pymavlink/README.txt
+++ /dev/null
@@ -1,4 +0,0 @@
-This is a python implementation of the MAVLink protocol.
-
-Please see http://www.qgroundcontrol.org/mavlink/pymavlink for
-documentation
diff --git a/mavlink/share/pyshared/pymavlink/examples/apmsetrate.py b/mavlink/share/pyshared/pymavlink/examples/apmsetrate.py
deleted file mode 100644
index d7d82256c..000000000
--- a/mavlink/share/pyshared/pymavlink/examples/apmsetrate.py
+++ /dev/null
@@ -1,67 +0,0 @@
-#!/usr/bin/env python
-
-'''
-set stream rate on an APM
-'''
-
-import sys, struct, time, os
-
-# allow import from the parent directory, where mavlink.py is
-sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..'))
-
-from optparse import OptionParser
-parser = OptionParser("apmsetrate.py [options]")
-
-parser.add_option("--baudrate", dest="baudrate", type='int',
- help="master port baud rate", default=115200)
-parser.add_option("--device", dest="device", default=None, help="serial device")
-parser.add_option("--rate", dest="rate", default=4, type='int', help="requested stream rate")
-parser.add_option("--source-system", dest='SOURCE_SYSTEM', type='int',
- default=255, help='MAVLink source system for this GCS')
-parser.add_option("--showmessages", dest="showmessages", action='store_true',
- help="show incoming messages", default=False)
-parser.add_option("--mav10", action='store_true', default=False, help="Use MAVLink protocol 1.0")
-(opts, args) = parser.parse_args()
-
-if opts.mav10:
- os.environ['MAVLINK10'] = '1'
- import mavlink10 as mavlink
-else:
- import mavlink
-import mavutil
-
-if opts.device is None:
- print("You must specify a serial device")
- sys.exit(1)
-
-def wait_heartbeat(m):
- '''wait for a heartbeat so we know the target system IDs'''
- print("Waiting for APM heartbeat")
- m.wait_heartbeat()
- print("Heartbeat from APM (system %u component %u)" % (m.target_system, m.target_system))
-
-def show_messages(m):
- '''show incoming mavlink messages'''
- while True:
- msg = m.recv_match(blocking=True)
- if not msg:
- return
- if msg.get_type() == "BAD_DATA":
- if mavutil.all_printable(msg.data):
- sys.stdout.write(msg.data)
- sys.stdout.flush()
- else:
- print(msg)
-
-# create a mavlink serial instance
-master = mavutil.mavlink_connection(opts.device, baud=opts.baudrate)
-
-# wait for the heartbeat msg to find the system ID
-wait_heartbeat(master)
-
-print("Sending all stream request for rate %u" % opts.rate)
-for i in range(0, 3):
- master.mav.request_data_stream_send(master.target_system, master.target_component,
- mavlink.MAV_DATA_STREAM_ALL, opts.rate, 1)
-if opts.showmessages:
- show_messages(master)
diff --git a/mavlink/share/pyshared/pymavlink/examples/bwtest.py b/mavlink/share/pyshared/pymavlink/examples/bwtest.py
deleted file mode 100644
index de56d4f8c..000000000
--- a/mavlink/share/pyshared/pymavlink/examples/bwtest.py
+++ /dev/null
@@ -1,58 +0,0 @@
-#!/usr/bin/env python
-
-'''
-check bandwidth of link
-'''
-
-import sys, struct, time, os
-
-# allow import from the parent directory, where mavlink.py is
-sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..'))
-
-import mavutil
-
-from optparse import OptionParser
-parser = OptionParser("bwtest.py [options]")
-
-parser.add_option("--baudrate", dest="baudrate", type='int',
- help="master port baud rate", default=115200)
-parser.add_option("--device", dest="device", default=None, help="serial device")
-(opts, args) = parser.parse_args()
-
-if opts.device is None:
- print("You must specify a serial device")
- sys.exit(1)
-
-# create a mavlink serial instance
-master = mavutil.mavlink_connection(opts.device, baud=opts.baudrate)
-
-t1 = time.time()
-
-counts = {}
-
-bytes_sent = 0
-bytes_recv = 0
-
-while True:
- master.mav.heartbeat_send(1, 1)
- master.mav.sys_status_send(1, 2, 3, 4, 5, 6, 7)
- master.mav.gps_raw_send(1, 2, 3, 4, 5, 6, 7, 8, 9)
- master.mav.attitude_send(1, 2, 3, 4, 5, 6, 7)
- master.mav.vfr_hud_send(1, 2, 3, 4, 5, 6)
- while master.port.inWaiting() > 0:
- m = master.recv_msg()
- if m == None: break
- if m.get_type() not in counts:
- counts[m.get_type()] = 0
- counts[m.get_type()] += 1
- t2 = time.time()
- if t2 - t1 > 1.0:
- print("%u sent, %u received, %u errors bwin=%.1f kB/s bwout=%.1f kB/s" % (
- master.mav.total_packets_sent,
- master.mav.total_packets_received,
- master.mav.total_receive_errors,
- 0.001*(master.mav.total_bytes_received-bytes_recv)/(t2-t1),
- 0.001*(master.mav.total_bytes_sent-bytes_sent)/(t2-t1)))
- bytes_sent = master.mav.total_bytes_sent
- bytes_recv = master.mav.total_bytes_received
- t1 = t2
diff --git a/mavlink/share/pyshared/pymavlink/examples/flightmodes.py b/mavlink/share/pyshared/pymavlink/examples/flightmodes.py
deleted file mode 100644
index 03d7e2c47..000000000
--- a/mavlink/share/pyshared/pymavlink/examples/flightmodes.py
+++ /dev/null
@@ -1,52 +0,0 @@
-#!/usr/bin/env python
-
-'''
-show changes in flight modes
-'''
-
-import sys, time, os
-
-# allow import from the parent directory, where mavlink.py is
-sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..'))
-
-from optparse import OptionParser
-parser = OptionParser("flightmodes.py [options]")
-parser.add_option("--mav10", action='store_true', default=False, help="Use MAVLink protocol 1.0")
-
-(opts, args) = parser.parse_args()
-
-if opts.mav10:
- os.environ['MAVLINK10'] = '1'
-import mavutil
-
-if len(args) < 1:
- print("Usage: flightmodes.py [options] <LOGFILE...>")
- sys.exit(1)
-
-def flight_modes(logfile):
- '''show flight modes for a log file'''
- print("Processing log %s" % filename)
- mlog = mavutil.mavlink_connection(filename)
-
- mode = -1
- nav_mode = -1
-
- filesize = os.path.getsize(filename)
-
- while True:
- m = mlog.recv_match(type='SYS_STATUS',
- condition='SYS_STATUS.mode != %u or SYS_STATUS.nav_mode != %u' % (mode, nav_mode))
- if m is None:
- return
- mode = m.mode
- nav_mode = m.nav_mode
- pct = (100.0 * mlog.f.tell()) / filesize
- print('%s MAV.flightmode=%-12s mode=%u nav_mode=%u (MAV.timestamp=%u %u%%)' % (
- time.asctime(time.localtime(m._timestamp)),
- mlog.flightmode,
- mode, nav_mode, m._timestamp, pct))
-
-for filename in args:
- flight_modes(filename)
-
-
diff --git a/mavlink/share/pyshared/pymavlink/examples/flighttime.py b/mavlink/share/pyshared/pymavlink/examples/flighttime.py
deleted file mode 100644
index 81cd38c94..000000000
--- a/mavlink/share/pyshared/pymavlink/examples/flighttime.py
+++ /dev/null
@@ -1,59 +0,0 @@
-#!/usr/bin/env python
-
-'''
-work out total flight time for a mavlink log
-'''
-
-import sys, time, os
-
-# allow import from the parent directory, where mavlink.py is
-sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..'))
-
-from optparse import OptionParser
-parser = OptionParser("flighttime.py [options]")
-parser.add_option("--mav10", action='store_true', default=False, help="Use MAVLink protocol 1.0")
-
-(opts, args) = parser.parse_args()
-
-if opts.mav10:
- os.environ['MAVLINK10'] = '1'
-import mavutil
-
-if len(args) < 1:
- print("Usage: flighttime.py [options] <LOGFILE...>")
- sys.exit(1)
-
-def flight_time(logfile):
- '''work out flight time for a log file'''
- print("Processing log %s" % filename)
- mlog = mavutil.mavlink_connection(filename)
-
- in_air = False
- start_time = 0.0
- total_time = 0.0
- t = None
-
- while True:
- m = mlog.recv_match(type='VFR_HUD')
- if m is None:
- if in_air:
- total_time += time.mktime(t) - start_time
- if total_time > 0:
- print("Flight time : %u:%02u" % (int(total_time)/60, int(total_time)%60))
- return total_time
- t = time.localtime(m._timestamp)
- if m.groundspeed > 3.0 and not in_air:
- print("In air at %s" % time.asctime(t))
- in_air = True
- start_time = time.mktime(t)
- elif m.groundspeed < 3.0 and in_air:
- print("On ground at %s" % time.asctime(t))
- in_air = False
- total_time += time.mktime(t) - start_time
- return total_time
-
-total = 0.0
-for filename in args:
- total += flight_time(filename)
-
-print("Total time in air: %u:%02u" % (int(total)/60, int(total)%60))
diff --git a/mavlink/share/pyshared/pymavlink/examples/gpslock.py b/mavlink/share/pyshared/pymavlink/examples/gpslock.py
deleted file mode 100644
index f15b29072..000000000
--- a/mavlink/share/pyshared/pymavlink/examples/gpslock.py
+++ /dev/null
@@ -1,68 +0,0 @@
-#!/usr/bin/env python
-
-'''
-show GPS lock events in a MAVLink log
-'''
-
-import sys, time, os
-
-# allow import from the parent directory, where mavlink.py is
-sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..'))
-
-from optparse import OptionParser
-parser = OptionParser("gpslock.py [options]")
-parser.add_option("--mav10", action='store_true', default=False, help="Use MAVLink protocol 1.0")
-
-(opts, args) = parser.parse_args()
-
-if opts.mav10:
- os.environ['MAVLINK10'] = '1'
-import mavutil
-
-if len(args) < 1:
- print("Usage: gpslock.py [options] <LOGFILE...>")
- sys.exit(1)
-
-def lock_time(logfile):
- '''work out gps lock times for a log file'''
- print("Processing log %s" % filename)
- mlog = mavutil.mavlink_connection(filename)
-
- locked = False
- start_time = 0.0
- total_time = 0.0
- t = None
- m = mlog.recv_match(type='GPS_RAW')
- unlock_time = time.mktime(time.localtime(m._timestamp))
-
- while True:
- m = mlog.recv_match(type='GPS_RAW')
- if m is None:
- if locked:
- total_time += time.mktime(t) - start_time
- if total_time > 0:
- print("Lock time : %u:%02u" % (int(total_time)/60, int(total_time)%60))
- return total_time
- t = time.localtime(m._timestamp)
- if m.fix_type == 2 and not locked:
- print("Locked at %s after %u seconds" % (time.asctime(t),
- time.mktime(t) - unlock_time))
- locked = True
- start_time = time.mktime(t)
- elif m.fix_type == 1 and locked:
- print("Lost GPS lock at %s" % time.asctime(t))
- locked = False
- total_time += time.mktime(t) - start_time
- unlock_time = time.mktime(t)
- elif m.fix_type == 0 and locked:
- print("Lost protocol lock at %s" % time.asctime(t))
- locked = False
- total_time += time.mktime(t) - start_time
- unlock_time = time.mktime(t)
- return total_time
-
-total = 0.0
-for filename in args:
- total += lock_time(filename)
-
-print("Total time locked: %u:%02u" % (int(total)/60, int(total)%60))
diff --git a/mavlink/share/pyshared/pymavlink/examples/magfit.py b/mavlink/share/pyshared/pymavlink/examples/magfit.py
deleted file mode 100644
index 7bfda796b..000000000
--- a/mavlink/share/pyshared/pymavlink/examples/magfit.py
+++ /dev/null
@@ -1,138 +0,0 @@
-#!/usr/bin/env python
-
-'''
-fit best estimate of magnetometer offsets
-'''
-
-import sys, time, os, math
-
-# allow import from the parent directory, where mavlink.py is
-sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..'))
-
-from optparse import OptionParser
-parser = OptionParser("magfit.py [options]")
-parser.add_option("--no-timestamps",dest="notimestamps", action='store_true', help="Log doesn't have timestamps")
-parser.add_option("--condition",dest="condition", default=None, help="select packets by condition")
-parser.add_option("--noise", type='float', default=0, help="noise to add")
-parser.add_option("--mav10", action='store_true', default=False, help="Use MAVLink protocol 1.0")
-
-(opts, args) = parser.parse_args()
-
-if opts.mav10:
- os.environ['MAVLINK10'] = '1'
-import mavutil
-from rotmat import Vector3
-
-if len(args) < 1:
- print("Usage: magfit.py [options] <LOGFILE...>")
- sys.exit(1)
-
-def noise():
- '''a noise vector'''
- from random import gauss
- v = Vector3(gauss(0, 1), gauss(0, 1), gauss(0, 1))
- v.normalize()
- return v * opts.noise
-
-def select_data(data):
- ret = []
- counts = {}
- for d in data:
- mag = d
- key = "%u:%u:%u" % (mag.x/20,mag.y/20,mag.z/20)
- if key in counts:
- counts[key] += 1
- else:
- counts[key] = 1
- if counts[key] < 3:
- ret.append(d)
- print(len(data), len(ret))
- return ret
-
-def radius(mag, offsets):
- '''return radius give data point and offsets'''
- return (mag + offsets).length()
-
-def radius_cmp(a, b, offsets):
- '''return radius give data point and offsets'''
- diff = radius(a, offsets) - radius(b, offsets)
- if diff > 0:
- return 1
- if diff < 0:
- return -1
- return 0
-
-def sphere_error(p, data):
- from scipy import sqrt
- x,y,z,r = p
- ofs = Vector3(x,y,z)
- ret = []
- for d in data:
- mag = d
- err = r - radius(mag, ofs)
- ret.append(err)
- return ret
-
-def fit_data(data):
- import numpy, scipy
- from scipy import optimize
-
- p0 = [0.0, 0.0, 0.0, 0.0]
- p1, ier = optimize.leastsq(sphere_error, p0[:], args=(data))
- if not ier in [1, 2, 3, 4]:
- raise RuntimeError("Unable to find solution")
- return (Vector3(p1[0], p1[1], p1[2]), p1[3])
-
-def magfit(logfile):
- '''find best magnetometer offset fit to a log file'''
-
- print("Processing log %s" % filename)
- mlog = mavutil.mavlink_connection(filename, notimestamps=opts.notimestamps)
-
- data = []
-
- last_t = 0
- offsets = Vector3(0,0,0)
-
- # now gather all the data
- while True:
- m = mlog.recv_match(condition=opts.condition)
- if m is None:
- break
- if m.get_type() == "SENSOR_OFFSETS":
- # update current offsets
- offsets = Vector3(m.mag_ofs_x, m.mag_ofs_y, m.mag_ofs_z)
- if m.get_type() == "RAW_IMU":
- mag = Vector3(m.xmag, m.ymag, m.zmag)
- # add data point after subtracting the current offsets
- data.append(mag - offsets + noise())
-
- print("Extracted %u data points" % len(data))
- print("Current offsets: %s" % offsets)
-
- data = select_data(data)
-
- # do an initial fit with all data
- (offsets, field_strength) = fit_data(data)
-
- for count in range(3):
- # sort the data by the radius
- data.sort(lambda a,b : radius_cmp(a,b,offsets))
-
- print("Fit %u : %s field_strength=%6.1f to %6.1f" % (
- count, offsets,
- radius(data[0], offsets), radius(data[-1], offsets)))
-
- # discard outliers, keep the middle 3/4
- data = data[len(data)/8:-len(data)/8]
-
- # fit again
- (offsets, field_strength) = fit_data(data)
-
- print("Final : %s field_strength=%6.1f to %6.1f" % (
- offsets,
- radius(data[0], offsets), radius(data[-1], offsets)))
-
-total = 0.0
-for filename in args:
- magfit(filename)
diff --git a/mavlink/share/pyshared/pymavlink/examples/magfit_delta.py b/mavlink/share/pyshared/pymavlink/examples/magfit_delta.py
deleted file mode 100644
index 87d2dbb7f..000000000
--- a/mavlink/share/pyshared/pymavlink/examples/magfit_delta.py
+++ /dev/null
@@ -1,145 +0,0 @@
-#!/usr/bin/env python
-
-'''
-fit best estimate of magnetometer offsets using the algorithm from
-Bill Premerlani
-'''
-
-import sys, time, os, math
-
-# allow import from the parent directory, where mavlink.py is
-sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..'))
-
-# command line option handling
-from optparse import OptionParser
-parser = OptionParser("magfit_delta.py [options]")
-parser.add_option("--no-timestamps",dest="notimestamps", action='store_true', help="Log doesn't have timestamps")
-parser.add_option("--condition",dest="condition", default=None, help="select packets by condition")
-parser.add_option("--mav10", action='store_true', default=False, help="Use MAVLink protocol 1.0")
-parser.add_option("--verbose", action='store_true', default=False, help="verbose offset output")
-parser.add_option("--gain", type='float', default=0.01, help="algorithm gain")
-parser.add_option("--noise", type='float', default=0, help="noise to add")
-parser.add_option("--max-change", type='float', default=10, help="max step change")
-parser.add_option("--min-diff", type='float', default=50, help="min mag vector delta")
-parser.add_option("--history", type='int', default=20, help="how many points to keep")
-parser.add_option("--repeat", type='int', default=1, help="number of repeats through the data")
-
-(opts, args) = parser.parse_args()
-
-if opts.mav10:
- os.environ['MAVLINK10'] = '1'
-import mavutil
-from rotmat import Vector3, Matrix3
-
-if len(args) < 1:
- print("Usage: magfit_delta.py [options] <LOGFILE...>")
- sys.exit(1)
-
-def noise():
- '''a noise vector'''
- from random import gauss
- v = Vector3(gauss(0, 1), gauss(0, 1), gauss(0, 1))
- v.normalize()
- return v * opts.noise
-
-def find_offsets(data, ofs):
- '''find mag offsets by applying Bills "offsets revisited" algorithm
- on the data
-
- This is an implementation of the algorithm from:
- http://gentlenav.googlecode.com/files/MagnetometerOffsetNullingRevisited.pdf
- '''
-
- # a limit on the maximum change in each step
- max_change = opts.max_change
-
- # the gain factor for the algorithm
- gain = opts.gain
-
- data2 = []
- for d in data:
- d = d.copy() + noise()
- d.x = float(int(d.x + 0.5))
- d.y = float(int(d.y + 0.5))
- d.z = float(int(d.z + 0.5))
- data2.append(d)
- data = data2
-
- history_idx = 0
- mag_history = data[0:opts.history]
-
- for i in range(opts.history, len(data)):
- B1 = mag_history[history_idx] + ofs
- B2 = data[i] + ofs
-
- diff = B2 - B1
- diff_length = diff.length()
- if diff_length <= opts.min_diff:
- # the mag vector hasn't changed enough - we don't get any
- # information from this
- history_idx = (history_idx+1) % opts.history
- continue
-
- mag_history[history_idx] = data[i]
- history_idx = (history_idx+1) % opts.history
-
- # equation 6 of Bills paper
- delta = diff * (gain * (B2.length() - B1.length()) / diff_length)
-
- # limit the change from any one reading. This is to prevent
- # single crazy readings from throwing off the offsets for a long
- # time
- delta_length = delta.length()
- if max_change != 0 and delta_length > max_change:
- delta *= max_change / delta_length
-
- # set the new offsets
- ofs = ofs - delta
-
- if opts.verbose:
- print ofs
- return ofs
-
-
-def magfit(logfile):
- '''find best magnetometer offset fit to a log file'''
-
- print("Processing log %s" % filename)
-
- # open the log file
- mlog = mavutil.mavlink_connection(filename, notimestamps=opts.notimestamps)
-
- data = []
- mag = None
- offsets = Vector3(0,0,0)
-
- # now gather all the data
- while True:
- # get the next MAVLink message in the log
- m = mlog.recv_match(condition=opts.condition)
- if m is None:
- break
- if m.get_type() == "SENSOR_OFFSETS":
- # update offsets that were used during this flight
- offsets = Vector3(m.mag_ofs_x, m.mag_ofs_y, m.mag_ofs_z)
- if m.get_type() == "RAW_IMU" and offsets != None:
- # extract one mag vector, removing the offsets that were
- # used during that flight to get the raw sensor values
- mag = Vector3(m.xmag, m.ymag, m.zmag) - offsets
- data.append(mag)
-
- print("Extracted %u data points" % len(data))
- print("Current offsets: %s" % offsets)
-
- # run the fitting algorithm
- ofs = offsets
- ofs = Vector3(0,0,0)
- for r in range(opts.repeat):
- ofs = find_offsets(data, ofs)
- print('Loop %u offsets %s' % (r, ofs))
- sys.stdout.flush()
- print("New offsets: %s" % ofs)
-
-total = 0.0
-for filename in args:
- magfit(filename)
diff --git a/mavlink/share/pyshared/pymavlink/examples/magfit_gps.py b/mavlink/share/pyshared/pymavlink/examples/magfit_gps.py
deleted file mode 100644
index 30ba45806..000000000
--- a/mavlink/share/pyshared/pymavlink/examples/magfit_gps.py
+++ /dev/null
@@ -1,159 +0,0 @@
-#!/usr/bin/env python
-
-'''
-fit best estimate of magnetometer offsets
-'''
-
-import sys, time, os, math
-
-# allow import from the parent directory, where mavlink.py is
-sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..'))
-
-from optparse import OptionParser
-parser = OptionParser("magfit.py [options]")
-parser.add_option("--no-timestamps",dest="notimestamps", action='store_true', help="Log doesn't have timestamps")
-parser.add_option("--mav10", action='store_true', default=False, help="Use MAVLink protocol 1.0")
-parser.add_option("--minspeed", type='float', default=5.0, help="minimum ground speed to use")
-
-(opts, args) = parser.parse_args()
-
-if opts.mav10:
- os.environ['MAVLINK10'] = '1'
-import mavutil
-
-if len(args) < 1:
- print("Usage: magfit.py [options] <LOGFILE...>")
- sys.exit(1)
-
-class vec3(object):
- def __init__(self, x, y, z):
- self.x = x
- self.y = y
- self.z = z
- def __str__(self):
- return "%.1f %.1f %.1f" % (self.x, self.y, self.z)
-
-def heading_error1(parm, data):
- from math import sin, cos, atan2, degrees
- from numpy import dot
- xofs,yofs,zofs,a1,a2,a3,a4,a5,a6,a7,a8,a9,declination = parm
-
- ret = []
- for d in data:
- x = d[0] + xofs
- y = d[1] + yofs
- z = d[2] + zofs
- r = d[3]
- p = d[4]
- h = d[5]
-
- headX = x*cos(p) + y*sin(r)*sin(p) + z*cos(r)*sin(p)
- headY = y*cos(r) - z*sin(r)
- heading = degrees(atan2(-headY,headX)) + declination
- if heading < 0:
- heading += 360
- herror = h - heading
- if herror > 180:
- herror -= 360
- if herror < -180:
- herror += 360
- ret.append(herror)
- return ret
-
-def heading_error(parm, data):
- from math import sin, cos, atan2, degrees
- from numpy import dot
- xofs,yofs,zofs,a1,a2,a3,a4,a5,a6,a7,a8,a9,declination = parm
-
- a = [[1.0,a2,a3],[a4,a5,a6],[a7,a8,a9]]
-
- ret = []
- for d in data:
- x = d[0] + xofs
- y = d[1] + yofs
- z = d[2] + zofs
- r = d[3]
- p = d[4]
- h = d[5]
- mv = [x, y, z]
- mv2 = dot(a, mv)
- x = mv2[0]
- y = mv2[1]
- z = mv2[2]
-
- headX = x*cos(p) + y*sin(r)*sin(p) + z*cos(r)*sin(p)
- headY = y*cos(r) - z*sin(r)
- heading = degrees(atan2(-headY,headX)) + declination
- if heading < 0:
- heading += 360
- herror = h - heading
- if herror > 180:
- herror -= 360
- if herror < -180:
- herror += 360
- ret.append(herror)
- return ret
-
-def fit_data(data):
- import numpy, scipy
- from scipy import optimize
-
- p0 = [0.0, 0.0, 0.0, 1, 0, 0, 0, 1, 0, 0, 0, 1, 0]
- p1, ier = optimize.leastsq(heading_error1, p0[:], args=(data))
-
-# p0 = p1[:]
-# p1, ier = optimize.leastsq(heading_error, p0[:], args=(data))
-
- print(p1)
- if not ier in [1, 2, 3, 4]:
- raise RuntimeError("Unable to find solution")
- return p1
-
-def magfit(logfile):
- '''find best magnetometer offset fit to a log file'''
- print("Processing log %s" % filename)
- mlog = mavutil.mavlink_connection(filename, notimestamps=opts.notimestamps)
-
- flying = False
- gps_heading = 0.0
-
- data = []
-
- # get the current mag offsets
- m = mlog.recv_match(type='SENSOR_OFFSETS')
- offsets = vec3(m.mag_ofs_x, m.mag_ofs_y, m.mag_ofs_z)
-
- attitude = mlog.recv_match(type='ATTITUDE')
-
- # now gather all the data
- while True:
- m = mlog.recv_match()
- if m is None:
- break
- if m.get_type() == "GPS_RAW":
- # flying if groundspeed more than 5 m/s
- flying = (m.v > opts.minspeed and m.fix_type == 2)
- gps_heading = m.hdg
- if m.get_type() == "ATTITUDE":
- attitude = m
- if m.get_type() == "SENSOR_OFFSETS":
- # update current offsets
- offsets = vec3(m.mag_ofs_x, m.mag_ofs_y, m.mag_ofs_z)
- if not flying:
- continue
- if m.get_type() == "RAW_IMU":
- data.append((m.xmag - offsets.x, m.ymag - offsets.y, m.zmag - offsets.z, attitude.roll, attitude.pitch, gps_heading))
- print("Extracted %u data points" % len(data))
- print("Current offsets: %s" % offsets)
- ofs2 = fit_data(data)
- print("Declination estimate: %.1f" % ofs2[-1])
- new_offsets = vec3(ofs2[0], ofs2[1], ofs2[2])
- a = [[ofs2[3], ofs2[4], ofs2[5]],
- [ofs2[6], ofs2[7], ofs2[8]],
- [ofs2[9], ofs2[10], ofs2[11]]]
- print(a)
- print("New offsets : %s" % new_offsets)
-
-total = 0.0
-for filename in args:
- magfit(filename)
diff --git a/mavlink/share/pyshared/pymavlink/examples/magtest.py b/mavlink/share/pyshared/pymavlink/examples/magtest.py
deleted file mode 100644
index 8b910f8fd..000000000
--- a/mavlink/share/pyshared/pymavlink/examples/magtest.py
+++ /dev/null
@@ -1,120 +0,0 @@
-#!/usr/bin/env python
-
-'''
-rotate APMs on bench to test magnetometers
-
-'''
-
-import sys, os, time
-from math import radians
-
-# allow import from the parent directory, where mavlink.py is
-sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..'))
-
-import mavlink, mavutil
-
-from optparse import OptionParser
-parser = OptionParser("rotate.py [options]")
-
-parser.add_option("--device1", dest="device1", default=None, help="mavlink device1")
-parser.add_option("--device2", dest="device2", default=None, help="mavlink device2")
-parser.add_option("--baudrate", dest="baudrate", type='int',
- help="master port baud rate", default=115200)
-(opts, args) = parser.parse_args()
-
-if opts.device1 is None or opts.device2 is None:
- print("You must specify a mavlink device")
- sys.exit(1)
-
-def set_attitude(rc3, rc4):
- global mav1, mav2
- values = [ 65535 ] * 8
- values[2] = rc3
- values[3] = rc4
- mav1.mav.rc_channels_override_send(mav1.target_system, mav1.target_component, *values)
- mav2.mav.rc_channels_override_send(mav2.target_system, mav2.target_component, *values)
-
-
-# create a mavlink instance
-mav1 = mavutil.mavlink_connection(opts.device1, baud=opts.baudrate)
-
-# create a mavlink instance
-mav2 = mavutil.mavlink_connection(opts.device2, baud=opts.baudrate)
-
-print("Waiting for HEARTBEAT")
-mav1.wait_heartbeat()
-mav2.wait_heartbeat()
-print("Heartbeat from APM (system %u component %u)" % (mav1.target_system, mav1.target_system))
-print("Heartbeat from APM (system %u component %u)" % (mav2.target_system, mav2.target_system))
-
-print("Waiting for MANUAL mode")
-mav1.recv_match(type='SYS_STATUS', condition='SYS_STATUS.mode==2 and SYS_STATUS.nav_mode==4', blocking=True)
-mav2.recv_match(type='SYS_STATUS', condition='SYS_STATUS.mode==2 and SYS_STATUS.nav_mode==4', blocking=True)
-
-print("Setting declination")
-mav1.mav.param_set_send(mav1.target_system, mav1.target_component,
- 'COMPASS_DEC', radians(12.33))
-mav2.mav.param_set_send(mav2.target_system, mav2.target_component,
- 'COMPASS_DEC', radians(12.33))
-
-
-set_attitude(1060, 1160)
-
-event = mavutil.periodic_event(30)
-pevent = mavutil.periodic_event(0.3)
-rc3_min = 1060
-rc3_max = 1850
-rc4_min = 1080
-rc4_max = 1500
-rc3 = rc3_min
-rc4 = 1160
-delta3 = 2
-delta4 = 1
-use_pitch = 1
-
-MAV_ACTION_CALIBRATE_GYRO = 17
-mav1.mav.action_send(mav1.target_system, mav1.target_component, MAV_ACTION_CALIBRATE_GYRO)
-mav2.mav.action_send(mav2.target_system, mav2.target_component, MAV_ACTION_CALIBRATE_GYRO)
-
-print("Waiting for gyro calibration")
-mav1.recv_match(type='ACTION_ACK')
-mav2.recv_match(type='ACTION_ACK')
-
-print("Resetting mag offsets")
-mav1.mav.set_mag_offsets_send(mav1.target_system, mav1.target_component, 0, 0, 0)
-mav2.mav.set_mag_offsets_send(mav2.target_system, mav2.target_component, 0, 0, 0)
-
-def TrueHeading(SERVO_OUTPUT_RAW):
- p = float(SERVO_OUTPUT_RAW.servo3_raw - rc3_min) / (rc3_max - rc3_min)
- return 172 + p*(326 - 172)
-
-while True:
- mav1.recv_msg()
- mav2.recv_msg()
- if event.trigger():
- if not use_pitch:
- rc4 = 1160
- set_attitude(rc3, rc4)
- rc3 += delta3
- if rc3 > rc3_max or rc3 < rc3_min:
- delta3 = -delta3
- use_pitch ^= 1
- rc4 += delta4
- if rc4 > rc4_max or rc4 < rc4_min:
- delta4 = -delta4
- if pevent.trigger():
- print "hdg1: %3u hdg2: %3u ofs1: %4u, %4u, %4u ofs2: %4u, %4u, %4u" % (
- mav1.messages['VFR_HUD'].heading,
- mav2.messages['VFR_HUD'].heading,
- mav1.messages['SENSOR_OFFSETS'].mag_ofs_x,
- mav1.messages['SENSOR_OFFSETS'].mag_ofs_y,
- mav1.messages['SENSOR_OFFSETS'].mag_ofs_z,
- mav2.messages['SENSOR_OFFSETS'].mag_ofs_x,
- mav2.messages['SENSOR_OFFSETS'].mag_ofs_y,
- mav2.messages['SENSOR_OFFSETS'].mag_ofs_z,
- )
- time.sleep(0.01)
-
-# 314M 326G
-# 160M 172G
-
diff --git a/mavlink/share/pyshared/pymavlink/examples/mavgraph.py b/mavlink/share/pyshared/pymavlink/examples/mavgraph.py
deleted file mode 100644
index e19856487..000000000
--- a/mavlink/share/pyshared/pymavlink/examples/mavgraph.py
+++ /dev/null
@@ -1,196 +0,0 @@
-#!/usr/bin/env python
-'''
-graph a MAVLink log file
-Andrew Tridgell August 2011
-'''
-
-import sys, struct, time, os, datetime
-import math, re
-import pylab, pytz, matplotlib
-from math import *
-
-# allow import from the parent directory, where mavlink.py is
-sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..'))
-
-from mavextra import *
-
-locator = None
-formatter = None
-
-def plotit(x, y, fields, colors=[]):
- '''plot a set of graphs using date for x axis'''
- global locator, formatter
- pylab.ion()
- fig = pylab.figure(num=1, figsize=(12,6))
- ax1 = fig.gca()
- ax2 = None
- xrange = 0.0
- for i in range(0, len(fields)):
- if len(x[i]) == 0: continue
- if x[i][-1] - x[i][0] > xrange:
- xrange = x[i][-1] - x[i][0]
- xrange *= 24 * 60 * 60
- if formatter is None:
- if xrange < 1000:
- formatter = matplotlib.dates.DateFormatter('%H:%M:%S')
- else:
- formatter = matplotlib.dates.DateFormatter('%H:%M')
- interval = 1
- intervals = [ 1, 2, 5, 10, 15, 30, 60, 120, 240, 300, 600,
- 900, 1800, 3600, 7200, 5*3600, 10*3600, 24*3600 ]
- for interval in intervals:
- if xrange / interval < 15:
- break
- locator = matplotlib.dates.SecondLocator(interval=interval)
- ax1.xaxis.set_major_locator(locator)
- ax1.xaxis.set_major_formatter(formatter)
- empty = True
- ax1_labels = []
- ax2_labels = []
- for i in range(0, len(fields)):
- if len(x[i]) == 0:
- print("Failed to find any values for field %s" % fields[i])
- continue
- if i < len(colors):
- color = colors[i]
- else:
- color = 'red'
- (tz, tzdst) = time.tzname
- if axes[i] == 2:
- if ax2 == None:
- ax2 = ax1.twinx()
- ax = ax2
- ax2.xaxis.set_major_locator(locator)
- ax2.xaxis.set_major_formatter(formatter)
- label = fields[i]
- if label.endswith(":2"):
- label = label[:-2]
- ax2_labels.append(label)
- else:
- ax1_labels.append(fields[i])
- ax = ax1
- ax.plot_date(x[i], y[i], color=color, label=fields[i],
- linestyle='-', marker='None', tz=None)
- pylab.draw()
- empty = False
- if ax1_labels != []:
- ax1.legend(ax1_labels,loc=opts.legend)
- if ax2_labels != []:
- ax2.legend(ax2_labels,loc=opts.legend2)
- if empty:
- print("No data to graph")
- return
-
-
-from optparse import OptionParser
-parser = OptionParser("mavgraph.py [options] <filename> <fields>")
-
-parser.add_option("--no-timestamps",dest="notimestamps", action='store_true', help="Log doesn't have timestamps")
-parser.add_option("--planner",dest="planner", action='store_true', help="use planner file format")
-parser.add_option("--condition",dest="condition", default=None, help="select packets by a condition")
-parser.add_option("--labels",dest="labels", default=None, help="comma separated field labels")
-parser.add_option("--mav10", action='store_true', default=False, help="Use MAVLink protocol 1.0")
-parser.add_option("--legend", default='upper left', help="default legend position")
-parser.add_option("--legend2", default='upper right', help="default legend2 position")
-(opts, args) = parser.parse_args()
-
-if opts.mav10:
- os.environ['MAVLINK10'] = '1'
-import mavutil
-
-if len(args) < 2:
- print("Usage: mavlogdump.py [options] <LOGFILES...> <fields...>")
- sys.exit(1)
-
-filenames = []
-fields = []
-for f in args:
- if os.path.exists(f):
- filenames.append(f)
- else:
- fields.append(f)
-msg_types = set()
-multiplier = []
-field_types = []
-
-colors = [ 'red', 'green', 'blue', 'orange', 'olive', 'black', 'grey' ]
-
-# work out msg types we are interested in
-x = []
-y = []
-axes = []
-first_only = []
-re_caps = re.compile('[A-Z_]+')
-for f in fields:
- caps = set(re.findall(re_caps, f))
- msg_types = msg_types.union(caps)
- field_types.append(caps)
- y.append([])
- x.append([])
- axes.append(1)
- first_only.append(False)
-
-def add_data(t, msg, vars):
- '''add some data'''
- mtype = msg.get_type()
- if mtype not in msg_types:
- return
- for i in range(0, len(fields)):
- if mtype not in field_types[i]:
- continue
- f = fields[i]
- if f.endswith(":2"):
- axes[i] = 2
- f = f[:-2]
- if f.endswith(":1"):
- first_only[i] = True
- f = f[:-2]
- v = mavutil.evaluate_expression(f, vars)
- if v is None:
- continue
- y[i].append(v)
- x[i].append(t)
-
-def process_file(filename):
- '''process one file'''
- print("Processing %s" % filename)
- mlog = mavutil.mavlink_connection(filename, notimestamps=opts.notimestamps)
- vars = {}
-
- while True:
- msg = mlog.recv_match(opts.condition)
- if msg is None: break
- tdays = (msg._timestamp - time.timezone) / (24 * 60 * 60)
- tdays += 719163 # pylab wants it since 0001-01-01
- add_data(tdays, msg, mlog.messages)
-
-if len(filenames) == 0:
- print("No files to process")
- sys.exit(1)
-
-if opts.labels is not None:
- labels = opts.labels.split(',')
- if len(labels) != len(fields)*len(filenames):
- print("Number of labels (%u) must match number of fields (%u)" % (
- len(labels), len(fields)*len(filenames)))
- sys.exit(1)
-else:
- labels = None
-
-for fi in range(0, len(filenames)):
- f = filenames[fi]
- process_file(f)
- for i in range(0, len(x)):
- if first_only[i] and fi != 0:
- x[i] = []
- y[i] = []
- if labels:
- lab = labels[fi*len(fields):(fi+1)*len(fields)]
- else:
- lab = fields[:]
- plotit(x, y, lab, colors=colors[fi*len(fields):])
- for i in range(0, len(x)):
- x[i] = []
- y[i] = []
-pylab.show()
-raw_input('press enter to exit....')
diff --git a/mavlink/share/pyshared/pymavlink/examples/mavlogdump.py b/mavlink/share/pyshared/pymavlink/examples/mavlogdump.py
deleted file mode 100644
index f4cdc56bf..000000000
--- a/mavlink/share/pyshared/pymavlink/examples/mavlogdump.py
+++ /dev/null
@@ -1,67 +0,0 @@
-#!/usr/bin/env python
-
-'''
-example program that dumps a Mavlink log file. The log file is
-assumed to be in the format that qgroundcontrol uses, which consists
-of a series of MAVLink packets, each with a 64 bit timestamp
-header. The timestamp is in microseconds since 1970 (unix epoch)
-'''
-
-import sys, time, os, struct
-
-# allow import from the parent directory, where mavlink.py is
-sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..'))
-
-from optparse import OptionParser
-parser = OptionParser("mavlogdump.py [options]")
-
-parser.add_option("--no-timestamps",dest="notimestamps", action='store_true', help="Log doesn't have timestamps")
-parser.add_option("--planner",dest="planner", action='store_true', help="use planner file format")
-parser.add_option("--robust",dest="robust", action='store_true', help="Enable robust parsing (skip over bad data)")
-parser.add_option("-f", "--follow",dest="follow", action='store_true', help="keep waiting for more data at end of file")
-parser.add_option("--condition",dest="condition", default=None, help="select packets by condition")
-parser.add_option("-q", "--quiet", dest="quiet", action='store_true', help="don't display packets")
-parser.add_option("-o", "--output", default=None, help="output matching packets to give file")
-parser.add_option("--mav10", action='store_true', default=False, help="Use MAVLink protocol 1.0")
-parser.add_option("--types", default=None, help="types of messages (comma separated)")
-(opts, args) = parser.parse_args()
-
-if opts.mav10:
- os.environ['MAVLINK10'] = '1'
-import mavutil
-
-if len(args) < 1:
- print("Usage: mavlogdump.py [options] <LOGFILE>")
- sys.exit(1)
-
-filename = args[0]
-mlog = mavutil.mavlink_connection(filename, planner_format=opts.planner,
- notimestamps=opts.notimestamps,
- robust_parsing=opts.robust)
-
-output = None
-if opts.output:
- output = mavutil.mavlogfile(opts.output, write=True)
-
-types = opts.types
-if types is not None:
- types = types.split(',')
-
-while True:
- m = mlog.recv_match(condition=opts.condition, blocking=opts.follow)
- if m is None:
- break
- if types is not None and m.get_type() not in types:
- continue
- if output:
- timestamp = getattr(m, '_timestamp', None)
- if timestamp:
- output.write(struct.pack('>Q', timestamp*1.0e6))
- output.write(m.get_msgbuf().tostring())
- if opts.quiet:
- continue
- print("%s.%02u: %s" % (
- time.strftime("%Y-%m-%d %H:%M:%S",
- time.localtime(m._timestamp)),
- int(m._timestamp*100.0)%100, m))
-
diff --git a/mavlink/share/pyshared/pymavlink/examples/mavparms.py b/mavlink/share/pyshared/pymavlink/examples/mavparms.py
deleted file mode 100644
index 702fbd9e1..000000000
--- a/mavlink/share/pyshared/pymavlink/examples/mavparms.py
+++ /dev/null
@@ -1,48 +0,0 @@
-#!/usr/bin/env python
-
-'''
-extract mavlink parameter values
-'''
-
-import sys, time, os
-
-# allow import from the parent directory, where mavlink.py is
-sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..'))
-
-from optparse import OptionParser
-parser = OptionParser("mavparms.py [options]")
-parser.add_option("--mav10", action='store_true', default=False, help="Use MAVLink protocol 1.0")
-
-(opts, args) = parser.parse_args()
-
-if opts.mav10:
- os.environ['MAVLINK10'] = '1'
-import mavutil
-
-if len(args) < 1:
- print("Usage: mavparms.py [options] <LOGFILE...>")
- sys.exit(1)
-
-parms = {}
-
-def mavparms(logfile):
- '''extract mavlink parameters'''
- mlog = mavutil.mavlink_connection(filename)
-
- while True:
- m = mlog.recv_match(type='PARAM_VALUE')
- if m is None:
- return
- pname = str(m.param_id).strip()
- if len(pname) > 0:
- parms[pname] = m.param_value
-
-total = 0.0
-for filename in args:
- mavparms(filename)
-
-keys = parms.keys()
-keys.sort()
-for p in keys:
- print("%-15s %.6f" % (p, parms[p]))
-
diff --git a/mavlink/share/pyshared/pymavlink/examples/mavtest.py b/mavlink/share/pyshared/pymavlink/examples/mavtest.py
deleted file mode 100644
index 3c385e48a..000000000
--- a/mavlink/share/pyshared/pymavlink/examples/mavtest.py
+++ /dev/null
@@ -1,41 +0,0 @@
-#!/usr/bin/env python
-
-import sys, os
-
-# allow import from the parent directory, where mavlink.py is
-sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..'))
-
-import mavlink
-
-class fifo(object):
- def __init__(self):
- self.buf = []
- def write(self, data):
- self.buf += data
- return len(data)
- def read(self):
- return self.buf.pop(0)
-
-f = fifo()
-
-# create a mavlink instance, which will do IO on file object 'f'
-mav = mavlink.MAVLink(f)
-
-# set the WP_RADIUS parameter on the MAV at the end of the link
-mav.param_set_send(7, 1, "WP_RADIUS", 101)
-
-# alternatively, produce a MAVLink_param_set object
-# this can be sent via your own transport if you like
-m = mav.param_set_encode(7, 1, "WP_RADIUS", 101)
-
-# get the encoded message as a buffer
-b = m.get_msgbuf()
-
-# decode an incoming message
-m2 = mav.decode(b)
-
-# show what fields it has
-print("Got a message with id %u and fields %s" % (m2.get_msgId(), m2.get_fieldnames()))
-
-# print out the fields
-print(m2)
diff --git a/mavlink/share/pyshared/pymavlink/examples/mavtester.py b/mavlink/share/pyshared/pymavlink/examples/mavtester.py
deleted file mode 100644
index 8b5284f3f..000000000
--- a/mavlink/share/pyshared/pymavlink/examples/mavtester.py
+++ /dev/null
@@ -1,43 +0,0 @@
-#!/usr/bin/env python
-
-'''
-test mavlink messages
-'''
-
-import sys, struct, time, os
-from curses import ascii
-
-# allow import from the parent directory, where mavlink.py is
-sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..'))
-
-import mavlink, mavtest, mavutil
-
-from optparse import OptionParser
-parser = OptionParser("mavtester.py [options]")
-
-parser.add_option("--baudrate", dest="baudrate", type='int',
- help="master port baud rate", default=115200)
-parser.add_option("--device", dest="device", default=None, help="serial device")
-parser.add_option("--source-system", dest='SOURCE_SYSTEM', type='int',
- default=255, help='MAVLink source system for this GCS')
-(opts, args) = parser.parse_args()
-
-if opts.device is None:
- print("You must specify a serial device")
- sys.exit(1)
-
-def wait_heartbeat(m):
- '''wait for a heartbeat so we know the target system IDs'''
- print("Waiting for APM heartbeat")
- msg = m.recv_match(type='HEARTBEAT', blocking=True)
- print("Heartbeat from APM (system %u component %u)" % (m.target_system, m.target_system))
-
-# create a mavlink serial instance
-master = mavutil.mavlink_connection(opts.device, baud=opts.baudrate, source_system=opts.SOURCE_SYSTEM)
-
-# wait for the heartbeat msg to find the system ID
-wait_heartbeat(master)
-
-print("Sending all message types")
-mavtest.generate_outputs(master.mav)
-
diff --git a/mavlink/share/pyshared/pymavlink/examples/mavtogpx.py b/mavlink/share/pyshared/pymavlink/examples/mavtogpx.py
deleted file mode 100644
index 92d3cb51c..000000000
--- a/mavlink/share/pyshared/pymavlink/examples/mavtogpx.py
+++ /dev/null
@@ -1,83 +0,0 @@
-#!/usr/bin/env python
-
-'''
-example program to extract GPS data from a mavlink log, and create a GPX
-file, for loading into google earth
-'''
-
-import sys, struct, time, os
-
-# allow import from the parent directory, where mavlink.py is
-sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..'))
-
-from optparse import OptionParser
-parser = OptionParser("mavtogpx.py [options]")
-parser.add_option("--condition",dest="condition", default=None, help="select packets by a condition")
-parser.add_option("--nofixcheck", default=False, action='store_true', help="don't check for GPS fix")
-parser.add_option("--mav10", action='store_true', default=False, help="Use MAVLink protocol 1.0")
-(opts, args) = parser.parse_args()
-
-if opts.mav10:
- os.environ['MAVLINK10'] = '1'
-import mavutil
-
-if len(args) < 1:
- print("Usage: mavtogpx.py <LOGFILE>")
- sys.exit(1)
-
-def mav_to_gpx(infilename, outfilename):
- '''convert a mavlink log file to a GPX file'''
-
- mlog = mavutil.mavlink_connection(infilename)
- outf = open(outfilename, mode='w')
-
- def process_packet(m):
- t = time.localtime(m._timestamp)
- outf.write('''<trkpt lat="%s" lon="%s">
- <ele>%s</ele>
- <time>%s</time>
- <course>%s</course>
- <speed>%s</speed>
- <fix>3d</fix>
-</trkpt>
-''' % (m.lat, m.lon, m.alt,
- time.strftime("%Y-%m-%dT%H:%M:%SZ", t),
- m.hdg, m.v))
-
- def add_header():
- outf.write('''<?xml version="1.0" encoding="UTF-8"?>
-<gpx
- version="1.0"
- creator="pymavlink"
- xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance"
- xmlns="http://www.topografix.com/GPX/1/0"
- xsi:schemaLocation="http://www.topografix.com/GPX/1/0 http://www.topografix.com/GPX/1/0/gpx.xsd">
-<trk>
-<trkseg>
-''')
-
- def add_footer():
- outf.write('''</trkseg>
-</trk>
-</gpx>
-''')
-
- add_header()
-
- count=0
- while True:
- m = mlog.recv_match(type='GPS_RAW', condition=opts.condition)
- if m is None: break
- if m.fix_type != 2 and not opts.nofixcheck:
- continue
- if m.lat == 0.0 or m.lon == 0.0:
- continue
- process_packet(m)
- count += 1
- add_footer()
- print("Created %s with %u points" % (outfilename, count))
-
-
-for infilename in args:
- outfilename = infilename + '.gpx'
- mav_to_gpx(infilename, outfilename)
diff --git a/mavlink/share/pyshared/pymavlink/examples/rotmat.py b/mavlink/share/pyshared/pymavlink/examples/rotmat.py
deleted file mode 100644
index 6d5405949..000000000
--- a/mavlink/share/pyshared/pymavlink/examples/rotmat.py
+++ /dev/null
@@ -1,269 +0,0 @@
-#!/usr/bin/env python
-#
-# vector3 and rotation matrix classes
-# This follows the conventions in the ArduPilot code,
-# and is essentially a python version of the AP_Math library
-#
-# Andrew Tridgell, March 2012
-#
-# This library is free software; you can redistribute it and/or modify it
-# under the terms of the GNU Lesser General Public License as published by the
-# Free Software Foundation; either version 2.1 of the License, or (at your
-# option) any later version.
-#
-# This library is distributed in the hope that it will be useful, but WITHOUT
-# ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
-# FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License
-# for more details.
-#
-# You should have received a copy of the GNU Lesser General Public License
-# along with this library; if not, write to the Free Software Foundation,
-# Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
-
-'''rotation matrix class
-'''
-
-from math import sin, cos, sqrt, asin, atan2, pi, radians, acos
-
-class Vector3:
- '''a vector'''
- def __init__(self, x=None, y=None, z=None):
- if x != None and y != None and z != None:
- self.x = float(x)
- self.y = float(y)
- self.z = float(z)
- elif x != None and len(x) == 3:
- self.x = float(x[0])
- self.y = float(x[1])
- self.z = float(x[2])
- elif x != None:
- raise ValueError('bad initialiser')
- else:
- self.x = float(0)
- self.y = float(0)
- self.z = float(0)
-
- def __repr__(self):
- return 'Vector3(%.2f, %.2f, %.2f)' % (self.x,
- self.y,
- self.z)
-
- def __add__(self, v):
- return Vector3(self.x + v.x,
- self.y + v.y,
- self.z + v.z)
-
- __radd__ = __add__
-
- def __sub__(self, v):
- return Vector3(self.x - v.x,
- self.y - v.y,
- self.z - v.z)
-
- def __neg__(self):
- return Vector3(-self.x, -self.y, -self.z)
-
- def __rsub__(self, v):
- return Vector3(v.x - self.x,
- v.y - self.y,
- v.z - self.z)
-
- def __mul__(self, v):
- if isinstance(v, Vector3):
- '''dot product'''
- return self.x*v.x + self.y*v.y + self.z*v.z
- return Vector3(self.x * v,
- self.y * v,
- self.z * v)
-
- __rmul__ = __mul__
-
- def __div__(self, v):
- return Vector3(self.x / v,
- self.y / v,
- self.z / v)
-
- def __mod__(self, v):
- '''cross product'''
- return Vector3(self.y*v.z - self.z*v.y,
- self.z*v.x - self.x*v.z,
- self.x*v.y - self.y*v.x)
-
- def __copy__(self):
- return Vector3(self.x, self.y, self.z)
-
- copy = __copy__
-
- def length(self):
- return sqrt(self.x**2 + self.y**2 + self.z**2)
-
- def zero(self):
- self.x = self.y = self.z = 0
-
- def angle(self, v):
- '''return the angle between this vector and another vector'''
- return acos(self * v) / (self.length() * v.length())
-
- def normalized(self):
- return self / self.length()
-
- def normalize(self):
- v = self.normalized()
- self.x = v.x
- self.y = v.y
- self.z = v.z
-
-class Matrix3:
- '''a 3x3 matrix, intended as a rotation matrix'''
- def __init__(self, a=None, b=None, c=None):
- if a is not None and b is not None and c is not None:
- self.a = a.copy()
- self.b = b.copy()
- self.c = c.copy()
- else:
- self.identity()
-
- def __repr__(self):
- return 'Matrix3((%.2f, %.2f, %.2f), (%.2f, %.2f, %.2f), (%.2f, %.2f, %.2f))' % (
- self.a.x, self.a.y, self.a.z,
- self.b.x, self.b.y, self.b.z,
- self.c.x, self.c.y, self.c.z)
-
- def identity(self):
- self.a = Vector3(1,0,0)
- self.b = Vector3(0,1,0)
- self.c = Vector3(0,0,1)
-
- def transposed(self):
- return Matrix3(Vector3(self.a.x, self.b.x, self.c.x),
- Vector3(self.a.y, self.b.y, self.c.y),
- Vector3(self.a.z, self.b.z, self.c.z))
-
-
- def from_euler(self, roll, pitch, yaw):
- '''fill the matrix from Euler angles in radians'''
- cp = cos(pitch)
- sp = sin(pitch)
- sr = sin(roll)
- cr = cos(roll)
- sy = sin(yaw)
- cy = cos(yaw)
-
- self.a.x = cp * cy
- self.a.y = (sr * sp * cy) - (cr * sy)
- self.a.z = (cr * sp * cy) + (sr * sy)
- self.b.x = cp * sy
- self.b.y = (sr * sp * sy) + (cr * cy)
- self.b.z = (cr * sp * sy) - (sr * cy)
- self.c.x = -sp
- self.c.y = sr * cp
- self.c.z = cr * cp
-
-
- def to_euler(self):
- '''find Euler angles for the matrix'''
- if self.c.x >= 1.0:
- pitch = pi
- elif self.c.x <= -1.0:
- pitch = -pi
- else:
- pitch = -asin(self.c.x)
- roll = atan2(self.c.y, self.c.z)
- yaw = atan2(self.b.x, self.a.x)
- return (roll, pitch, yaw)
-
- def __add__(self, m):
- return Matrix3(self.a + m.a, self.b + m.b, self.c + m.c)
-
- __radd__ = __add__
-
- def __sub__(self, m):
- return Matrix3(self.a - m.a, self.b - m.b, self.c - m.c)
-
- def __rsub__(self, m):
- return Matrix3(m.a - self.a, m.b - self.b, m.c - self.c)
-
- def __mul__(self, other):
- if isinstance(other, Vector3):
- v = other
- return Vector3(self.a.x * v.x + self.a.y * v.y + self.a.z * v.z,
- self.b.x * v.x + self.b.y * v.y + self.b.z * v.z,
- self.c.x * v.x + self.c.y * v.y + self.c.z * v.z)
- elif isinstance(other, Matrix3):
- m = other
- return Matrix3(Vector3(self.a.x * m.a.x + self.a.y * m.b.x + self.a.z * m.c.x,
- self.a.x * m.a.y + self.a.y * m.b.y + self.a.z * m.c.y,
- self.a.x * m.a.z + self.a.y * m.b.z + self.a.z * m.c.z),
- Vector3(self.b.x * m.a.x + self.b.y * m.b.x + self.b.z * m.c.x,
- self.b.x * m.a.y + self.b.y * m.b.y + self.b.z * m.c.y,
- self.b.x * m.a.z + self.b.y * m.b.z + self.b.z * m.c.z),
- Vector3(self.c.x * m.a.x + self.c.y * m.b.x + self.c.z * m.c.x,
- self.c.x * m.a.y + self.c.y * m.b.y + self.c.z * m.c.y,
- self.c.x * m.a.z + self.c.y * m.b.z + self.c.z * m.c.z))
- v = other
- return Matrix3(self.a * v, self.b * v, self.c * v)
-
- def __div__(self, v):
- return Matrix3(self.a / v, self.b / v, self.c / v)
-
- def __neg__(self):
- return Matrix3(-self.a, -self.b, -self.c)
-
- def __copy__(self):
- return Matrix3(self.a, self.b, self.c)
-
- copy = __copy__
-
- def rotate(self, g):
- '''rotate the matrix by a given amount on 3 axes'''
- temp_matrix = Matrix3()
- a = self.a
- b = self.b
- c = self.c
- temp_matrix.a.x = a.y * g.z - a.z * g.y
- temp_matrix.a.y = a.z * g.x - a.x * g.z
- temp_matrix.a.z = a.x * g.y - a.y * g.x
- temp_matrix.b.x = b.y * g.z - b.z * g.y
- temp_matrix.b.y = b.z * g.x - b.x * g.z
- temp_matrix.b.z = b.x * g.y - b.y * g.x
- temp_matrix.c.x = c.y * g.z - c.z * g.y
- temp_matrix.c.y = c.z * g.x - c.x * g.z
- temp_matrix.c.z = c.x * g.y - c.y * g.x
- self.a += temp_matrix.a
- self.b += temp_matrix.b
- self.c += temp_matrix.c
-
- def normalize(self):
- '''re-normalise a rotation matrix'''
- error = self.a * self.b
- t0 = self.a - (self.b * (0.5 * error))
- t1 = self.b - (self.a * (0.5 * error))
- t2 = t0 % t1
- self.a = t0 * (1.0 / t0.length())
- self.b = t1 * (1.0 / t1.length())
- self.c = t2 * (1.0 / t2.length())
-
- def trace(self):
- '''the trace of the matrix'''
- return self.a.x + self.b.y + self.c.z
-
-def test_euler():
- '''check that from_euler() and to_euler() are consistent'''
- m = Matrix3()
- from math import radians, degrees
- for r in range(-179, 179, 3):
- for p in range(-89, 89, 3):
- for y in range(-179, 179, 3):
- m.from_euler(radians(r), radians(p), radians(y))
- (r2, p2, y2) = m.to_euler()
- v1 = Vector3(r,p,y)
- v2 = Vector3(degrees(r2),degrees(p2),degrees(y2))
- diff = v1 - v2
- if diff.length() > 1.0e-12:
- print('EULER ERROR:', v1, v2, diff.length())
-
-if __name__ == "__main__":
- import doctest
- doctest.testmod()
- test_euler()
-
diff --git a/mavlink/share/pyshared/pymavlink/examples/sigloss.py b/mavlink/share/pyshared/pymavlink/examples/sigloss.py
deleted file mode 100644
index feb189d97..000000000
--- a/mavlink/share/pyshared/pymavlink/examples/sigloss.py
+++ /dev/null
@@ -1,57 +0,0 @@
-#!/usr/bin/env python
-
-'''
-show times when signal is lost
-'''
-
-import sys, time, os
-
-# allow import from the parent directory, where mavlink.py is
-sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..'))
-
-from optparse import OptionParser
-parser = OptionParser("sigloss.py [options]")
-parser.add_option("--no-timestamps",dest="notimestamps", action='store_true', help="Log doesn't have timestamps")
-parser.add_option("--planner",dest="planner", action='store_true', help="use planner file format")
-parser.add_option("--robust",dest="robust", action='store_true', help="Enable robust parsing (skip over bad data)")
-parser.add_option("--mav10", action='store_true', default=False, help="Use MAVLink protocol 1.0")
-parser.add_option("--deltat", type='float', default=1.0, help="loss threshold in seconds")
-
-(opts, args) = parser.parse_args()
-
-if opts.mav10:
- os.environ['MAVLINK10'] = '1'
-import mavutil
-
-if len(args) < 1:
- print("Usage: sigloss.py [options] <LOGFILE...>")
- sys.exit(1)
-
-def sigloss(logfile):
- '''work out signal loss times for a log file'''
- print("Processing log %s" % filename)
- mlog = mavutil.mavlink_connection(filename,
- planner_format=opts.planner,
- notimestamps=opts.notimestamps,
- robust_parsing=opts.robust)
-
- last_t = 0
-
- while True:
- m = mlog.recv_match()
- if m is None:
- return
- if opts.notimestamps:
- if not 'usec' in m._fieldnames:
- continue
- t = m.usec / 1.0e6
- else:
- t = m._timestamp
- if last_t != 0:
- if t - last_t > opts.deltat:
- print("Sig lost for %.1fs at %s" % (t-last_t, time.asctime(time.localtime(t))))
- last_t = t
-
-total = 0.0
-for filename in args:
- sigloss(filename)
diff --git a/mavlink/share/pyshared/pymavlink/examples/wptogpx.py b/mavlink/share/pyshared/pymavlink/examples/wptogpx.py
deleted file mode 100644
index 306f20af2..000000000
--- a/mavlink/share/pyshared/pymavlink/examples/wptogpx.py
+++ /dev/null
@@ -1,69 +0,0 @@
-#!/usr/bin/env python
-
-'''
-example program to extract GPS data from a waypoint file, and create a GPX
-file, for loading into google earth
-'''
-
-import sys, struct, time, os
-
-# allow import from the parent directory, where mavlink.py is
-sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..'))
-
-from optparse import OptionParser
-parser = OptionParser("wptogpx.py [options]")
-(opts, args) = parser.parse_args()
-
-import mavutil, mavwp
-
-if len(args) < 1:
- print("Usage: wptogpx.py <WPFILE>")
- sys.exit(1)
-
-def wp_to_gpx(infilename, outfilename):
- '''convert a wp file to a GPX file'''
-
- wp = mavwp.MAVWPLoader()
- wp.load(infilename)
- outf = open(outfilename, mode='w')
-
- def process_wp(w, i):
- t = time.localtime(i)
- outf.write('''<wpt lat="%s" lon="%s">
- <ele>%s</ele>
- <cmt>WP %u</cmt>
-</wpt>
-''' % (w.x, w.y, w.z, i))
-
- def add_header():
- outf.write('''<?xml version="1.0" encoding="UTF-8"?>
-<gpx
- version="1.0"
- creator="pymavlink"
- xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance"
- xmlns="http://www.topografix.com/GPX/1/0"
- xsi:schemaLocation="http://www.topografix.com/GPX/1/0 http://www.topografix.com/GPX/1/0/gpx.xsd">
-''')
-
- def add_footer():
- outf.write('''
-</gpx>
-''')
-
- add_header()
-
- count = 0
- for i in range(wp.count()):
- w = wp.wp(i)
- if w.frame == 3:
- w.z += wp.wp(0).z
- if w.command == 16:
- process_wp(w, i)
- count += 1
- add_footer()
- print("Created %s with %u points" % (outfilename, count))
-
-
-for infilename in args:
- outfilename = infilename + '.gpx'
- wp_to_gpx(infilename, outfilename)
diff --git a/mavlink/share/pyshared/pymavlink/fgFDM.py b/mavlink/share/pyshared/pymavlink/fgFDM.py
deleted file mode 100644
index f390e0a93..000000000
--- a/mavlink/share/pyshared/pymavlink/fgFDM.py
+++ /dev/null
@@ -1,209 +0,0 @@
-#!/usr/bin/env python
-# parse and construct FlightGear NET FDM packets
-# Andrew Tridgell, November 2011
-# released under GNU GPL version 2 or later
-
-import struct, math
-
-class fgFDMError(Exception):
- '''fgFDM error class'''
- def __init__(self, msg):
- Exception.__init__(self, msg)
- self.message = 'fgFDMError: ' + msg
-
-class fgFDMVariable(object):
- '''represent a single fgFDM variable'''
- def __init__(self, index, arraylength, units):
- self.index = index
- self.arraylength = arraylength
- self.units = units
-
-class fgFDMVariableList(object):
- '''represent a list of fgFDM variable'''
- def __init__(self):
- self.vars = {}
- self._nextidx = 0
-
- def add(self, varname, arraylength=1, units=None):
- self.vars[varname] = fgFDMVariable(self._nextidx, arraylength, units=units)
- self._nextidx += arraylength
-
-class fgFDM(object):
- '''a flightgear native FDM parser/generator'''
- def __init__(self):
- '''init a fgFDM object'''
- self.FG_NET_FDM_VERSION = 24
- self.pack_string = '>I 4x 3d 6f 11f 3f 2f I 4I 4f 4f 4f 4f 4f 4f 4f 4f 4f I 4f I 3I 3f 3f 3f I i f 10f'
- self.values = [0]*98
-
- self.FG_MAX_ENGINES = 4
- self.FG_MAX_WHEELS = 3
- self.FG_MAX_TANKS = 4
-
- # supported unit mappings
- self.unitmap = {
- ('radians', 'degrees') : math.degrees(1),
- ('rps', 'dps') : math.degrees(1),
- ('feet', 'meters') : 0.3048,
- ('fps', 'mps') : 0.3048,
- ('knots', 'mps') : 0.514444444,
- ('knots', 'fps') : 0.514444444/0.3048,
- ('fpss', 'mpss') : 0.3048,
- ('seconds', 'minutes') : 60,
- ('seconds', 'hours') : 3600,
- }
-
- # build a mapping between variable name and index in the values array
- # note that the order of this initialisation is critical - it must
- # match the wire structure
- self.mapping = fgFDMVariableList()
- self.mapping.add('version')
-
- # position
- self.mapping.add('longitude', units='radians') # geodetic (radians)
- self.mapping.add('latitude', units='radians') # geodetic (radians)
- self.mapping.add('altitude', units='meters') # above sea level (meters)
- self.mapping.add('agl', units='meters') # above ground level (meters)
-
- # attitude
- self.mapping.add('phi', units='radians') # roll (radians)
- self.mapping.add('theta', units='radians') # pitch (radians)
- self.mapping.add('psi', units='radians') # yaw or true heading (radians)
- self.mapping.add('alpha', units='radians') # angle of attack (radians)
- self.mapping.add('beta', units='radians') # side slip angle (radians)
-
- # Velocities
- self.mapping.add('phidot', units='rps') # roll rate (radians/sec)
- self.mapping.add('thetadot', units='rps') # pitch rate (radians/sec)
- self.mapping.add('psidot', units='rps') # yaw rate (radians/sec)
- self.mapping.add('vcas', units='fps') # calibrated airspeed
- self.mapping.add('climb_rate', units='fps') # feet per second
- self.mapping.add('v_north', units='fps') # north velocity in local/body frame, fps
- self.mapping.add('v_east', units='fps') # east velocity in local/body frame, fps
- self.mapping.add('v_down', units='fps') # down/vertical velocity in local/body frame, fps
- self.mapping.add('v_wind_body_north', units='fps') # north velocity in local/body frame
- self.mapping.add('v_wind_body_east', units='fps') # east velocity in local/body frame
- self.mapping.add('v_wind_body_down', units='fps') # down/vertical velocity in local/body
-
- # Accelerations
- self.mapping.add('A_X_pilot', units='fpss') # X accel in body frame ft/sec^2
- self.mapping.add('A_Y_pilot', units='fpss') # Y accel in body frame ft/sec^2
- self.mapping.add('A_Z_pilot', units='fpss') # Z accel in body frame ft/sec^2
-
- # Stall
- self.mapping.add('stall_warning') # 0.0 - 1.0 indicating the amount of stall
- self.mapping.add('slip_deg', units='degrees') # slip ball deflection
-
- # Engine status
- self.mapping.add('num_engines') # Number of valid engines
- self.mapping.add('eng_state', self.FG_MAX_ENGINES) # Engine state (off, cranking, running)
- self.mapping.add('rpm', self.FG_MAX_ENGINES) # Engine RPM rev/min
- self.mapping.add('fuel_flow', self.FG_MAX_ENGINES) # Fuel flow gallons/hr
- self.mapping.add('fuel_px', self.FG_MAX_ENGINES) # Fuel pressure psi
- self.mapping.add('egt', self.FG_MAX_ENGINES) # Exhuast gas temp deg F
- self.mapping.add('cht', self.FG_MAX_ENGINES) # Cylinder head temp deg F
- self.mapping.add('mp_osi', self.FG_MAX_ENGINES) # Manifold pressure
- self.mapping.add('tit', self.FG_MAX_ENGINES) # Turbine Inlet Temperature
- self.mapping.add('oil_temp', self.FG_MAX_ENGINES) # Oil temp deg F
- self.mapping.add('oil_px', self.FG_MAX_ENGINES) # Oil pressure psi
-
- # Consumables
- self.mapping.add('num_tanks') # Max number of fuel tanks
- self.mapping.add('fuel_quantity', self.FG_MAX_TANKS)
-
- # Gear status
- self.mapping.add('num_wheels')
- self.mapping.add('wow', self.FG_MAX_WHEELS)
- self.mapping.add('gear_pos', self.FG_MAX_WHEELS)
- self.mapping.add('gear_steer', self.FG_MAX_WHEELS)
- self.mapping.add('gear_compression', self.FG_MAX_WHEELS)
-
- # Environment
- self.mapping.add('cur_time', units='seconds') # current unix time
- self.mapping.add('warp', units='seconds') # offset in seconds to unix time
- self.mapping.add('visibility', units='meters') # visibility in meters (for env. effects)
-
- # Control surface positions (normalized values)
- self.mapping.add('elevator')
- self.mapping.add('elevator_trim_tab')
- self.mapping.add('left_flap')
- self.mapping.add('right_flap')
- self.mapping.add('left_aileron')
- self.mapping.add('right_aileron')
- self.mapping.add('rudder')
- self.mapping.add('nose_wheel')
- self.mapping.add('speedbrake')
- self.mapping.add('spoilers')
-
- self._packet_size = struct.calcsize(self.pack_string)
-
- self.set('version', self.FG_NET_FDM_VERSION)
-
- if len(self.values) != self.mapping._nextidx:
- raise fgFDMError('Invalid variable list in initialisation')
-
- def packet_size(self):
- '''return expected size of FG FDM packets'''
- return self._packet_size
-
- def convert(self, value, fromunits, tounits):
- '''convert a value from one set of units to another'''
- if fromunits == tounits:
- return value
- if (fromunits,tounits) in self.unitmap:
- return value * self.unitmap[(fromunits,tounits)]
- if (tounits,fromunits) in self.unitmap:
- return value / self.unitmap[(tounits,fromunits)]
- raise fgFDMError("unknown unit mapping (%s,%s)" % (fromunits, tounits))
-
-
- def units(self, varname):
- '''return the default units of a variable'''
- if not varname in self.mapping.vars:
- raise fgFDMError('Unknown variable %s' % varname)
- return self.mapping.vars[varname].units
-
-
- def variables(self):
- '''return a list of available variables'''
- return sorted(self.mapping.vars.keys(),
- key = lambda v : self.mapping.vars[v].index)
-
-
- def get(self, varname, idx=0, units=None):
- '''get a variable value'''
- if not varname in self.mapping.vars:
- raise fgFDMError('Unknown variable %s' % varname)
- if idx >= self.mapping.vars[varname].arraylength:
- raise fgFDMError('index of %s beyond end of array idx=%u arraylength=%u' % (
- varname, idx, self.mapping.vars[varname].arraylength))
- value = self.values[self.mapping.vars[varname].index + idx]
- if units:
- value = self.convert(value, self.mapping.vars[varname].units, units)
- return value
-
- def set(self, varname, value, idx=0, units=None):
- '''set a variable value'''
- if not varname in self.mapping.vars:
- raise fgFDMError('Unknown variable %s' % varname)
- if idx >= self.mapping.vars[varname].arraylength:
- raise fgFDMError('index of %s beyond end of array idx=%u arraylength=%u' % (
- varname, idx, self.mapping.vars[varname].arraylength))
- if units:
- value = self.convert(value, units, self.mapping.vars[varname].units)
- self.values[self.mapping.vars[varname].index + idx] = value
-
- def parse(self, buf):
- '''parse a FD FDM buffer'''
- try:
- t = struct.unpack(self.pack_string, buf)
- except struct.error, msg:
- raise fgFDMError('unable to parse - %s' % msg)
- self.values = list(t)
-
- def pack(self):
- '''pack a FD FDM buffer from current values'''
- for i in range(len(self.values)):
- if math.isnan(self.values[i]):
- self.values[i] = 0
- return struct.pack(self.pack_string, *self.values)
diff --git a/mavlink/share/pyshared/pymavlink/generator/.gitignore b/mavlink/share/pyshared/pymavlink/generator/.gitignore
deleted file mode 100644
index 0d20b6487..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/.gitignore
+++ /dev/null
@@ -1 +0,0 @@
-*.pyc
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/checksum.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/checksum.h
deleted file mode 100644
index b70991f5a..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/checksum.h
+++ /dev/null
@@ -1,89 +0,0 @@
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-#ifndef _CHECKSUM_H_
-#define _CHECKSUM_H_
-
-
-/**
- *
- * CALCULATE THE CHECKSUM
- *
- */
-
-#define X25_INIT_CRC 0xffff
-#define X25_VALIDATE_CRC 0xf0b8
-
-/**
- * @brief Accumulate the X.25 CRC by adding one char at a time.
- *
- * The checksum function adds the hash of one char at a time to the
- * 16 bit checksum (uint16_t).
- *
- * @param data new char to hash
- * @param crcAccum the already accumulated checksum
- **/
-static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum)
-{
- /*Accumulate one byte of data into the CRC*/
- uint8_t tmp;
-
- tmp = data ^ (uint8_t)(*crcAccum &0xff);
- tmp ^= (tmp<<4);
- *crcAccum = (*crcAccum>>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4);
-}
-
-/**
- * @brief Initiliaze the buffer for the X.25 CRC
- *
- * @param crcAccum the 16 bit X.25 CRC
- */
-static inline void crc_init(uint16_t* crcAccum)
-{
- *crcAccum = X25_INIT_CRC;
-}
-
-
-/**
- * @brief Calculates the X.25 checksum on a byte buffer
- *
- * @param pBuffer buffer containing the byte array to hash
- * @param length length of the byte array
- * @return the checksum over the buffer bytes
- **/
-static inline uint16_t crc_calculate(uint8_t* pBuffer, uint16_t length)
-{
- uint16_t crcTmp;
- crc_init(&crcTmp);
- while (length--) {
- crc_accumulate(*pBuffer++, &crcTmp);
- }
- return crcTmp;
-}
-
-/**
- * @brief Accumulate the X.25 CRC by adding an array of bytes
- *
- * The checksum function adds the hash of one char at a time to the
- * 16 bit checksum (uint16_t).
- *
- * @param data new bytes to hash
- * @param crcAccum the already accumulated checksum
- **/
-static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint8_t length)
-{
- const uint8_t *p = (const uint8_t *)pBuffer;
- while (length--) {
- crc_accumulate(*p++, crcAccum);
- }
-}
-
-
-
-
-#endif /* _CHECKSUM_H_ */
-
-#ifdef __cplusplus
-}
-#endif
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/mavlink_helpers.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/mavlink_helpers.h
deleted file mode 100644
index 98250e1ac..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/mavlink_helpers.h
+++ /dev/null
@@ -1,488 +0,0 @@
-#ifndef _MAVLINK_HELPERS_H_
-#define _MAVLINK_HELPERS_H_
-
-#include "string.h"
-#include "checksum.h"
-#include "mavlink_types.h"
-
-#ifndef MAVLINK_HELPER
-#define MAVLINK_HELPER
-#endif
-
-/*
- internal function to give access to the channel status for each channel
- */
-MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan)
-{
- static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS];
- return &m_mavlink_status[chan];
-}
-
-/**
- * @brief Finalize a MAVLink message with channel assignment
- *
- * This function calculates the checksum and sets length and aircraft id correctly.
- * It assumes that the message id and the payload are already correctly set. This function
- * can also be used if the message header has already been written before (as in mavlink_msg_xxx_pack
- * instead of mavlink_msg_xxx_pack_headerless), it just introduces little extra overhead.
- *
- * @param msg Message to finalize
- * @param system_id Id of the sending (this) system, 1-127
- * @param length Message length
- */
-#if MAVLINK_CRC_EXTRA
-MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
- uint8_t chan, uint8_t length, uint8_t crc_extra)
-#else
-MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
- uint8_t chan, uint8_t length)
-#endif
-{
- // This code part is the same for all messages;
- uint16_t checksum;
- msg->magic = MAVLINK_STX;
- msg->len = length;
- msg->sysid = system_id;
- msg->compid = component_id;
- // One sequence number per component
- msg->seq = mavlink_get_channel_status(chan)->current_tx_seq;
- mavlink_get_channel_status(chan)->current_tx_seq = mavlink_get_channel_status(chan)->current_tx_seq+1;
- checksum = crc_calculate((uint8_t*)&msg->len, length + MAVLINK_CORE_HEADER_LEN);
-#if MAVLINK_CRC_EXTRA
- crc_accumulate(crc_extra, &checksum);
-#endif
- mavlink_ck_a(msg) = (uint8_t)(checksum & 0xFF);
- mavlink_ck_b(msg) = (uint8_t)(checksum >> 8);
-
- return length + MAVLINK_NUM_NON_PAYLOAD_BYTES;
-}
-
-
-/**
- * @brief Finalize a MAVLink message with MAVLINK_COMM_0 as default channel
- */
-#if MAVLINK_CRC_EXTRA
-MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
- uint8_t length, uint8_t crc_extra)
-{
- return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length, crc_extra);
-}
-#else
-MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
- uint8_t length)
-{
- return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length);
-}
-#endif
-
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len);
-
-/**
- * @brief Finalize a MAVLink message with channel assignment and send
- */
-#if MAVLINK_CRC_EXTRA
-MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet,
- uint8_t length, uint8_t crc_extra)
-#else
-MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length)
-#endif
-{
- uint16_t checksum;
- uint8_t buf[MAVLINK_NUM_HEADER_BYTES];
- uint8_t ck[2];
- mavlink_status_t *status = mavlink_get_channel_status(chan);
- buf[0] = MAVLINK_STX;
- buf[1] = length;
- buf[2] = status->current_tx_seq;
- buf[3] = mavlink_system.sysid;
- buf[4] = mavlink_system.compid;
- buf[5] = msgid;
- status->current_tx_seq++;
- checksum = crc_calculate((uint8_t*)&buf[1], MAVLINK_CORE_HEADER_LEN);
- crc_accumulate_buffer(&checksum, packet, length);
-#if MAVLINK_CRC_EXTRA
- crc_accumulate(crc_extra, &checksum);
-#endif
- ck[0] = (uint8_t)(checksum & 0xFF);
- ck[1] = (uint8_t)(checksum >> 8);
-
- MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length);
- _mavlink_send_uart(chan, (const char *)buf, MAVLINK_NUM_HEADER_BYTES);
- _mavlink_send_uart(chan, packet, length);
- _mavlink_send_uart(chan, (const char *)ck, 2);
- MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length);
-}
-#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-/**
- * @brief Pack a message to send it over a serial byte stream
- */
-MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg)
-{
- memcpy(buffer, (uint8_t *)&msg->magic, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len);
- return MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len;
-}
-
-union __mavlink_bitfield {
- uint8_t uint8;
- int8_t int8;
- uint16_t uint16;
- int16_t int16;
- uint32_t uint32;
- int32_t int32;
-};
-
-
-MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg)
-{
- crc_init(&msg->checksum);
-}
-
-MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c)
-{
- crc_accumulate(c, &msg->checksum);
-}
-
-/**
- * This is a convenience function which handles the complete MAVLink parsing.
- * the function will parse one byte at a time and return the complete packet once
- * it could be successfully decoded. Checksum and other failures will be silently
- * ignored.
- *
- * @param chan ID of the current channel. This allows to parse different channels with this function.
- * a channel is not a physical message channel like a serial port, but a logic partition of
- * the communication streams in this case. COMM_NB is the limit for the number of channels
- * on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows
- * @param c The char to barse
- *
- * @param returnMsg NULL if no message could be decoded, the message data else
- * @return 0 if no message could be decoded, 1 else
- *
- * A typical use scenario of this function call is:
- *
- * @code
- * #include <inttypes.h> // For fixed-width uint8_t type
- *
- * mavlink_message_t msg;
- * int chan = 0;
- *
- *
- * while(serial.bytesAvailable > 0)
- * {
- * uint8_t byte = serial.getNextByte();
- * if (mavlink_parse_char(chan, byte, &msg))
- * {
- * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid);
- * }
- * }
- *
- *
- * @endcode
- */
-MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status)
-{
- static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NUM_BUFFERS];
-
- /*
- default message crc function. You can override this per-system to
- put this data in a different memory segment
- */
-#if MAVLINK_CRC_EXTRA
-#ifndef MAVLINK_MESSAGE_CRC
- static const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS;
-#define MAVLINK_MESSAGE_CRC(msgid) mavlink_message_crcs[msgid]
-#endif
-#endif
-
- mavlink_message_t* rxmsg = &m_mavlink_message[chan]; ///< The currently decoded message
- mavlink_status_t* status = mavlink_get_channel_status(chan); ///< The current decode status
- int bufferIndex = 0;
-
- status->msg_received = 0;
-
- switch (status->parse_state)
- {
- case MAVLINK_PARSE_STATE_UNINIT:
- case MAVLINK_PARSE_STATE_IDLE:
- if (c == MAVLINK_STX)
- {
- status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
- rxmsg->len = 0;
- mavlink_start_checksum(rxmsg);
- }
- break;
-
- case MAVLINK_PARSE_STATE_GOT_STX:
- if (status->msg_received
- /* Support shorter buffers than the
- default maximum packet size */
-#if (MAVLINK_MAX_PAYLOAD_LEN < 255)
- || c > MAVLINK_MAX_PAYLOAD_LEN
-#endif
- )
- {
- status->buffer_overrun++;
- status->parse_error++;
- status->msg_received = 0;
- status->parse_state = MAVLINK_PARSE_STATE_IDLE;
- }
- else
- {
- // NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2
- rxmsg->len = c;
- status->packet_idx = 0;
- mavlink_update_checksum(rxmsg, c);
- status->parse_state = MAVLINK_PARSE_STATE_GOT_LENGTH;
- }
- break;
-
- case MAVLINK_PARSE_STATE_GOT_LENGTH:
- rxmsg->seq = c;
- mavlink_update_checksum(rxmsg, c);
- status->parse_state = MAVLINK_PARSE_STATE_GOT_SEQ;
- break;
-
- case MAVLINK_PARSE_STATE_GOT_SEQ:
- rxmsg->sysid = c;
- mavlink_update_checksum(rxmsg, c);
- status->parse_state = MAVLINK_PARSE_STATE_GOT_SYSID;
- break;
-
- case MAVLINK_PARSE_STATE_GOT_SYSID:
- rxmsg->compid = c;
- mavlink_update_checksum(rxmsg, c);
- status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPID;
- break;
-
- case MAVLINK_PARSE_STATE_GOT_COMPID:
- rxmsg->msgid = c;
- mavlink_update_checksum(rxmsg, c);
- if (rxmsg->len == 0)
- {
- status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD;
- }
- else
- {
- status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID;
- }
- break;
-
- case MAVLINK_PARSE_STATE_GOT_MSGID:
- _MAV_PAYLOAD(rxmsg)[status->packet_idx++] = (char)c;
- mavlink_update_checksum(rxmsg, c);
- if (status->packet_idx == rxmsg->len)
- {
- status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD;
- }
- break;
-
- case MAVLINK_PARSE_STATE_GOT_PAYLOAD:
-#if MAVLINK_CRC_EXTRA
- mavlink_update_checksum(rxmsg, MAVLINK_MESSAGE_CRC(rxmsg->msgid));
-#endif
- if (c != (rxmsg->checksum & 0xFF)) {
- // Check first checksum byte
- status->parse_error++;
- status->msg_received = 0;
- status->parse_state = MAVLINK_PARSE_STATE_IDLE;
- if (c == MAVLINK_STX)
- {
- status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
- rxmsg->len = 0;
- mavlink_start_checksum(rxmsg);
- }
- }
- else
- {
- status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1;
- }
- break;
-
- case MAVLINK_PARSE_STATE_GOT_CRC1:
- if (c != (rxmsg->checksum >> 8)) {
- // Check second checksum byte
- status->parse_error++;
- status->msg_received = 0;
- status->parse_state = MAVLINK_PARSE_STATE_IDLE;
- if (c == MAVLINK_STX)
- {
- status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
- rxmsg->len = 0;
- mavlink_start_checksum(rxmsg);
- }
- }
- else
- {
- // Successfully got message
- status->msg_received = 1;
- status->parse_state = MAVLINK_PARSE_STATE_IDLE;
- memcpy(r_message, rxmsg, sizeof(mavlink_message_t));
- }
- break;
- }
-
- bufferIndex++;
- // If a message has been sucessfully decoded, check index
- if (status->msg_received == 1)
- {
- //while(status->current_seq != rxmsg->seq)
- //{
- // status->packet_rx_drop_count++;
- // status->current_seq++;
- //}
- status->current_rx_seq = rxmsg->seq;
- // Initial condition: If no packet has been received so far, drop count is undefined
- if (status->packet_rx_success_count == 0) status->packet_rx_drop_count = 0;
- // Count this packet as received
- status->packet_rx_success_count++;
- }
-
- r_mavlink_status->current_rx_seq = status->current_rx_seq+1;
- r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count;
- r_mavlink_status->packet_rx_drop_count = status->parse_error;
- status->parse_error = 0;
- return status->msg_received;
-}
-
-/**
- * @brief Put a bitfield of length 1-32 bit into the buffer
- *
- * @param b the value to add, will be encoded in the bitfield
- * @param bits number of bits to use to encode b, e.g. 1 for boolean, 2, 3, etc.
- * @param packet_index the position in the packet (the index of the first byte to use)
- * @param bit_index the position in the byte (the index of the first bit to use)
- * @param buffer packet buffer to write into
- * @return new position of the last used byte in the buffer
- */
-MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index, uint8_t* r_bit_index, uint8_t* buffer)
-{
- uint16_t bits_remain = bits;
- // Transform number into network order
- int32_t v;
- uint8_t i_bit_index, i_byte_index, curr_bits_n;
-#if MAVLINK_NEED_BYTE_SWAP
- union {
- int32_t i;
- uint8_t b[4];
- } bin, bout;
- bin.i = b;
- bout.b[0] = bin.b[3];
- bout.b[1] = bin.b[2];
- bout.b[2] = bin.b[1];
- bout.b[3] = bin.b[0];
- v = bout.i;
-#else
- v = b;
-#endif
-
- // buffer in
- // 01100000 01000000 00000000 11110001
- // buffer out
- // 11110001 00000000 01000000 01100000
-
- // Existing partly filled byte (four free slots)
- // 0111xxxx
-
- // Mask n free bits
- // 00001111 = 2^0 + 2^1 + 2^2 + 2^3 = 2^n - 1
- // = ((uint32_t)(1 << n)) - 1; // = 2^n - 1
-
- // Shift n bits into the right position
- // out = in >> n;
-
- // Mask and shift bytes
- i_bit_index = bit_index;
- i_byte_index = packet_index;
- if (bit_index > 0)
- {
- // If bits were available at start, they were available
- // in the byte before the current index
- i_byte_index--;
- }
-
- // While bits have not been packed yet
- while (bits_remain > 0)
- {
- // Bits still have to be packed
- // there can be more than 8 bits, so
- // we might have to pack them into more than one byte
-
- // First pack everything we can into the current 'open' byte
- //curr_bits_n = bits_remain << 3; // Equals bits_remain mod 8
- //FIXME
- if (bits_remain <= (uint8_t)(8 - i_bit_index))
- {
- // Enough space
- curr_bits_n = (uint8_t)bits_remain;
- }
- else
- {
- curr_bits_n = (8 - i_bit_index);
- }
-
- // Pack these n bits into the current byte
- // Mask out whatever was at that position with ones (xxx11111)
- buffer[i_byte_index] &= (0xFF >> (8 - curr_bits_n));
- // Put content to this position, by masking out the non-used part
- buffer[i_byte_index] |= ((0x00 << curr_bits_n) & v);
-
- // Increment the bit index
- i_bit_index += curr_bits_n;
-
- // Now proceed to the next byte, if necessary
- bits_remain -= curr_bits_n;
- if (bits_remain > 0)
- {
- // Offer another 8 bits / one byte
- i_byte_index++;
- i_bit_index = 0;
- }
- }
-
- *r_bit_index = i_bit_index;
- // If a partly filled byte is present, mark this as consumed
- if (i_bit_index != 7) i_byte_index++;
- return i_byte_index - packet_index;
-}
-
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-// To make MAVLink work on your MCU, define comm_send_ch() if you wish
-// to send 1 byte at a time, or MAVLINK_SEND_UART_BYTES() to send a
-// whole packet at a time
-
-/*
-
-#include "mavlink_types.h"
-
-void comm_send_ch(mavlink_channel_t chan, uint8_t ch)
-{
- if (chan == MAVLINK_COMM_0)
- {
- uart0_transmit(ch);
- }
- if (chan == MAVLINK_COMM_1)
- {
- uart1_transmit(ch);
- }
-}
- */
-
-MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len)
-{
-#ifdef MAVLINK_SEND_UART_BYTES
- /* this is the more efficient approach, if the platform
- defines it */
- MAVLINK_SEND_UART_BYTES(chan, (uint8_t *)buf, len);
-#else
- /* fallback to one byte at a time */
- uint16_t i;
- for (i = 0; i < len; i++) {
- comm_send_ch(chan, (uint8_t)buf[i]);
- }
-#endif
-}
-#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-#endif /* _MAVLINK_HELPERS_H_ */
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/mavlink_types.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/mavlink_types.h
deleted file mode 100644
index 630cb84b7..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/mavlink_types.h
+++ /dev/null
@@ -1,300 +0,0 @@
-#ifndef MAVLINK_TYPES_H_
-#define MAVLINK_TYPES_H_
-
-#include "inttypes.h"
-
-enum MAV_CLASS
-{
- MAV_CLASS_GENERIC = 0, ///< Generic autopilot, full support for everything
- MAV_CLASS_PIXHAWK = 1, ///< PIXHAWK autopilot, http://pixhawk.ethz.ch
- MAV_CLASS_SLUGS = 2, ///< SLUGS autopilot, http://slugsuav.soe.ucsc.edu
- MAV_CLASS_ARDUPILOTMEGA = 3, ///< ArduPilotMega / ArduCopter, http://diydrones.com
- MAV_CLASS_OPENPILOT = 4, ///< OpenPilot, http://openpilot.org
- MAV_CLASS_GENERIC_MISSION_WAYPOINTS_ONLY = 5, ///< Generic autopilot only supporting simple waypoints
- MAV_CLASS_GENERIC_MISSION_NAVIGATION_ONLY = 6, ///< Generic autopilot supporting waypoints and other simple navigation commands
- MAV_CLASS_GENERIC_MISSION_FULL = 7, ///< Generic autopilot supporting the full mission command set
- MAV_CLASS_NONE = 8, ///< No valid autopilot
- MAV_CLASS_NB ///< Number of autopilot classes
-};
-
-enum MAV_ACTION
-{
- MAV_ACTION_HOLD = 0,
- MAV_ACTION_MOTORS_START = 1,
- MAV_ACTION_LAUNCH = 2,
- MAV_ACTION_RETURN = 3,
- MAV_ACTION_EMCY_LAND = 4,
- MAV_ACTION_EMCY_KILL = 5,
- MAV_ACTION_CONFIRM_KILL = 6,
- MAV_ACTION_CONTINUE = 7,
- MAV_ACTION_MOTORS_STOP = 8,
- MAV_ACTION_HALT = 9,
- MAV_ACTION_SHUTDOWN = 10,
- MAV_ACTION_REBOOT = 11,
- MAV_ACTION_SET_MANUAL = 12,
- MAV_ACTION_SET_AUTO = 13,
- MAV_ACTION_STORAGE_READ = 14,
- MAV_ACTION_STORAGE_WRITE = 15,
- MAV_ACTION_CALIBRATE_RC = 16,
- MAV_ACTION_CALIBRATE_GYRO = 17,
- MAV_ACTION_CALIBRATE_MAG = 18,
- MAV_ACTION_CALIBRATE_ACC = 19,
- MAV_ACTION_CALIBRATE_PRESSURE = 20,
- MAV_ACTION_REC_START = 21,
- MAV_ACTION_REC_PAUSE = 22,
- MAV_ACTION_REC_STOP = 23,
- MAV_ACTION_TAKEOFF = 24,
- MAV_ACTION_NAVIGATE = 25,
- MAV_ACTION_LAND = 26,
- MAV_ACTION_LOITER = 27,
- MAV_ACTION_SET_ORIGIN = 28,
- MAV_ACTION_RELAY_ON = 29,
- MAV_ACTION_RELAY_OFF = 30,
- MAV_ACTION_GET_IMAGE = 31,
- MAV_ACTION_VIDEO_START = 32,
- MAV_ACTION_VIDEO_STOP = 33,
- MAV_ACTION_RESET_MAP = 34,
- MAV_ACTION_RESET_PLAN = 35,
- MAV_ACTION_DELAY_BEFORE_COMMAND = 36,
- MAV_ACTION_ASCEND_AT_RATE = 37,
- MAV_ACTION_CHANGE_MODE = 38,
- MAV_ACTION_LOITER_MAX_TURNS = 39,
- MAV_ACTION_LOITER_MAX_TIME = 40,
- MAV_ACTION_START_HILSIM = 41,
- MAV_ACTION_STOP_HILSIM = 42,
- MAV_ACTION_NB ///< Number of MAV actions
-};
-
-enum MAV_MODE
-{
- MAV_MODE_UNINIT = 0, ///< System is in undefined state
- MAV_MODE_LOCKED = 1, ///< Motors are blocked, system is safe
- MAV_MODE_MANUAL = 2, ///< System is allowed to be active, under manual (RC) control
- MAV_MODE_GUIDED = 3, ///< System is allowed to be active, under autonomous control, manual setpoint
- MAV_MODE_AUTO = 4, ///< System is allowed to be active, under autonomous control and navigation
- MAV_MODE_TEST1 = 5, ///< Generic test mode, for custom use
- MAV_MODE_TEST2 = 6, ///< Generic test mode, for custom use
- MAV_MODE_TEST3 = 7, ///< Generic test mode, for custom use
- MAV_MODE_READY = 8, ///< System is ready, motors are unblocked, but controllers are inactive
- MAV_MODE_RC_TRAINING = 9 ///< System is blocked, only RC valued are read and reported back
-};
-
-enum MAV_STATE
-{
- MAV_STATE_UNINIT = 0,
- MAV_STATE_BOOT,
- MAV_STATE_CALIBRATING,
- MAV_STATE_STANDBY,
- MAV_STATE_ACTIVE,
- MAV_STATE_CRITICAL,
- MAV_STATE_EMERGENCY,
- MAV_STATE_HILSIM,
- MAV_STATE_POWEROFF
-};
-
-enum MAV_NAV
-{
- MAV_NAV_GROUNDED = 0,
- MAV_NAV_LIFTOFF,
- MAV_NAV_HOLD,
- MAV_NAV_WAYPOINT,
- MAV_NAV_VECTOR,
- MAV_NAV_RETURNING,
- MAV_NAV_LANDING,
- MAV_NAV_LOST,
- MAV_NAV_LOITER,
- MAV_NAV_FREE_DRIFT
-};
-
-enum MAV_TYPE
-{
- MAV_GENERIC = 0,
- MAV_FIXED_WING = 1,
- MAV_QUADROTOR = 2,
- MAV_COAXIAL = 3,
- MAV_HELICOPTER = 4,
- MAV_GROUND = 5,
- OCU = 6,
- MAV_AIRSHIP = 7,
- MAV_FREE_BALLOON = 8,
- MAV_ROCKET = 9,
- UGV_GROUND_ROVER = 10,
- UGV_SURFACE_SHIP = 11
-};
-
-enum MAV_AUTOPILOT_TYPE
-{
- MAV_AUTOPILOT_GENERIC = 0,
- MAV_AUTOPILOT_PIXHAWK = 1,
- MAV_AUTOPILOT_SLUGS = 2,
- MAV_AUTOPILOT_ARDUPILOTMEGA = 3,
- MAV_AUTOPILOT_NONE = 4
-};
-
-enum MAV_COMPONENT
-{
- MAV_COMP_ID_GPS,
- MAV_COMP_ID_WAYPOINTPLANNER,
- MAV_COMP_ID_BLOBTRACKER,
- MAV_COMP_ID_PATHPLANNER,
- MAV_COMP_ID_AIRSLAM,
- MAV_COMP_ID_MAPPER,
- MAV_COMP_ID_CAMERA,
- MAV_COMP_ID_RADIO = 68,
- MAV_COMP_ID_IMU = 200,
- MAV_COMP_ID_IMU_2 = 201,
- MAV_COMP_ID_IMU_3 = 202,
- MAV_COMP_ID_UDP_BRIDGE = 240,
- MAV_COMP_ID_UART_BRIDGE = 241,
- MAV_COMP_ID_SYSTEM_CONTROL = 250
-};
-
-enum MAV_FRAME
-{
- MAV_FRAME_GLOBAL = 0,
- MAV_FRAME_LOCAL = 1,
- MAV_FRAME_MISSION = 2,
- MAV_FRAME_GLOBAL_RELATIVE_ALT = 3,
- MAV_FRAME_LOCAL_ENU = 4
-};
-
-enum MAVLINK_DATA_STREAM_TYPE
-{
- MAVLINK_DATA_STREAM_IMG_JPEG,
- MAVLINK_DATA_STREAM_IMG_BMP,
- MAVLINK_DATA_STREAM_IMG_RAW8U,
- MAVLINK_DATA_STREAM_IMG_RAW32U,
- MAVLINK_DATA_STREAM_IMG_PGM,
- MAVLINK_DATA_STREAM_IMG_PNG
-};
-
-#ifndef MAVLINK_MAX_PAYLOAD_LEN
-// it is possible to override this, but be careful!
-#define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length
-#endif
-
-#define MAVLINK_CORE_HEADER_LEN 5 ///< Length of core header (of the comm. layer): message length (1 byte) + message sequence (1 byte) + message system id (1 byte) + message component id (1 byte) + message type id (1 byte)
-#define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1) ///< Length of all header bytes, including core and checksum
-#define MAVLINK_NUM_CHECKSUM_BYTES 2
-#define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES)
-
-#define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) ///< Maximum packet length
-
-typedef struct param_union {
- union {
- float param_float;
- int32_t param_int32;
- uint32_t param_uint32;
- };
- uint8_t type;
-} mavlink_param_union_t;
-
-typedef struct __mavlink_system {
- uint8_t sysid; ///< Used by the MAVLink message_xx_send() convenience function
- uint8_t compid; ///< Used by the MAVLink message_xx_send() convenience function
- uint8_t type; ///< Unused, can be used by user to store the system's type
- uint8_t state; ///< Unused, can be used by user to store the system's state
- uint8_t mode; ///< Unused, can be used by user to store the system's mode
- uint8_t nav_mode; ///< Unused, can be used by user to store the system's navigation mode
-} mavlink_system_t;
-
-typedef struct __mavlink_message {
- uint16_t checksum; /// sent at end of packet
- uint8_t magic; ///< protocol magic marker
- uint8_t len; ///< Length of payload
- uint8_t seq; ///< Sequence of packet
- uint8_t sysid; ///< ID of message sender system/aircraft
- uint8_t compid; ///< ID of the message sender component
- uint8_t msgid; ///< ID of message in payload
- uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8];
-} mavlink_message_t;
-
-typedef enum {
- MAVLINK_TYPE_CHAR = 0,
- MAVLINK_TYPE_UINT8_T = 1,
- MAVLINK_TYPE_INT8_T = 2,
- MAVLINK_TYPE_UINT16_T = 3,
- MAVLINK_TYPE_INT16_T = 4,
- MAVLINK_TYPE_UINT32_T = 5,
- MAVLINK_TYPE_INT32_T = 6,
- MAVLINK_TYPE_UINT64_T = 7,
- MAVLINK_TYPE_INT64_T = 8,
- MAVLINK_TYPE_FLOAT = 9,
- MAVLINK_TYPE_DOUBLE = 10
-} mavlink_message_type_t;
-
-#define MAVLINK_MAX_FIELDS 64
-
-typedef struct __mavlink_field_info {
- const char *name; // name of this field
- const char *print_format; // printing format hint, or NULL
- mavlink_message_type_t type; // type of this field
- unsigned array_length; // if non-zero, field is an array
- unsigned wire_offset; // offset of each field in the payload
- unsigned structure_offset; // offset in a C structure
-} mavlink_field_info_t;
-
-// note that in this structure the order of fields is the order
-// in the XML file, not necessary the wire order
-typedef struct __mavlink_message_info {
- const char *name; // name of the message
- unsigned num_fields; // how many fields in this message
- mavlink_field_info_t fields[MAVLINK_MAX_FIELDS]; // field information
-} mavlink_message_info_t;
-
-#define _MAV_PAYLOAD(msg) ((char *)(&(msg)->payload64[0]))
-#define _MAV_PAYLOAD_NON_CONST(msg) ((char *)(&((msg)->payload64[0])))
-
-// checksum is immediately after the payload bytes
-#define mavlink_ck_a(msg) *(msg->len + (uint8_t *)_MAV_PAYLOAD(msg))
-#define mavlink_ck_b(msg) *((msg->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD(msg))
-
-typedef enum {
- MAVLINK_COMM_0,
- MAVLINK_COMM_1,
- MAVLINK_COMM_2,
- MAVLINK_COMM_3
-} mavlink_channel_t;
-
-/*
- * applications can set MAVLINK_COMM_NUM_BUFFERS to the maximum number
- * of buffers they will use. If more are used, then the result will be
- * a stack overrun
- */
-#ifndef MAVLINK_COMM_NUM_BUFFERS
-#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32)
-# define MAVLINK_COMM_NUM_BUFFERS 16
-#else
-# define MAVLINK_COMM_NUM_BUFFERS 4
-#endif
-#endif
-
-typedef enum {
- MAVLINK_PARSE_STATE_UNINIT=0,
- MAVLINK_PARSE_STATE_IDLE,
- MAVLINK_PARSE_STATE_GOT_STX,
- MAVLINK_PARSE_STATE_GOT_SEQ,
- MAVLINK_PARSE_STATE_GOT_LENGTH,
- MAVLINK_PARSE_STATE_GOT_SYSID,
- MAVLINK_PARSE_STATE_GOT_COMPID,
- MAVLINK_PARSE_STATE_GOT_MSGID,
- MAVLINK_PARSE_STATE_GOT_PAYLOAD,
- MAVLINK_PARSE_STATE_GOT_CRC1
-} mavlink_parse_state_t; ///< The state machine for the comm parser
-
-typedef struct __mavlink_status {
- uint8_t msg_received; ///< Number of received messages
- uint8_t buffer_overrun; ///< Number of buffer overruns
- uint8_t parse_error; ///< Number of parse errors
- mavlink_parse_state_t parse_state; ///< Parsing state machine
- uint8_t packet_idx; ///< Index in current packet
- uint8_t current_rx_seq; ///< Sequence number of last packet received
- uint8_t current_tx_seq; ///< Sequence number of last packet sent
- uint16_t packet_rx_success_count; ///< Received packets
- uint16_t packet_rx_drop_count; ///< Number of packet drops
-} mavlink_status_t;
-
-#define MAVLINK_BIG_ENDIAN 0
-#define MAVLINK_LITTLE_ENDIAN 1
-
-#endif /* MAVLINK_TYPES_H_ */
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/protocol.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/protocol.h
deleted file mode 100644
index 05195c369..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/protocol.h
+++ /dev/null
@@ -1,319 +0,0 @@
-#ifndef _MAVLINK_PROTOCOL_H_
-#define _MAVLINK_PROTOCOL_H_
-
-#include "string.h"
-#include "mavlink_types.h"
-
-/*
- If you want MAVLink on a system that is native big-endian,
- you need to define NATIVE_BIG_ENDIAN
-*/
-#ifdef NATIVE_BIG_ENDIAN
-# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN == MAVLINK_LITTLE_ENDIAN)
-#else
-# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN != MAVLINK_LITTLE_ENDIAN)
-#endif
-
-#ifndef MAVLINK_STACK_BUFFER
-#define MAVLINK_STACK_BUFFER 0
-#endif
-
-#ifndef MAVLINK_AVOID_GCC_STACK_BUG
-# define MAVLINK_AVOID_GCC_STACK_BUG defined(__GNUC__)
-#endif
-
-#ifndef MAVLINK_ASSERT
-#define MAVLINK_ASSERT(x)
-#endif
-
-#ifndef MAVLINK_START_UART_SEND
-#define MAVLINK_START_UART_SEND(chan, length)
-#endif
-
-#ifndef MAVLINK_END_UART_SEND
-#define MAVLINK_END_UART_SEND(chan, length)
-#endif
-
-#ifdef MAVLINK_SEPARATE_HELPERS
-#define MAVLINK_HELPER
-#else
-#define MAVLINK_HELPER static inline
-#include "mavlink_helpers.h"
-#endif // MAVLINK_SEPARATE_HELPERS
-
-/* always include the prototypes to ensure we don't get out of sync */
-MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan);
-#if MAVLINK_CRC_EXTRA
-MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
- uint8_t chan, uint8_t length, uint8_t crc_extra);
-MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
- uint8_t length, uint8_t crc_extra);
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet,
- uint8_t length, uint8_t crc_extra);
-#endif
-#else
-MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
- uint8_t chan, uint8_t length);
-MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
- uint8_t length);
-MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length);
-#endif // MAVLINK_CRC_EXTRA
-MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg);
-MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg);
-MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c);
-MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status);
-MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index,
- uint8_t* r_bit_index, uint8_t* buffer);
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len);
-#endif
-
-/**
- * @brief Get the required buffer size for this message
- */
-static inline uint16_t mavlink_msg_get_send_buffer_length(const mavlink_message_t* msg)
-{
- return msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES;
-}
-
-#if MAVLINK_NEED_BYTE_SWAP
-static inline void byte_swap_2(char *dst, const char *src)
-{
- dst[0] = src[1];
- dst[1] = src[0];
-}
-static inline void byte_swap_4(char *dst, const char *src)
-{
- dst[0] = src[3];
- dst[1] = src[2];
- dst[2] = src[1];
- dst[3] = src[0];
-}
-static inline void byte_swap_8(char *dst, const char *src)
-{
- dst[0] = src[7];
- dst[1] = src[6];
- dst[2] = src[5];
- dst[3] = src[4];
- dst[4] = src[3];
- dst[5] = src[2];
- dst[6] = src[1];
- dst[7] = src[0];
-}
-#elif !MAVLINK_ALIGNED_FIELDS
-static inline void byte_copy_2(char *dst, const char *src)
-{
- dst[0] = src[0];
- dst[1] = src[1];
-}
-static inline void byte_copy_4(char *dst, const char *src)
-{
- dst[0] = src[0];
- dst[1] = src[1];
- dst[2] = src[2];
- dst[3] = src[3];
-}
-static inline void byte_copy_8(char *dst, const char *src)
-{
- memcpy(dst, src, 8);
-}
-#endif
-
-#define _mav_put_uint8_t(buf, wire_offset, b) buf[wire_offset] = (uint8_t)b
-#define _mav_put_int8_t(buf, wire_offset, b) buf[wire_offset] = (int8_t)b
-#define _mav_put_char(buf, wire_offset, b) buf[wire_offset] = b
-
-#if MAVLINK_NEED_BYTE_SWAP
-#define _mav_put_uint16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b)
-#define _mav_put_int16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b)
-#define _mav_put_uint32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b)
-#define _mav_put_int32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b)
-#define _mav_put_uint64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b)
-#define _mav_put_int64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b)
-#define _mav_put_float(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b)
-#define _mav_put_double(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b)
-#elif !MAVLINK_ALIGNED_FIELDS
-#define _mav_put_uint16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b)
-#define _mav_put_int16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b)
-#define _mav_put_uint32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b)
-#define _mav_put_int32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b)
-#define _mav_put_uint64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b)
-#define _mav_put_int64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b)
-#define _mav_put_float(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b)
-#define _mav_put_double(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b)
-#else
-#define _mav_put_uint16_t(buf, wire_offset, b) *(uint16_t *)&buf[wire_offset] = b
-#define _mav_put_int16_t(buf, wire_offset, b) *(int16_t *)&buf[wire_offset] = b
-#define _mav_put_uint32_t(buf, wire_offset, b) *(uint32_t *)&buf[wire_offset] = b
-#define _mav_put_int32_t(buf, wire_offset, b) *(int32_t *)&buf[wire_offset] = b
-#define _mav_put_uint64_t(buf, wire_offset, b) *(uint64_t *)&buf[wire_offset] = b
-#define _mav_put_int64_t(buf, wire_offset, b) *(int64_t *)&buf[wire_offset] = b
-#define _mav_put_float(buf, wire_offset, b) *(float *)&buf[wire_offset] = b
-#define _mav_put_double(buf, wire_offset, b) *(double *)&buf[wire_offset] = b
-#endif
-
-/*
- like memcpy(), but if src is NULL, do a memset to zero
- */
-static void mav_array_memcpy(void *dest, const void *src, size_t n)
-{
- if (src == NULL) {
- memset(dest, 0, n);
- } else {
- memcpy(dest, src, n);
- }
-}
-
-/*
- * Place a char array into a buffer
- */
-static inline void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length)
-{
- mav_array_memcpy(&buf[wire_offset], b, array_length);
-}
-
-/*
- * Place a uint8_t array into a buffer
- */
-static inline void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length)
-{
- mav_array_memcpy(&buf[wire_offset], b, array_length);
-}
-
-/*
- * Place a int8_t array into a buffer
- */
-static inline void _mav_put_int8_t_array(char *buf, uint8_t wire_offset, const int8_t *b, uint8_t array_length)
-{
- mav_array_memcpy(&buf[wire_offset], b, array_length);
-}
-
-#if MAVLINK_NEED_BYTE_SWAP
-#define _MAV_PUT_ARRAY(TYPE, V) \
-static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \
-{ \
- if (b == NULL) { \
- memset(&buf[wire_offset], 0, array_length*sizeof(TYPE)); \
- } else { \
- uint16_t i; \
- for (i=0; i<array_length; i++) { \
- _mav_put_## TYPE (buf, wire_offset+(i*sizeof(TYPE)), b[i]); \
- } \
- } \
-}
-#else
-#define _MAV_PUT_ARRAY(TYPE, V) \
-static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \
-{ \
- mav_array_memcpy(&buf[wire_offset], b, array_length*sizeof(TYPE)); \
-}
-#endif
-
-_MAV_PUT_ARRAY(uint16_t, u16)
-_MAV_PUT_ARRAY(uint32_t, u32)
-_MAV_PUT_ARRAY(uint64_t, u64)
-_MAV_PUT_ARRAY(int16_t, i16)
-_MAV_PUT_ARRAY(int32_t, i32)
-_MAV_PUT_ARRAY(int64_t, i64)
-_MAV_PUT_ARRAY(float, f)
-_MAV_PUT_ARRAY(double, d)
-
-#define _MAV_RETURN_char(msg, wire_offset) _MAV_PAYLOAD(msg)[wire_offset]
-#define _MAV_RETURN_int8_t(msg, wire_offset) (int8_t)_MAV_PAYLOAD(msg)[wire_offset]
-#define _MAV_RETURN_uint8_t(msg, wire_offset) (uint8_t)_MAV_PAYLOAD(msg)[wire_offset]
-
-#if MAVLINK_NEED_BYTE_SWAP
-#define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \
-static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
-{ TYPE r; byte_swap_## SIZE((char*)&r, &_MAV_PAYLOAD(msg)[ofs]); return r; }
-
-_MAV_MSG_RETURN_TYPE(uint16_t, 2)
-_MAV_MSG_RETURN_TYPE(int16_t, 2)
-_MAV_MSG_RETURN_TYPE(uint32_t, 4)
-_MAV_MSG_RETURN_TYPE(int32_t, 4)
-_MAV_MSG_RETURN_TYPE(uint64_t, 8)
-_MAV_MSG_RETURN_TYPE(int64_t, 8)
-_MAV_MSG_RETURN_TYPE(float, 4)
-_MAV_MSG_RETURN_TYPE(double, 8)
-
-#elif !MAVLINK_ALIGNED_FIELDS
-#define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \
-static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
-{ TYPE r; byte_copy_## SIZE((char*)&r, &_MAV_PAYLOAD(msg)[ofs]); return r; }
-
-_MAV_MSG_RETURN_TYPE(uint16_t, 2)
-_MAV_MSG_RETURN_TYPE(int16_t, 2)
-_MAV_MSG_RETURN_TYPE(uint32_t, 4)
-_MAV_MSG_RETURN_TYPE(int32_t, 4)
-_MAV_MSG_RETURN_TYPE(uint64_t, 8)
-_MAV_MSG_RETURN_TYPE(int64_t, 8)
-_MAV_MSG_RETURN_TYPE(float, 4)
-_MAV_MSG_RETURN_TYPE(double, 8)
-#else // nicely aligned, no swap
-#define _MAV_MSG_RETURN_TYPE(TYPE) \
-static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
-{ return *(const TYPE *)(&_MAV_PAYLOAD(msg)[ofs]);}
-
-_MAV_MSG_RETURN_TYPE(uint16_t)
-_MAV_MSG_RETURN_TYPE(int16_t)
-_MAV_MSG_RETURN_TYPE(uint32_t)
-_MAV_MSG_RETURN_TYPE(int32_t)
-_MAV_MSG_RETURN_TYPE(uint64_t)
-_MAV_MSG_RETURN_TYPE(int64_t)
-_MAV_MSG_RETURN_TYPE(float)
-_MAV_MSG_RETURN_TYPE(double)
-#endif // MAVLINK_NEED_BYTE_SWAP
-
-static inline uint16_t _MAV_RETURN_char_array(const mavlink_message_t *msg, char *value,
- uint8_t array_length, uint8_t wire_offset)
-{
- memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length);
- return array_length;
-}
-
-static inline uint16_t _MAV_RETURN_uint8_t_array(const mavlink_message_t *msg, uint8_t *value,
- uint8_t array_length, uint8_t wire_offset)
-{
- memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length);
- return array_length;
-}
-
-static inline uint16_t _MAV_RETURN_int8_t_array(const mavlink_message_t *msg, int8_t *value,
- uint8_t array_length, uint8_t wire_offset)
-{
- memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length);
- return array_length;
-}
-
-#if MAVLINK_NEED_BYTE_SWAP
-#define _MAV_RETURN_ARRAY(TYPE, V) \
-static inline uint16_t _MAV_RETURN_## TYPE ##_array(const mavlink_message_t *msg, TYPE *value, \
- uint8_t array_length, uint8_t wire_offset) \
-{ \
- uint16_t i; \
- for (i=0; i<array_length; i++) { \
- value[i] = _MAV_RETURN_## TYPE (msg, wire_offset+(i*sizeof(value[0]))); \
- } \
- return array_length*sizeof(value[0]); \
-}
-#else
-#define _MAV_RETURN_ARRAY(TYPE, V) \
-static inline uint16_t _MAV_RETURN_## TYPE ##_array(const mavlink_message_t *msg, TYPE *value, \
- uint8_t array_length, uint8_t wire_offset) \
-{ \
- memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length*sizeof(TYPE)); \
- return array_length*sizeof(TYPE); \
-}
-#endif
-
-_MAV_RETURN_ARRAY(uint16_t, u16)
-_MAV_RETURN_ARRAY(uint32_t, u32)
-_MAV_RETURN_ARRAY(uint64_t, u64)
-_MAV_RETURN_ARRAY(int16_t, i16)
-_MAV_RETURN_ARRAY(int32_t, i32)
-_MAV_RETURN_ARRAY(int64_t, i64)
-_MAV_RETURN_ARRAY(float, f)
-_MAV_RETURN_ARRAY(double, d)
-
-#endif // _MAVLINK_PROTOCOL_H_
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/mavlink.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/mavlink.h
deleted file mode 100644
index 5b91bfe2d..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/mavlink.h
+++ /dev/null
@@ -1,27 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol built from test.xml
- * @see http://pixhawk.ethz.ch/software/mavlink
- */
-#ifndef MAVLINK_H
-#define MAVLINK_H
-
-#ifndef MAVLINK_STX
-#define MAVLINK_STX 85
-#endif
-
-#ifndef MAVLINK_ENDIAN
-#define MAVLINK_ENDIAN MAVLINK_BIG_ENDIAN
-#endif
-
-#ifndef MAVLINK_ALIGNED_FIELDS
-#define MAVLINK_ALIGNED_FIELDS 0
-#endif
-
-#ifndef MAVLINK_CRC_EXTRA
-#define MAVLINK_CRC_EXTRA 0
-#endif
-
-#include "version.h"
-#include "test.h"
-
-#endif // MAVLINK_H
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/mavlink_msg_test_types.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/mavlink_msg_test_types.h
deleted file mode 100644
index 50b4fd6bc..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/mavlink_msg_test_types.h
+++ /dev/null
@@ -1,610 +0,0 @@
-// MESSAGE TEST_TYPES PACKING
-
-#define MAVLINK_MSG_ID_TEST_TYPES 0
-
-typedef struct __mavlink_test_types_t
-{
- char c; ///< char
- char s[10]; ///< string
- uint8_t u8; ///< uint8_t
- uint16_t u16; ///< uint16_t
- uint32_t u32; ///< uint32_t
- uint64_t u64; ///< uint64_t
- int8_t s8; ///< int8_t
- int16_t s16; ///< int16_t
- int32_t s32; ///< int32_t
- int64_t s64; ///< int64_t
- float f; ///< float
- double d; ///< double
- uint8_t u8_array[3]; ///< uint8_t_array
- uint16_t u16_array[3]; ///< uint16_t_array
- uint32_t u32_array[3]; ///< uint32_t_array
- uint64_t u64_array[3]; ///< uint64_t_array
- int8_t s8_array[3]; ///< int8_t_array
- int16_t s16_array[3]; ///< int16_t_array
- int32_t s32_array[3]; ///< int32_t_array
- int64_t s64_array[3]; ///< int64_t_array
- float f_array[3]; ///< float_array
- double d_array[3]; ///< double_array
-} mavlink_test_types_t;
-
-#define MAVLINK_MSG_ID_TEST_TYPES_LEN 179
-#define MAVLINK_MSG_ID_0_LEN 179
-
-#define MAVLINK_MSG_TEST_TYPES_FIELD_S_LEN 10
-#define MAVLINK_MSG_TEST_TYPES_FIELD_U8_ARRAY_LEN 3
-#define MAVLINK_MSG_TEST_TYPES_FIELD_U16_ARRAY_LEN 3
-#define MAVLINK_MSG_TEST_TYPES_FIELD_U32_ARRAY_LEN 3
-#define MAVLINK_MSG_TEST_TYPES_FIELD_U64_ARRAY_LEN 3
-#define MAVLINK_MSG_TEST_TYPES_FIELD_S8_ARRAY_LEN 3
-#define MAVLINK_MSG_TEST_TYPES_FIELD_S16_ARRAY_LEN 3
-#define MAVLINK_MSG_TEST_TYPES_FIELD_S32_ARRAY_LEN 3
-#define MAVLINK_MSG_TEST_TYPES_FIELD_S64_ARRAY_LEN 3
-#define MAVLINK_MSG_TEST_TYPES_FIELD_F_ARRAY_LEN 3
-#define MAVLINK_MSG_TEST_TYPES_FIELD_D_ARRAY_LEN 3
-
-#define MAVLINK_MESSAGE_INFO_TEST_TYPES { \
- "TEST_TYPES", \
- 22, \
- { { "c", NULL, MAVLINK_TYPE_CHAR, 0, 0, offsetof(mavlink_test_types_t, c) }, \
- { "s", NULL, MAVLINK_TYPE_CHAR, 10, 1, offsetof(mavlink_test_types_t, s) }, \
- { "u8", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_test_types_t, u8) }, \
- { "u16", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_test_types_t, u16) }, \
- { "u32", "0x%08x", MAVLINK_TYPE_UINT32_T, 0, 14, offsetof(mavlink_test_types_t, u32) }, \
- { "u64", NULL, MAVLINK_TYPE_UINT64_T, 0, 18, offsetof(mavlink_test_types_t, u64) }, \
- { "s8", NULL, MAVLINK_TYPE_INT8_T, 0, 26, offsetof(mavlink_test_types_t, s8) }, \
- { "s16", NULL, MAVLINK_TYPE_INT16_T, 0, 27, offsetof(mavlink_test_types_t, s16) }, \
- { "s32", NULL, MAVLINK_TYPE_INT32_T, 0, 29, offsetof(mavlink_test_types_t, s32) }, \
- { "s64", NULL, MAVLINK_TYPE_INT64_T, 0, 33, offsetof(mavlink_test_types_t, s64) }, \
- { "f", NULL, MAVLINK_TYPE_FLOAT, 0, 41, offsetof(mavlink_test_types_t, f) }, \
- { "d", NULL, MAVLINK_TYPE_DOUBLE, 0, 45, offsetof(mavlink_test_types_t, d) }, \
- { "u8_array", NULL, MAVLINK_TYPE_UINT8_T, 3, 53, offsetof(mavlink_test_types_t, u8_array) }, \
- { "u16_array", NULL, MAVLINK_TYPE_UINT16_T, 3, 56, offsetof(mavlink_test_types_t, u16_array) }, \
- { "u32_array", NULL, MAVLINK_TYPE_UINT32_T, 3, 62, offsetof(mavlink_test_types_t, u32_array) }, \
- { "u64_array", NULL, MAVLINK_TYPE_UINT64_T, 3, 74, offsetof(mavlink_test_types_t, u64_array) }, \
- { "s8_array", NULL, MAVLINK_TYPE_INT8_T, 3, 98, offsetof(mavlink_test_types_t, s8_array) }, \
- { "s16_array", NULL, MAVLINK_TYPE_INT16_T, 3, 101, offsetof(mavlink_test_types_t, s16_array) }, \
- { "s32_array", NULL, MAVLINK_TYPE_INT32_T, 3, 107, offsetof(mavlink_test_types_t, s32_array) }, \
- { "s64_array", NULL, MAVLINK_TYPE_INT64_T, 3, 119, offsetof(mavlink_test_types_t, s64_array) }, \
- { "f_array", NULL, MAVLINK_TYPE_FLOAT, 3, 143, offsetof(mavlink_test_types_t, f_array) }, \
- { "d_array", NULL, MAVLINK_TYPE_DOUBLE, 3, 155, offsetof(mavlink_test_types_t, d_array) }, \
- } \
-}
-
-
-/**
- * @brief Pack a test_types message
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param msg The MAVLink message to compress the data into
- *
- * @param c char
- * @param s string
- * @param u8 uint8_t
- * @param u16 uint16_t
- * @param u32 uint32_t
- * @param u64 uint64_t
- * @param s8 int8_t
- * @param s16 int16_t
- * @param s32 int32_t
- * @param s64 int64_t
- * @param f float
- * @param d double
- * @param u8_array uint8_t_array
- * @param u16_array uint16_t_array
- * @param u32_array uint32_t_array
- * @param u64_array uint64_t_array
- * @param s8_array int8_t_array
- * @param s16_array int16_t_array
- * @param s32_array int32_t_array
- * @param s64_array int64_t_array
- * @param f_array float_array
- * @param d_array double_array
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_test_types_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- char c, const char *s, uint8_t u8, uint16_t u16, uint32_t u32, uint64_t u64, int8_t s8, int16_t s16, int32_t s32, int64_t s64, float f, double d, const uint8_t *u8_array, const uint16_t *u16_array, const uint32_t *u32_array, const uint64_t *u64_array, const int8_t *s8_array, const int16_t *s16_array, const int32_t *s32_array, const int64_t *s64_array, const float *f_array, const double *d_array)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[179];
- _mav_put_char(buf, 0, c);
- _mav_put_uint8_t(buf, 11, u8);
- _mav_put_uint16_t(buf, 12, u16);
- _mav_put_uint32_t(buf, 14, u32);
- _mav_put_uint64_t(buf, 18, u64);
- _mav_put_int8_t(buf, 26, s8);
- _mav_put_int16_t(buf, 27, s16);
- _mav_put_int32_t(buf, 29, s32);
- _mav_put_int64_t(buf, 33, s64);
- _mav_put_float(buf, 41, f);
- _mav_put_double(buf, 45, d);
- _mav_put_char_array(buf, 1, s, 10);
- _mav_put_uint8_t_array(buf, 53, u8_array, 3);
- _mav_put_uint16_t_array(buf, 56, u16_array, 3);
- _mav_put_uint32_t_array(buf, 62, u32_array, 3);
- _mav_put_uint64_t_array(buf, 74, u64_array, 3);
- _mav_put_int8_t_array(buf, 98, s8_array, 3);
- _mav_put_int16_t_array(buf, 101, s16_array, 3);
- _mav_put_int32_t_array(buf, 107, s32_array, 3);
- _mav_put_int64_t_array(buf, 119, s64_array, 3);
- _mav_put_float_array(buf, 143, f_array, 3);
- _mav_put_double_array(buf, 155, d_array, 3);
- memcpy(_MAV_PAYLOAD(msg), buf, 179);
-#else
- mavlink_test_types_t packet;
- packet.c = c;
- packet.u8 = u8;
- packet.u16 = u16;
- packet.u32 = u32;
- packet.u64 = u64;
- packet.s8 = s8;
- packet.s16 = s16;
- packet.s32 = s32;
- packet.s64 = s64;
- packet.f = f;
- packet.d = d;
- mav_array_memcpy(packet.s, s, sizeof(char)*10);
- mav_array_memcpy(packet.u8_array, u8_array, sizeof(uint8_t)*3);
- mav_array_memcpy(packet.u16_array, u16_array, sizeof(uint16_t)*3);
- mav_array_memcpy(packet.u32_array, u32_array, sizeof(uint32_t)*3);
- mav_array_memcpy(packet.u64_array, u64_array, sizeof(uint64_t)*3);
- mav_array_memcpy(packet.s8_array, s8_array, sizeof(int8_t)*3);
- mav_array_memcpy(packet.s16_array, s16_array, sizeof(int16_t)*3);
- mav_array_memcpy(packet.s32_array, s32_array, sizeof(int32_t)*3);
- mav_array_memcpy(packet.s64_array, s64_array, sizeof(int64_t)*3);
- mav_array_memcpy(packet.f_array, f_array, sizeof(float)*3);
- mav_array_memcpy(packet.d_array, d_array, sizeof(double)*3);
- memcpy(_MAV_PAYLOAD(msg), &packet, 179);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_TEST_TYPES;
- return mavlink_finalize_message(msg, system_id, component_id, 179);
-}
-
-/**
- * @brief Pack a test_types message on a channel
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
- * @param msg The MAVLink message to compress the data into
- * @param c char
- * @param s string
- * @param u8 uint8_t
- * @param u16 uint16_t
- * @param u32 uint32_t
- * @param u64 uint64_t
- * @param s8 int8_t
- * @param s16 int16_t
- * @param s32 int32_t
- * @param s64 int64_t
- * @param f float
- * @param d double
- * @param u8_array uint8_t_array
- * @param u16_array uint16_t_array
- * @param u32_array uint32_t_array
- * @param u64_array uint64_t_array
- * @param s8_array int8_t_array
- * @param s16_array int16_t_array
- * @param s32_array int32_t_array
- * @param s64_array int64_t_array
- * @param f_array float_array
- * @param d_array double_array
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_test_types_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- char c,const char *s,uint8_t u8,uint16_t u16,uint32_t u32,uint64_t u64,int8_t s8,int16_t s16,int32_t s32,int64_t s64,float f,double d,const uint8_t *u8_array,const uint16_t *u16_array,const uint32_t *u32_array,const uint64_t *u64_array,const int8_t *s8_array,const int16_t *s16_array,const int32_t *s32_array,const int64_t *s64_array,const float *f_array,const double *d_array)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[179];
- _mav_put_char(buf, 0, c);
- _mav_put_uint8_t(buf, 11, u8);
- _mav_put_uint16_t(buf, 12, u16);
- _mav_put_uint32_t(buf, 14, u32);
- _mav_put_uint64_t(buf, 18, u64);
- _mav_put_int8_t(buf, 26, s8);
- _mav_put_int16_t(buf, 27, s16);
- _mav_put_int32_t(buf, 29, s32);
- _mav_put_int64_t(buf, 33, s64);
- _mav_put_float(buf, 41, f);
- _mav_put_double(buf, 45, d);
- _mav_put_char_array(buf, 1, s, 10);
- _mav_put_uint8_t_array(buf, 53, u8_array, 3);
- _mav_put_uint16_t_array(buf, 56, u16_array, 3);
- _mav_put_uint32_t_array(buf, 62, u32_array, 3);
- _mav_put_uint64_t_array(buf, 74, u64_array, 3);
- _mav_put_int8_t_array(buf, 98, s8_array, 3);
- _mav_put_int16_t_array(buf, 101, s16_array, 3);
- _mav_put_int32_t_array(buf, 107, s32_array, 3);
- _mav_put_int64_t_array(buf, 119, s64_array, 3);
- _mav_put_float_array(buf, 143, f_array, 3);
- _mav_put_double_array(buf, 155, d_array, 3);
- memcpy(_MAV_PAYLOAD(msg), buf, 179);
-#else
- mavlink_test_types_t packet;
- packet.c = c;
- packet.u8 = u8;
- packet.u16 = u16;
- packet.u32 = u32;
- packet.u64 = u64;
- packet.s8 = s8;
- packet.s16 = s16;
- packet.s32 = s32;
- packet.s64 = s64;
- packet.f = f;
- packet.d = d;
- mav_array_memcpy(packet.s, s, sizeof(char)*10);
- mav_array_memcpy(packet.u8_array, u8_array, sizeof(uint8_t)*3);
- mav_array_memcpy(packet.u16_array, u16_array, sizeof(uint16_t)*3);
- mav_array_memcpy(packet.u32_array, u32_array, sizeof(uint32_t)*3);
- mav_array_memcpy(packet.u64_array, u64_array, sizeof(uint64_t)*3);
- mav_array_memcpy(packet.s8_array, s8_array, sizeof(int8_t)*3);
- mav_array_memcpy(packet.s16_array, s16_array, sizeof(int16_t)*3);
- mav_array_memcpy(packet.s32_array, s32_array, sizeof(int32_t)*3);
- mav_array_memcpy(packet.s64_array, s64_array, sizeof(int64_t)*3);
- mav_array_memcpy(packet.f_array, f_array, sizeof(float)*3);
- mav_array_memcpy(packet.d_array, d_array, sizeof(double)*3);
- memcpy(_MAV_PAYLOAD(msg), &packet, 179);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_TEST_TYPES;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 179);
-}
-
-/**
- * @brief Encode a test_types struct into a message
- *
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param msg The MAVLink message to compress the data into
- * @param test_types C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_test_types_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_test_types_t* test_types)
-{
- return mavlink_msg_test_types_pack(system_id, component_id, msg, test_types->c, test_types->s, test_types->u8, test_types->u16, test_types->u32, test_types->u64, test_types->s8, test_types->s16, test_types->s32, test_types->s64, test_types->f, test_types->d, test_types->u8_array, test_types->u16_array, test_types->u32_array, test_types->u64_array, test_types->s8_array, test_types->s16_array, test_types->s32_array, test_types->s64_array, test_types->f_array, test_types->d_array);
-}
-
-/**
- * @brief Send a test_types message
- * @param chan MAVLink channel to send the message
- *
- * @param c char
- * @param s string
- * @param u8 uint8_t
- * @param u16 uint16_t
- * @param u32 uint32_t
- * @param u64 uint64_t
- * @param s8 int8_t
- * @param s16 int16_t
- * @param s32 int32_t
- * @param s64 int64_t
- * @param f float
- * @param d double
- * @param u8_array uint8_t_array
- * @param u16_array uint16_t_array
- * @param u32_array uint32_t_array
- * @param u64_array uint64_t_array
- * @param s8_array int8_t_array
- * @param s16_array int16_t_array
- * @param s32_array int32_t_array
- * @param s64_array int64_t_array
- * @param f_array float_array
- * @param d_array double_array
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_test_types_send(mavlink_channel_t chan, char c, const char *s, uint8_t u8, uint16_t u16, uint32_t u32, uint64_t u64, int8_t s8, int16_t s16, int32_t s32, int64_t s64, float f, double d, const uint8_t *u8_array, const uint16_t *u16_array, const uint32_t *u32_array, const uint64_t *u64_array, const int8_t *s8_array, const int16_t *s16_array, const int32_t *s32_array, const int64_t *s64_array, const float *f_array, const double *d_array)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[179];
- _mav_put_char(buf, 0, c);
- _mav_put_uint8_t(buf, 11, u8);
- _mav_put_uint16_t(buf, 12, u16);
- _mav_put_uint32_t(buf, 14, u32);
- _mav_put_uint64_t(buf, 18, u64);
- _mav_put_int8_t(buf, 26, s8);
- _mav_put_int16_t(buf, 27, s16);
- _mav_put_int32_t(buf, 29, s32);
- _mav_put_int64_t(buf, 33, s64);
- _mav_put_float(buf, 41, f);
- _mav_put_double(buf, 45, d);
- _mav_put_char_array(buf, 1, s, 10);
- _mav_put_uint8_t_array(buf, 53, u8_array, 3);
- _mav_put_uint16_t_array(buf, 56, u16_array, 3);
- _mav_put_uint32_t_array(buf, 62, u32_array, 3);
- _mav_put_uint64_t_array(buf, 74, u64_array, 3);
- _mav_put_int8_t_array(buf, 98, s8_array, 3);
- _mav_put_int16_t_array(buf, 101, s16_array, 3);
- _mav_put_int32_t_array(buf, 107, s32_array, 3);
- _mav_put_int64_t_array(buf, 119, s64_array, 3);
- _mav_put_float_array(buf, 143, f_array, 3);
- _mav_put_double_array(buf, 155, d_array, 3);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TYPES, buf, 179);
-#else
- mavlink_test_types_t packet;
- packet.c = c;
- packet.u8 = u8;
- packet.u16 = u16;
- packet.u32 = u32;
- packet.u64 = u64;
- packet.s8 = s8;
- packet.s16 = s16;
- packet.s32 = s32;
- packet.s64 = s64;
- packet.f = f;
- packet.d = d;
- mav_array_memcpy(packet.s, s, sizeof(char)*10);
- mav_array_memcpy(packet.u8_array, u8_array, sizeof(uint8_t)*3);
- mav_array_memcpy(packet.u16_array, u16_array, sizeof(uint16_t)*3);
- mav_array_memcpy(packet.u32_array, u32_array, sizeof(uint32_t)*3);
- mav_array_memcpy(packet.u64_array, u64_array, sizeof(uint64_t)*3);
- mav_array_memcpy(packet.s8_array, s8_array, sizeof(int8_t)*3);
- mav_array_memcpy(packet.s16_array, s16_array, sizeof(int16_t)*3);
- mav_array_memcpy(packet.s32_array, s32_array, sizeof(int32_t)*3);
- mav_array_memcpy(packet.s64_array, s64_array, sizeof(int64_t)*3);
- mav_array_memcpy(packet.f_array, f_array, sizeof(float)*3);
- mav_array_memcpy(packet.d_array, d_array, sizeof(double)*3);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TYPES, (const char *)&packet, 179);
-#endif
-}
-
-#endif
-
-// MESSAGE TEST_TYPES UNPACKING
-
-
-/**
- * @brief Get field c from test_types message
- *
- * @return char
- */
-static inline char mavlink_msg_test_types_get_c(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_char(msg, 0);
-}
-
-/**
- * @brief Get field s from test_types message
- *
- * @return string
- */
-static inline uint16_t mavlink_msg_test_types_get_s(const mavlink_message_t* msg, char *s)
-{
- return _MAV_RETURN_char_array(msg, s, 10, 1);
-}
-
-/**
- * @brief Get field u8 from test_types message
- *
- * @return uint8_t
- */
-static inline uint8_t mavlink_msg_test_types_get_u8(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 11);
-}
-
-/**
- * @brief Get field u16 from test_types message
- *
- * @return uint16_t
- */
-static inline uint16_t mavlink_msg_test_types_get_u16(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 12);
-}
-
-/**
- * @brief Get field u32 from test_types message
- *
- * @return uint32_t
- */
-static inline uint32_t mavlink_msg_test_types_get_u32(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint32_t(msg, 14);
-}
-
-/**
- * @brief Get field u64 from test_types message
- *
- * @return uint64_t
- */
-static inline uint64_t mavlink_msg_test_types_get_u64(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 18);
-}
-
-/**
- * @brief Get field s8 from test_types message
- *
- * @return int8_t
- */
-static inline int8_t mavlink_msg_test_types_get_s8(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int8_t(msg, 26);
-}
-
-/**
- * @brief Get field s16 from test_types message
- *
- * @return int16_t
- */
-static inline int16_t mavlink_msg_test_types_get_s16(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int16_t(msg, 27);
-}
-
-/**
- * @brief Get field s32 from test_types message
- *
- * @return int32_t
- */
-static inline int32_t mavlink_msg_test_types_get_s32(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 29);
-}
-
-/**
- * @brief Get field s64 from test_types message
- *
- * @return int64_t
- */
-static inline int64_t mavlink_msg_test_types_get_s64(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int64_t(msg, 33);
-}
-
-/**
- * @brief Get field f from test_types message
- *
- * @return float
- */
-static inline float mavlink_msg_test_types_get_f(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 41);
-}
-
-/**
- * @brief Get field d from test_types message
- *
- * @return double
- */
-static inline double mavlink_msg_test_types_get_d(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_double(msg, 45);
-}
-
-/**
- * @brief Get field u8_array from test_types message
- *
- * @return uint8_t_array
- */
-static inline uint16_t mavlink_msg_test_types_get_u8_array(const mavlink_message_t* msg, uint8_t *u8_array)
-{
- return _MAV_RETURN_uint8_t_array(msg, u8_array, 3, 53);
-}
-
-/**
- * @brief Get field u16_array from test_types message
- *
- * @return uint16_t_array
- */
-static inline uint16_t mavlink_msg_test_types_get_u16_array(const mavlink_message_t* msg, uint16_t *u16_array)
-{
- return _MAV_RETURN_uint16_t_array(msg, u16_array, 3, 56);
-}
-
-/**
- * @brief Get field u32_array from test_types message
- *
- * @return uint32_t_array
- */
-static inline uint16_t mavlink_msg_test_types_get_u32_array(const mavlink_message_t* msg, uint32_t *u32_array)
-{
- return _MAV_RETURN_uint32_t_array(msg, u32_array, 3, 62);
-}
-
-/**
- * @brief Get field u64_array from test_types message
- *
- * @return uint64_t_array
- */
-static inline uint16_t mavlink_msg_test_types_get_u64_array(const mavlink_message_t* msg, uint64_t *u64_array)
-{
- return _MAV_RETURN_uint64_t_array(msg, u64_array, 3, 74);
-}
-
-/**
- * @brief Get field s8_array from test_types message
- *
- * @return int8_t_array
- */
-static inline uint16_t mavlink_msg_test_types_get_s8_array(const mavlink_message_t* msg, int8_t *s8_array)
-{
- return _MAV_RETURN_int8_t_array(msg, s8_array, 3, 98);
-}
-
-/**
- * @brief Get field s16_array from test_types message
- *
- * @return int16_t_array
- */
-static inline uint16_t mavlink_msg_test_types_get_s16_array(const mavlink_message_t* msg, int16_t *s16_array)
-{
- return _MAV_RETURN_int16_t_array(msg, s16_array, 3, 101);
-}
-
-/**
- * @brief Get field s32_array from test_types message
- *
- * @return int32_t_array
- */
-static inline uint16_t mavlink_msg_test_types_get_s32_array(const mavlink_message_t* msg, int32_t *s32_array)
-{
- return _MAV_RETURN_int32_t_array(msg, s32_array, 3, 107);
-}
-
-/**
- * @brief Get field s64_array from test_types message
- *
- * @return int64_t_array
- */
-static inline uint16_t mavlink_msg_test_types_get_s64_array(const mavlink_message_t* msg, int64_t *s64_array)
-{
- return _MAV_RETURN_int64_t_array(msg, s64_array, 3, 119);
-}
-
-/**
- * @brief Get field f_array from test_types message
- *
- * @return float_array
- */
-static inline uint16_t mavlink_msg_test_types_get_f_array(const mavlink_message_t* msg, float *f_array)
-{
- return _MAV_RETURN_float_array(msg, f_array, 3, 143);
-}
-
-/**
- * @brief Get field d_array from test_types message
- *
- * @return double_array
- */
-static inline uint16_t mavlink_msg_test_types_get_d_array(const mavlink_message_t* msg, double *d_array)
-{
- return _MAV_RETURN_double_array(msg, d_array, 3, 155);
-}
-
-/**
- * @brief Decode a test_types message into a struct
- *
- * @param msg The message to decode
- * @param test_types C-struct to decode the message contents into
- */
-static inline void mavlink_msg_test_types_decode(const mavlink_message_t* msg, mavlink_test_types_t* test_types)
-{
-#if MAVLINK_NEED_BYTE_SWAP
- test_types->c = mavlink_msg_test_types_get_c(msg);
- mavlink_msg_test_types_get_s(msg, test_types->s);
- test_types->u8 = mavlink_msg_test_types_get_u8(msg);
- test_types->u16 = mavlink_msg_test_types_get_u16(msg);
- test_types->u32 = mavlink_msg_test_types_get_u32(msg);
- test_types->u64 = mavlink_msg_test_types_get_u64(msg);
- test_types->s8 = mavlink_msg_test_types_get_s8(msg);
- test_types->s16 = mavlink_msg_test_types_get_s16(msg);
- test_types->s32 = mavlink_msg_test_types_get_s32(msg);
- test_types->s64 = mavlink_msg_test_types_get_s64(msg);
- test_types->f = mavlink_msg_test_types_get_f(msg);
- test_types->d = mavlink_msg_test_types_get_d(msg);
- mavlink_msg_test_types_get_u8_array(msg, test_types->u8_array);
- mavlink_msg_test_types_get_u16_array(msg, test_types->u16_array);
- mavlink_msg_test_types_get_u32_array(msg, test_types->u32_array);
- mavlink_msg_test_types_get_u64_array(msg, test_types->u64_array);
- mavlink_msg_test_types_get_s8_array(msg, test_types->s8_array);
- mavlink_msg_test_types_get_s16_array(msg, test_types->s16_array);
- mavlink_msg_test_types_get_s32_array(msg, test_types->s32_array);
- mavlink_msg_test_types_get_s64_array(msg, test_types->s64_array);
- mavlink_msg_test_types_get_f_array(msg, test_types->f_array);
- mavlink_msg_test_types_get_d_array(msg, test_types->d_array);
-#else
- memcpy(test_types, _MAV_PAYLOAD(msg), 179);
-#endif
-}
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/test.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/test.h
deleted file mode 100644
index 23ee65986..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/test.h
+++ /dev/null
@@ -1,53 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol generated from test.xml
- * @see http://qgroundcontrol.org/mavlink/
- */
-#ifndef TEST_H
-#define TEST_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-// MESSAGE LENGTHS AND CRCS
-
-#ifndef MAVLINK_MESSAGE_LENGTHS
-#define MAVLINK_MESSAGE_LENGTHS {179, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
-#endif
-
-#ifndef MAVLINK_MESSAGE_CRCS
-#define MAVLINK_MESSAGE_CRCS {91, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
-#endif
-
-#ifndef MAVLINK_MESSAGE_INFO
-#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_TEST_TYPES, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}}
-#endif
-
-#include "../protocol.h"
-
-#define MAVLINK_ENABLED_TEST
-
-
-
-// MAVLINK VERSION
-
-#ifndef MAVLINK_VERSION
-#define MAVLINK_VERSION 3
-#endif
-
-#if (MAVLINK_VERSION == 0)
-#undef MAVLINK_VERSION
-#define MAVLINK_VERSION 3
-#endif
-
-// ENUM DEFINITIONS
-
-
-
-// MESSAGE DEFINITIONS
-#include "./mavlink_msg_test_types.h"
-
-#ifdef __cplusplus
-}
-#endif // __cplusplus
-#endif // TEST_H
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/testsuite.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/testsuite.h
deleted file mode 100644
index 9b0fc041b..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/testsuite.h
+++ /dev/null
@@ -1,120 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol testsuite generated from test.xml
- * @see http://qgroundcontrol.org/mavlink/
- */
-#ifndef TEST_TESTSUITE_H
-#define TEST_TESTSUITE_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-#ifndef MAVLINK_TEST_ALL
-#define MAVLINK_TEST_ALL
-
-static void mavlink_test_test(uint8_t, uint8_t, mavlink_message_t *last_msg);
-
-static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
-{
-
- mavlink_test_test(system_id, component_id, last_msg);
-}
-#endif
-
-
-
-
-static void mavlink_test_test_types(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
-{
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_test_types_t packet_in = {
- 'A',
- "BCDEFGHIJ",
- 230,
- 17859,
- 963498192,
- 93372036854776941ULL,
- 211,
- 18639,
- 963498972,
- 93372036854777886LL,
- 304.0,
- 438.0,
- { 228, 229, 230 },
- { 20147, 20148, 20149 },
- { 963500688, 963500689, 963500690 },
- { 93372036854780469, 93372036854780470, 93372036854780471 },
- { 171, 172, 173 },
- { 22487, 22488, 22489 },
- { 963503028, 963503029, 963503030 },
- { 93372036854783304, 93372036854783305, 93372036854783306 },
- { 1018.0, 1019.0, 1020.0 },
- { 1208.0, 1209.0, 1210.0 },
- };
- mavlink_test_types_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.c = packet_in.c;
- packet1.u8 = packet_in.u8;
- packet1.u16 = packet_in.u16;
- packet1.u32 = packet_in.u32;
- packet1.u64 = packet_in.u64;
- packet1.s8 = packet_in.s8;
- packet1.s16 = packet_in.s16;
- packet1.s32 = packet_in.s32;
- packet1.s64 = packet_in.s64;
- packet1.f = packet_in.f;
- packet1.d = packet_in.d;
-
- mav_array_memcpy(packet1.s, packet_in.s, sizeof(char)*10);
- mav_array_memcpy(packet1.u8_array, packet_in.u8_array, sizeof(uint8_t)*3);
- mav_array_memcpy(packet1.u16_array, packet_in.u16_array, sizeof(uint16_t)*3);
- mav_array_memcpy(packet1.u32_array, packet_in.u32_array, sizeof(uint32_t)*3);
- mav_array_memcpy(packet1.u64_array, packet_in.u64_array, sizeof(uint64_t)*3);
- mav_array_memcpy(packet1.s8_array, packet_in.s8_array, sizeof(int8_t)*3);
- mav_array_memcpy(packet1.s16_array, packet_in.s16_array, sizeof(int16_t)*3);
- mav_array_memcpy(packet1.s32_array, packet_in.s32_array, sizeof(int32_t)*3);
- mav_array_memcpy(packet1.s64_array, packet_in.s64_array, sizeof(int64_t)*3);
- mav_array_memcpy(packet1.f_array, packet_in.f_array, sizeof(float)*3);
- mav_array_memcpy(packet1.d_array, packet_in.d_array, sizeof(double)*3);
-
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_test_types_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_test_types_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_test_types_pack(system_id, component_id, &msg , packet1.c , packet1.s , packet1.u8 , packet1.u16 , packet1.u32 , packet1.u64 , packet1.s8 , packet1.s16 , packet1.s32 , packet1.s64 , packet1.f , packet1.d , packet1.u8_array , packet1.u16_array , packet1.u32_array , packet1.u64_array , packet1.s8_array , packet1.s16_array , packet1.s32_array , packet1.s64_array , packet1.f_array , packet1.d_array );
- mavlink_msg_test_types_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_test_types_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.c , packet1.s , packet1.u8 , packet1.u16 , packet1.u32 , packet1.u64 , packet1.s8 , packet1.s16 , packet1.s32 , packet1.s64 , packet1.f , packet1.d , packet1.u8_array , packet1.u16_array , packet1.u32_array , packet1.u64_array , packet1.s8_array , packet1.s16_array , packet1.s32_array , packet1.s64_array , packet1.f_array , packet1.d_array );
- mavlink_msg_test_types_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_to_send_buffer(buffer, &msg);
- for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_test_types_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_test_types_send(MAVLINK_COMM_1 , packet1.c , packet1.s , packet1.u8 , packet1.u16 , packet1.u32 , packet1.u64 , packet1.s8 , packet1.s16 , packet1.s32 , packet1.s64 , packet1.f , packet1.d , packet1.u8_array , packet1.u16_array , packet1.u32_array , packet1.u64_array , packet1.s8_array , packet1.s16_array , packet1.s32_array , packet1.s64_array , packet1.f_array , packet1.d_array );
- mavlink_msg_test_types_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_test(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
-{
- mavlink_test_test_types(system_id, component_id, last_msg);
-}
-
-#ifdef __cplusplus
-}
-#endif // __cplusplus
-#endif // TEST_TESTSUITE_H
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/version.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/version.h
deleted file mode 100644
index 64ca0cb38..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/version.h
+++ /dev/null
@@ -1,12 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol built from test.xml
- * @see http://pixhawk.ethz.ch/software/mavlink
- */
-#ifndef MAVLINK_VERSION_H
-#define MAVLINK_VERSION_H
-
-#define MAVLINK_BUILD_DATE "Thu Mar 1 15:11:54 2012"
-#define MAVLINK_WIRE_PROTOCOL_VERSION "0.9"
-#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 179
-
-#endif // MAVLINK_VERSION_H
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/checksum.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/checksum.h
deleted file mode 100644
index 4f4cce02f..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/checksum.h
+++ /dev/null
@@ -1,89 +0,0 @@
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-#ifndef _CHECKSUM_H_
-#define _CHECKSUM_H_
-
-
-/**
- *
- * CALCULATE THE CHECKSUM
- *
- */
-
-#define X25_INIT_CRC 0xffff
-#define X25_VALIDATE_CRC 0xf0b8
-
-/**
- * @brief Accumulate the X.25 CRC by adding one char at a time.
- *
- * The checksum function adds the hash of one char at a time to the
- * 16 bit checksum (uint16_t).
- *
- * @param data new char to hash
- * @param crcAccum the already accumulated checksum
- **/
-static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum)
-{
- /*Accumulate one byte of data into the CRC*/
- uint8_t tmp;
-
- tmp = data ^ (uint8_t)(*crcAccum &0xff);
- tmp ^= (tmp<<4);
- *crcAccum = (*crcAccum>>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4);
-}
-
-/**
- * @brief Initiliaze the buffer for the X.25 CRC
- *
- * @param crcAccum the 16 bit X.25 CRC
- */
-static inline void crc_init(uint16_t* crcAccum)
-{
- *crcAccum = X25_INIT_CRC;
-}
-
-
-/**
- * @brief Calculates the X.25 checksum on a byte buffer
- *
- * @param pBuffer buffer containing the byte array to hash
- * @param length length of the byte array
- * @return the checksum over the buffer bytes
- **/
-static inline uint16_t crc_calculate(const uint8_t* pBuffer, uint16_t length)
-{
- uint16_t crcTmp;
- crc_init(&crcTmp);
- while (length--) {
- crc_accumulate(*pBuffer++, &crcTmp);
- }
- return crcTmp;
-}
-
-/**
- * @brief Accumulate the X.25 CRC by adding an array of bytes
- *
- * The checksum function adds the hash of one char at a time to the
- * 16 bit checksum (uint16_t).
- *
- * @param data new bytes to hash
- * @param crcAccum the already accumulated checksum
- **/
-static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint8_t length)
-{
- const uint8_t *p = (const uint8_t *)pBuffer;
- while (length--) {
- crc_accumulate(*p++, crcAccum);
- }
-}
-
-
-
-
-#endif /* _CHECKSUM_H_ */
-
-#ifdef __cplusplus
-}
-#endif
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_helpers.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_helpers.h
deleted file mode 100644
index 39d6930e5..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_helpers.h
+++ /dev/null
@@ -1,507 +0,0 @@
-#ifndef _MAVLINK_HELPERS_H_
-#define _MAVLINK_HELPERS_H_
-
-#include "string.h"
-#include "checksum.h"
-#include "mavlink_types.h"
-
-#ifndef MAVLINK_HELPER
-#define MAVLINK_HELPER
-#endif
-
-/*
- internal function to give access to the channel status for each channel
- */
-MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan)
-{
- static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS];
- return &m_mavlink_status[chan];
-}
-
-/*
- internal function to give access to the channel buffer for each channel
- */
-MAVLINK_HELPER mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan)
-{
-
-#if MAVLINK_EXTERNAL_RX_BUFFER
- // No m_mavlink_message array defined in function,
- // has to be defined externally
-#ifndef m_mavlink_message
-#error ERROR: IF #define MAVLINK_EXTERNAL_RX_BUFFER IS SET, THE BUFFER HAS TO BE ALLOCATED OUTSIDE OF THIS FUNCTION (mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS];)
-#endif
-#else
- static mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS];
-#endif
- return &m_mavlink_buffer[chan];
-}
-
-/**
- * @brief Finalize a MAVLink message with channel assignment
- *
- * This function calculates the checksum and sets length and aircraft id correctly.
- * It assumes that the message id and the payload are already correctly set. This function
- * can also be used if the message header has already been written before (as in mavlink_msg_xxx_pack
- * instead of mavlink_msg_xxx_pack_headerless), it just introduces little extra overhead.
- *
- * @param msg Message to finalize
- * @param system_id Id of the sending (this) system, 1-127
- * @param length Message length
- */
-#if MAVLINK_CRC_EXTRA
-MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
- uint8_t chan, uint8_t length, uint8_t crc_extra)
-#else
-MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
- uint8_t chan, uint8_t length)
-#endif
-{
- // This code part is the same for all messages;
- uint16_t checksum;
- msg->magic = MAVLINK_STX;
- msg->len = length;
- msg->sysid = system_id;
- msg->compid = component_id;
- // One sequence number per component
- msg->seq = mavlink_get_channel_status(chan)->current_tx_seq;
- mavlink_get_channel_status(chan)->current_tx_seq = mavlink_get_channel_status(chan)->current_tx_seq+1;
- checksum = crc_calculate((uint8_t*)&msg->len, length + MAVLINK_CORE_HEADER_LEN);
-#if MAVLINK_CRC_EXTRA
- crc_accumulate(crc_extra, &checksum);
-#endif
- mavlink_ck_a(msg) = (uint8_t)(checksum & 0xFF);
- mavlink_ck_b(msg) = (uint8_t)(checksum >> 8);
-
- return length + MAVLINK_NUM_NON_PAYLOAD_BYTES;
-}
-
-
-/**
- * @brief Finalize a MAVLink message with MAVLINK_COMM_0 as default channel
- */
-#if MAVLINK_CRC_EXTRA
-MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
- uint8_t length, uint8_t crc_extra)
-{
- return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length, crc_extra);
-}
-#else
-MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
- uint8_t length)
-{
- return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length);
-}
-#endif
-
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len);
-
-/**
- * @brief Finalize a MAVLink message with channel assignment and send
- */
-#if MAVLINK_CRC_EXTRA
-MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet,
- uint8_t length, uint8_t crc_extra)
-#else
-MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length)
-#endif
-{
- uint16_t checksum;
- uint8_t buf[MAVLINK_NUM_HEADER_BYTES];
- uint8_t ck[2];
- mavlink_status_t *status = mavlink_get_channel_status(chan);
- buf[0] = MAVLINK_STX;
- buf[1] = length;
- buf[2] = status->current_tx_seq;
- buf[3] = mavlink_system.sysid;
- buf[4] = mavlink_system.compid;
- buf[5] = msgid;
- status->current_tx_seq++;
- checksum = crc_calculate((uint8_t*)&buf[1], MAVLINK_CORE_HEADER_LEN);
- crc_accumulate_buffer(&checksum, packet, length);
-#if MAVLINK_CRC_EXTRA
- crc_accumulate(crc_extra, &checksum);
-#endif
- ck[0] = (uint8_t)(checksum & 0xFF);
- ck[1] = (uint8_t)(checksum >> 8);
-
- MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length);
- _mavlink_send_uart(chan, (const char *)buf, MAVLINK_NUM_HEADER_BYTES);
- _mavlink_send_uart(chan, packet, length);
- _mavlink_send_uart(chan, (const char *)ck, 2);
- MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length);
-}
-#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-/**
- * @brief Pack a message to send it over a serial byte stream
- */
-MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg)
-{
- memcpy(buffer, (const uint8_t *)&msg->magic, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len);
- return MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len;
-}
-
-union __mavlink_bitfield {
- uint8_t uint8;
- int8_t int8;
- uint16_t uint16;
- int16_t int16;
- uint32_t uint32;
- int32_t int32;
-};
-
-
-MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg)
-{
- crc_init(&msg->checksum);
-}
-
-MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c)
-{
- crc_accumulate(c, &msg->checksum);
-}
-
-/**
- * This is a convenience function which handles the complete MAVLink parsing.
- * the function will parse one byte at a time and return the complete packet once
- * it could be successfully decoded. Checksum and other failures will be silently
- * ignored.
- *
- * @param chan ID of the current channel. This allows to parse different channels with this function.
- * a channel is not a physical message channel like a serial port, but a logic partition of
- * the communication streams in this case. COMM_NB is the limit for the number of channels
- * on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows
- * @param c The char to barse
- *
- * @param returnMsg NULL if no message could be decoded, the message data else
- * @return 0 if no message could be decoded, 1 else
- *
- * A typical use scenario of this function call is:
- *
- * @code
- * #include <inttypes.h> // For fixed-width uint8_t type
- *
- * mavlink_message_t msg;
- * int chan = 0;
- *
- *
- * while(serial.bytesAvailable > 0)
- * {
- * uint8_t byte = serial.getNextByte();
- * if (mavlink_parse_char(chan, byte, &msg))
- * {
- * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid);
- * }
- * }
- *
- *
- * @endcode
- */
-MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status)
-{
- /*
- default message crc function. You can override this per-system to
- put this data in a different memory segment
- */
-#if MAVLINK_CRC_EXTRA
-#ifndef MAVLINK_MESSAGE_CRC
- static const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS;
-#define MAVLINK_MESSAGE_CRC(msgid) mavlink_message_crcs[msgid]
-#endif
-#endif
-
- mavlink_message_t* rxmsg = mavlink_get_channel_buffer(chan); ///< The currently decoded message
- mavlink_status_t* status = mavlink_get_channel_status(chan); ///< The current decode status
- int bufferIndex = 0;
-
- status->msg_received = 0;
-
- switch (status->parse_state)
- {
- case MAVLINK_PARSE_STATE_UNINIT:
- case MAVLINK_PARSE_STATE_IDLE:
- if (c == MAVLINK_STX)
- {
- status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
- rxmsg->len = 0;
- rxmsg->magic = c;
- mavlink_start_checksum(rxmsg);
- }
- break;
-
- case MAVLINK_PARSE_STATE_GOT_STX:
- if (status->msg_received
-/* Support shorter buffers than the
- default maximum packet size */
-#if (MAVLINK_MAX_PAYLOAD_LEN < 255)
- || c > MAVLINK_MAX_PAYLOAD_LEN
-#endif
- )
- {
- status->buffer_overrun++;
- status->parse_error++;
- status->msg_received = 0;
- status->parse_state = MAVLINK_PARSE_STATE_IDLE;
- }
- else
- {
- // NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2
- rxmsg->len = c;
- status->packet_idx = 0;
- mavlink_update_checksum(rxmsg, c);
- status->parse_state = MAVLINK_PARSE_STATE_GOT_LENGTH;
- }
- break;
-
- case MAVLINK_PARSE_STATE_GOT_LENGTH:
- rxmsg->seq = c;
- mavlink_update_checksum(rxmsg, c);
- status->parse_state = MAVLINK_PARSE_STATE_GOT_SEQ;
- break;
-
- case MAVLINK_PARSE_STATE_GOT_SEQ:
- rxmsg->sysid = c;
- mavlink_update_checksum(rxmsg, c);
- status->parse_state = MAVLINK_PARSE_STATE_GOT_SYSID;
- break;
-
- case MAVLINK_PARSE_STATE_GOT_SYSID:
- rxmsg->compid = c;
- mavlink_update_checksum(rxmsg, c);
- status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPID;
- break;
-
- case MAVLINK_PARSE_STATE_GOT_COMPID:
- rxmsg->msgid = c;
- mavlink_update_checksum(rxmsg, c);
- if (rxmsg->len == 0)
- {
- status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD;
- }
- else
- {
- status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID;
- }
- break;
-
- case MAVLINK_PARSE_STATE_GOT_MSGID:
- _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx++] = (char)c;
- mavlink_update_checksum(rxmsg, c);
- if (status->packet_idx == rxmsg->len)
- {
- status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD;
- }
- break;
-
- case MAVLINK_PARSE_STATE_GOT_PAYLOAD:
-#if MAVLINK_CRC_EXTRA
- mavlink_update_checksum(rxmsg, MAVLINK_MESSAGE_CRC(rxmsg->msgid));
-#endif
- if (c != (rxmsg->checksum & 0xFF)) {
- // Check first checksum byte
- status->parse_error++;
- status->msg_received = 0;
- status->parse_state = MAVLINK_PARSE_STATE_IDLE;
- if (c == MAVLINK_STX)
- {
- status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
- rxmsg->len = 0;
- mavlink_start_checksum(rxmsg);
- }
- }
- else
- {
- status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1;
- _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx] = (char)c;
- }
- break;
-
- case MAVLINK_PARSE_STATE_GOT_CRC1:
- if (c != (rxmsg->checksum >> 8)) {
- // Check second checksum byte
- status->parse_error++;
- status->msg_received = 0;
- status->parse_state = MAVLINK_PARSE_STATE_IDLE;
- if (c == MAVLINK_STX)
- {
- status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
- rxmsg->len = 0;
- mavlink_start_checksum(rxmsg);
- }
- }
- else
- {
- // Successfully got message
- status->msg_received = 1;
- status->parse_state = MAVLINK_PARSE_STATE_IDLE;
- _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx+1] = (char)c;
- memcpy(r_message, rxmsg, sizeof(mavlink_message_t));
- }
- break;
- }
-
- bufferIndex++;
- // If a message has been sucessfully decoded, check index
- if (status->msg_received == 1)
- {
- //while(status->current_seq != rxmsg->seq)
- //{
- // status->packet_rx_drop_count++;
- // status->current_seq++;
- //}
- status->current_rx_seq = rxmsg->seq;
- // Initial condition: If no packet has been received so far, drop count is undefined
- if (status->packet_rx_success_count == 0) status->packet_rx_drop_count = 0;
- // Count this packet as received
- status->packet_rx_success_count++;
- }
-
- r_mavlink_status->current_rx_seq = status->current_rx_seq+1;
- r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count;
- r_mavlink_status->packet_rx_drop_count = status->parse_error;
- status->parse_error = 0;
- return status->msg_received;
-}
-
-/**
- * @brief Put a bitfield of length 1-32 bit into the buffer
- *
- * @param b the value to add, will be encoded in the bitfield
- * @param bits number of bits to use to encode b, e.g. 1 for boolean, 2, 3, etc.
- * @param packet_index the position in the packet (the index of the first byte to use)
- * @param bit_index the position in the byte (the index of the first bit to use)
- * @param buffer packet buffer to write into
- * @return new position of the last used byte in the buffer
- */
-MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index, uint8_t* r_bit_index, uint8_t* buffer)
-{
- uint16_t bits_remain = bits;
- // Transform number into network order
- int32_t v;
- uint8_t i_bit_index, i_byte_index, curr_bits_n;
-#if MAVLINK_NEED_BYTE_SWAP
- union {
- int32_t i;
- uint8_t b[4];
- } bin, bout;
- bin.i = b;
- bout.b[0] = bin.b[3];
- bout.b[1] = bin.b[2];
- bout.b[2] = bin.b[1];
- bout.b[3] = bin.b[0];
- v = bout.i;
-#else
- v = b;
-#endif
-
- // buffer in
- // 01100000 01000000 00000000 11110001
- // buffer out
- // 11110001 00000000 01000000 01100000
-
- // Existing partly filled byte (four free slots)
- // 0111xxxx
-
- // Mask n free bits
- // 00001111 = 2^0 + 2^1 + 2^2 + 2^3 = 2^n - 1
- // = ((uint32_t)(1 << n)) - 1; // = 2^n - 1
-
- // Shift n bits into the right position
- // out = in >> n;
-
- // Mask and shift bytes
- i_bit_index = bit_index;
- i_byte_index = packet_index;
- if (bit_index > 0)
- {
- // If bits were available at start, they were available
- // in the byte before the current index
- i_byte_index--;
- }
-
- // While bits have not been packed yet
- while (bits_remain > 0)
- {
- // Bits still have to be packed
- // there can be more than 8 bits, so
- // we might have to pack them into more than one byte
-
- // First pack everything we can into the current 'open' byte
- //curr_bits_n = bits_remain << 3; // Equals bits_remain mod 8
- //FIXME
- if (bits_remain <= (uint8_t)(8 - i_bit_index))
- {
- // Enough space
- curr_bits_n = (uint8_t)bits_remain;
- }
- else
- {
- curr_bits_n = (8 - i_bit_index);
- }
-
- // Pack these n bits into the current byte
- // Mask out whatever was at that position with ones (xxx11111)
- buffer[i_byte_index] &= (0xFF >> (8 - curr_bits_n));
- // Put content to this position, by masking out the non-used part
- buffer[i_byte_index] |= ((0x00 << curr_bits_n) & v);
-
- // Increment the bit index
- i_bit_index += curr_bits_n;
-
- // Now proceed to the next byte, if necessary
- bits_remain -= curr_bits_n;
- if (bits_remain > 0)
- {
- // Offer another 8 bits / one byte
- i_byte_index++;
- i_bit_index = 0;
- }
- }
-
- *r_bit_index = i_bit_index;
- // If a partly filled byte is present, mark this as consumed
- if (i_bit_index != 7) i_byte_index++;
- return i_byte_index - packet_index;
-}
-
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-// To make MAVLink work on your MCU, define comm_send_ch() if you wish
-// to send 1 byte at a time, or MAVLINK_SEND_UART_BYTES() to send a
-// whole packet at a time
-
-/*
-
-#include "mavlink_types.h"
-
-void comm_send_ch(mavlink_channel_t chan, uint8_t ch)
-{
- if (chan == MAVLINK_COMM_0)
- {
- uart0_transmit(ch);
- }
- if (chan == MAVLINK_COMM_1)
- {
- uart1_transmit(ch);
- }
-}
- */
-
-MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len)
-{
-#ifdef MAVLINK_SEND_UART_BYTES
- /* this is the more efficient approach, if the platform
- defines it */
- MAVLINK_SEND_UART_BYTES(chan, (uint8_t *)buf, len);
-#else
- /* fallback to one byte at a time */
- uint16_t i;
- for (i = 0; i < len; i++) {
- comm_send_ch(chan, (uint8_t)buf[i]);
- }
-#endif
-}
-#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-#endif /* _MAVLINK_HELPERS_H_ */
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_protobuf_manager.hpp b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_protobuf_manager.hpp
deleted file mode 100644
index fd3ddd026..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_protobuf_manager.hpp
+++ /dev/null
@@ -1,377 +0,0 @@
-#ifndef MAVLINKPROTOBUFMANAGER_HPP
-#define MAVLINKPROTOBUFMANAGER_HPP
-
-#include <deque>
-#include <google/protobuf/message.h>
-#include <iostream>
-#include <tr1/memory>
-
-#include <checksum.h>
-#include <common/mavlink.h>
-#include <mavlink_types.h>
-#include <pixhawk/pixhawk.pb.h>
-
-namespace mavlink
-{
-
-class ProtobufManager
-{
-public:
- ProtobufManager()
- : mRegisteredTypeCount(0)
- , mStreamID(0)
- , mVerbose(false)
- , kExtendedHeaderSize(MAVLINK_EXTENDED_HEADER_LEN)
- , kExtendedPayloadMaxSize(MAVLINK_MAX_EXTENDED_PAYLOAD_LEN)
- {
- // register GLOverlay
- {
- std::tr1::shared_ptr<px::GLOverlay> msg(new px::GLOverlay);
- registerType(msg);
- }
-
- // register ObstacleList
- {
- std::tr1::shared_ptr<px::ObstacleList> msg(new px::ObstacleList);
- registerType(msg);
- }
-
- // register ObstacleMap
- {
- std::tr1::shared_ptr<px::ObstacleMap> msg(new px::ObstacleMap);
- registerType(msg);
- }
-
- // register Path
- {
- std::tr1::shared_ptr<px::Path> msg(new px::Path);
- registerType(msg);
- }
-
- // register PointCloudXYZI
- {
- std::tr1::shared_ptr<px::PointCloudXYZI> msg(new px::PointCloudXYZI);
- registerType(msg);
- }
-
- // register PointCloudXYZRGB
- {
- std::tr1::shared_ptr<px::PointCloudXYZRGB> msg(new px::PointCloudXYZRGB);
- registerType(msg);
- }
-
- // register RGBDImage
- {
- std::tr1::shared_ptr<px::RGBDImage> msg(new px::RGBDImage);
- registerType(msg);
- }
-
- srand(time(NULL));
- mStreamID = rand() + 1;
- }
-
- bool fragmentMessage(uint8_t system_id, uint8_t component_id,
- uint8_t target_system, uint8_t target_component,
- const google::protobuf::Message& protobuf_msg,
- std::vector<mavlink_extended_message_t>& fragments) const
- {
- TypeMap::const_iterator it = mTypeMap.find(protobuf_msg.GetTypeName());
- if (it == mTypeMap.end())
- {
- std::cout << "# WARNING: Protobuf message with type "
- << protobuf_msg.GetTypeName() << " is not registered."
- << std::endl;
- return false;
- }
-
- uint8_t typecode = it->second;
-
- std::string data = protobuf_msg.SerializeAsString();
-
- int fragmentCount = (protobuf_msg.ByteSize() + kExtendedPayloadMaxSize - 1) / kExtendedPayloadMaxSize;
- unsigned int offset = 0;
-
- for (int i = 0; i < fragmentCount; ++i)
- {
- mavlink_extended_message_t fragment;
-
- // write extended header data
- uint8_t* payload = reinterpret_cast<uint8_t*>(fragment.base_msg.payload64);
- unsigned int length = 0;
- uint8_t flags = 0;
-
- if (i < fragmentCount - 1)
- {
- length = kExtendedPayloadMaxSize;
- flags |= 0x1;
- }
- else
- {
- length = protobuf_msg.ByteSize() - kExtendedPayloadMaxSize * (fragmentCount - 1);
- }
-
- memcpy(payload, &target_system, 1);
- memcpy(payload + 1, &target_component, 1);
- memcpy(payload + 2, &typecode, 1);
- memcpy(payload + 3, &length, 4);
- memcpy(payload + 7, &mStreamID, 2);
- memcpy(payload + 9, &offset, 4);
- memcpy(payload + 13, &flags, 1);
-
- fragment.base_msg.msgid = MAVLINK_MSG_ID_EXTENDED_MESSAGE;
- mavlink_finalize_message(&fragment.base_msg, system_id, component_id, kExtendedHeaderSize, 0);
-
- // write extended payload data
- fragment.extended_payload_len = length;
- memcpy(fragment.extended_payload, &data[offset], length);
-
- fragments.push_back(fragment);
- offset += length;
- }
-
- if (mVerbose)
- {
- std::cerr << "# INFO: Split extended message with size "
- << protobuf_msg.ByteSize() << " into "
- << fragmentCount << " fragments." << std::endl;
- }
-
- return true;
- }
-
- bool cacheFragment(mavlink_extended_message_t& msg)
- {
- if (!validFragment(msg))
- {
- if (mVerbose)
- {
- std::cerr << "# WARNING: Message is not a valid fragment. "
- << "Dropping message..." << std::endl;
- }
- return false;
- }
-
- // read extended header
- uint8_t* payload = reinterpret_cast<uint8_t*>(msg.base_msg.payload64);
- uint8_t typecode = 0;
- unsigned int length = 0;
- unsigned short streamID = 0;
- unsigned int offset = 0;
- uint8_t flags = 0;
-
- memcpy(&typecode, payload + 2, 1);
- memcpy(&length, payload + 3, 4);
- memcpy(&streamID, payload + 7, 2);
- memcpy(&offset, payload + 9, 4);
- memcpy(&flags, payload + 13, 1);
-
- if (typecode >= mTypeMap.size())
- {
- std::cout << "# WARNING: Protobuf message with type code "
- << static_cast<int>(typecode) << " is not registered." << std::endl;
- return false;
- }
-
- bool reassemble = false;
-
- FragmentQueue::iterator it = mFragmentQueue.find(streamID);
- if (it == mFragmentQueue.end())
- {
- if (offset == 0)
- {
- mFragmentQueue[streamID].push_back(msg);
-
- if ((flags & 0x1) != 0x1)
- {
- reassemble = true;
- }
-
- if (mVerbose)
- {
- std::cerr << "# INFO: Added fragment to new queue."
- << std::endl;
- }
- }
- else
- {
- if (mVerbose)
- {
- std::cerr << "# WARNING: Message is not a valid fragment. "
- << "Dropping message..." << std::endl;
- }
- }
- }
- else
- {
- std::deque<mavlink_extended_message_t>& queue = it->second;
-
- if (queue.empty())
- {
- if (offset == 0)
- {
- queue.push_back(msg);
-
- if ((flags & 0x1) != 0x1)
- {
- reassemble = true;
- }
- }
- else
- {
- if (mVerbose)
- {
- std::cerr << "# WARNING: Message is not a valid fragment. "
- << "Dropping message..." << std::endl;
- }
- }
- }
- else
- {
- if (fragmentDataSize(queue.back()) + fragmentOffset(queue.back()) != offset)
- {
- if (mVerbose)
- {
- std::cerr << "# WARNING: Previous fragment(s) have been lost. "
- << "Dropping message and clearing queue..." << std::endl;
- }
- queue.clear();
- }
- else
- {
- queue.push_back(msg);
-
- if ((flags & 0x1) != 0x1)
- {
- reassemble = true;
- }
- }
- }
- }
-
- if (reassemble)
- {
- std::deque<mavlink_extended_message_t>& queue = mFragmentQueue[streamID];
-
- std::string data;
- for (size_t i = 0; i < queue.size(); ++i)
- {
- mavlink_extended_message_t& mavlink_msg = queue.at(i);
-
- data.append(reinterpret_cast<char*>(&mavlink_msg.extended_payload[0]),
- static_cast<size_t>(mavlink_msg.extended_payload_len));
- }
-
- mMessages.at(typecode)->ParseFromString(data);
-
- mMessageAvailable.at(typecode) = true;
-
- queue.clear();
-
- if (mVerbose)
- {
- std::cerr << "# INFO: Reassembled fragments for message with typename "
- << mMessages.at(typecode)->GetTypeName() << " and size "
- << mMessages.at(typecode)->ByteSize()
- << "." << std::endl;
- }
- }
-
- return true;
- }
-
- bool getMessage(std::tr1::shared_ptr<google::protobuf::Message>& msg)
- {
- for (size_t i = 0; i < mMessageAvailable.size(); ++i)
- {
- if (mMessageAvailable.at(i))
- {
- msg = mMessages.at(i);
- mMessageAvailable.at(i) = false;
-
- return true;
- }
- }
-
- return false;
- }
-
-private:
- void registerType(const std::tr1::shared_ptr<google::protobuf::Message>& msg)
- {
- mTypeMap[msg->GetTypeName()] = mRegisteredTypeCount;
- ++mRegisteredTypeCount;
- mMessages.push_back(msg);
- mMessageAvailable.push_back(false);
- }
-
- bool validFragment(const mavlink_extended_message_t& msg) const
- {
- if (msg.base_msg.magic != MAVLINK_STX ||
- msg.base_msg.len != kExtendedHeaderSize ||
- msg.base_msg.msgid != MAVLINK_MSG_ID_EXTENDED_MESSAGE)
- {
- return false;
- }
-
- uint16_t checksum;
- checksum = crc_calculate(reinterpret_cast<const uint8_t*>(&msg.base_msg.len), MAVLINK_CORE_HEADER_LEN);
- crc_accumulate_buffer(&checksum, reinterpret_cast<const char*>(&msg.base_msg.payload64), kExtendedHeaderSize);
-#if MAVLINK_CRC_EXTRA
- static const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS;
- crc_accumulate(mavlink_message_crcs[msg.base_msg.msgid], &checksum);
-#endif
-
- if (mavlink_ck_a(&(msg.base_msg)) != (uint8_t)(checksum & 0xFF) &&
- mavlink_ck_b(&(msg.base_msg)) != (uint8_t)(checksum >> 8))
- {
- return false;
- }
-
- return true;
- }
-
- unsigned int fragmentDataSize(const mavlink_extended_message_t& msg) const
- {
- const uint8_t* payload = reinterpret_cast<const uint8_t*>(msg.base_msg.payload64);
-
- return *(reinterpret_cast<const unsigned int*>(payload + 3));
- }
-
- unsigned int fragmentOffset(const mavlink_extended_message_t& msg) const
- {
- const uint8_t* payload = reinterpret_cast<const uint8_t*>(msg.base_msg.payload64);
-
- return *(reinterpret_cast<const unsigned int*>(payload + 9));
- }
-
- int mRegisteredTypeCount;
- unsigned short mStreamID;
- bool mVerbose;
-
- typedef std::map<std::string, uint8_t> TypeMap;
- TypeMap mTypeMap;
- std::vector< std::tr1::shared_ptr<google::protobuf::Message> > mMessages;
- std::vector<bool> mMessageAvailable;
-
- typedef std::map<unsigned short, std::deque<mavlink_extended_message_t> > FragmentQueue;
- FragmentQueue mFragmentQueue;
-
- const int kExtendedHeaderSize;
- /**
- * Extended header structure
- * =========================
- * byte 0 - target_system
- * byte 1 - target_component
- * byte 2 - extended message id (type code)
- * bytes 3-6 - extended payload size in bytes
- * byte 7-8 - stream ID
- * byte 9-12 - fragment offset
- * byte 13 - fragment flags (bit 0 - 1=more fragments, 0=last fragment)
- */
-
- const int kExtendedPayloadMaxSize;
-};
-
-}
-
-#endif
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_types.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_types.h
deleted file mode 100644
index 5fbde97f7..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_types.h
+++ /dev/null
@@ -1,158 +0,0 @@
-#ifndef MAVLINK_TYPES_H_
-#define MAVLINK_TYPES_H_
-
-#include <inttypes.h>
-
-#ifndef MAVLINK_MAX_PAYLOAD_LEN
-// it is possible to override this, but be careful!
-#define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length
-#endif
-
-#define MAVLINK_CORE_HEADER_LEN 5 ///< Length of core header (of the comm. layer): message length (1 byte) + message sequence (1 byte) + message system id (1 byte) + message component id (1 byte) + message type id (1 byte)
-#define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1) ///< Length of all header bytes, including core and checksum
-#define MAVLINK_NUM_CHECKSUM_BYTES 2
-#define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES)
-
-#define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) ///< Maximum packet length
-
-#define MAVLINK_MSG_ID_EXTENDED_MESSAGE 255
-#define MAVLINK_EXTENDED_HEADER_LEN 14
-
-#if (defined _MSC_VER) | ((defined __APPLE__) & (defined __MACH__)) | (defined __linux__)
- /* full fledged 32bit++ OS */
- #define MAVLINK_MAX_EXTENDED_PACKET_LEN 65507
-#else
- /* small microcontrollers */
- #define MAVLINK_MAX_EXTENDED_PACKET_LEN 2048
-#endif
-
-#define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES)
-
-typedef struct param_union {
- union {
- float param_float;
- int32_t param_int32;
- uint32_t param_uint32;
- uint8_t param_uint8;
- uint8_t bytes[4];
- };
- uint8_t type;
-} mavlink_param_union_t;
-
-typedef struct __mavlink_system {
- uint8_t sysid; ///< Used by the MAVLink message_xx_send() convenience function
- uint8_t compid; ///< Used by the MAVLink message_xx_send() convenience function
- uint8_t type; ///< Unused, can be used by user to store the system's type
- uint8_t state; ///< Unused, can be used by user to store the system's state
- uint8_t mode; ///< Unused, can be used by user to store the system's mode
- uint8_t nav_mode; ///< Unused, can be used by user to store the system's navigation mode
-} mavlink_system_t;
-
-typedef struct __mavlink_message {
- uint16_t checksum; /// sent at end of packet
- uint8_t magic; ///< protocol magic marker
- uint8_t len; ///< Length of payload
- uint8_t seq; ///< Sequence of packet
- uint8_t sysid; ///< ID of message sender system/aircraft
- uint8_t compid; ///< ID of the message sender component
- uint8_t msgid; ///< ID of message in payload
- uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8];
-} mavlink_message_t;
-
-
-typedef struct __mavlink_extended_message {
- mavlink_message_t base_msg;
- int32_t extended_payload_len; ///< Length of extended payload if any
- uint8_t extended_payload[MAVLINK_MAX_EXTENDED_PAYLOAD_LEN];
-} mavlink_extended_message_t;
-
-
-typedef enum {
- MAVLINK_TYPE_CHAR = 0,
- MAVLINK_TYPE_UINT8_T = 1,
- MAVLINK_TYPE_INT8_T = 2,
- MAVLINK_TYPE_UINT16_T = 3,
- MAVLINK_TYPE_INT16_T = 4,
- MAVLINK_TYPE_UINT32_T = 5,
- MAVLINK_TYPE_INT32_T = 6,
- MAVLINK_TYPE_UINT64_T = 7,
- MAVLINK_TYPE_INT64_T = 8,
- MAVLINK_TYPE_FLOAT = 9,
- MAVLINK_TYPE_DOUBLE = 10
-} mavlink_message_type_t;
-
-#define MAVLINK_MAX_FIELDS 64
-
-typedef struct __mavlink_field_info {
- const char *name; // name of this field
- const char *print_format; // printing format hint, or NULL
- mavlink_message_type_t type; // type of this field
- unsigned int array_length; // if non-zero, field is an array
- unsigned int wire_offset; // offset of each field in the payload
- unsigned int structure_offset; // offset in a C structure
-} mavlink_field_info_t;
-
-// note that in this structure the order of fields is the order
-// in the XML file, not necessary the wire order
-typedef struct __mavlink_message_info {
- const char *name; // name of the message
- unsigned num_fields; // how many fields in this message
- mavlink_field_info_t fields[MAVLINK_MAX_FIELDS]; // field information
-} mavlink_message_info_t;
-
-#define _MAV_PAYLOAD(msg) ((const char *)(&((msg)->payload64[0])))
-#define _MAV_PAYLOAD_NON_CONST(msg) ((char *)(&((msg)->payload64[0])))
-
-// checksum is immediately after the payload bytes
-#define mavlink_ck_a(msg) *((msg)->len + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg))
-#define mavlink_ck_b(msg) *(((msg)->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg))
-
-typedef enum {
- MAVLINK_COMM_0,
- MAVLINK_COMM_1,
- MAVLINK_COMM_2,
- MAVLINK_COMM_3
-} mavlink_channel_t;
-
-/*
- * applications can set MAVLINK_COMM_NUM_BUFFERS to the maximum number
- * of buffers they will use. If more are used, then the result will be
- * a stack overrun
- */
-#ifndef MAVLINK_COMM_NUM_BUFFERS
-#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32)
-# define MAVLINK_COMM_NUM_BUFFERS 16
-#else
-# define MAVLINK_COMM_NUM_BUFFERS 4
-#endif
-#endif
-
-typedef enum {
- MAVLINK_PARSE_STATE_UNINIT=0,
- MAVLINK_PARSE_STATE_IDLE,
- MAVLINK_PARSE_STATE_GOT_STX,
- MAVLINK_PARSE_STATE_GOT_SEQ,
- MAVLINK_PARSE_STATE_GOT_LENGTH,
- MAVLINK_PARSE_STATE_GOT_SYSID,
- MAVLINK_PARSE_STATE_GOT_COMPID,
- MAVLINK_PARSE_STATE_GOT_MSGID,
- MAVLINK_PARSE_STATE_GOT_PAYLOAD,
- MAVLINK_PARSE_STATE_GOT_CRC1
-} mavlink_parse_state_t; ///< The state machine for the comm parser
-
-typedef struct __mavlink_status {
- uint8_t msg_received; ///< Number of received messages
- uint8_t buffer_overrun; ///< Number of buffer overruns
- uint8_t parse_error; ///< Number of parse errors
- mavlink_parse_state_t parse_state; ///< Parsing state machine
- uint8_t packet_idx; ///< Index in current packet
- uint8_t current_rx_seq; ///< Sequence number of last packet received
- uint8_t current_tx_seq; ///< Sequence number of last packet sent
- uint16_t packet_rx_success_count; ///< Received packets
- uint16_t packet_rx_drop_count; ///< Number of packet drops
-} mavlink_status_t;
-
-#define MAVLINK_BIG_ENDIAN 0
-#define MAVLINK_LITTLE_ENDIAN 1
-
-#endif /* MAVLINK_TYPES_H_ */
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/pixhawk/pixhawk.pb.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/pixhawk/pixhawk.pb.h
deleted file mode 100644
index 7556606e9..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/pixhawk/pixhawk.pb.h
+++ /dev/null
@@ -1,3663 +0,0 @@
-// Generated by the protocol buffer compiler. DO NOT EDIT!
-// source: pixhawk.proto
-
-#ifndef PROTOBUF_pixhawk_2eproto__INCLUDED
-#define PROTOBUF_pixhawk_2eproto__INCLUDED
-
-#include <string>
-
-#include <google/protobuf/stubs/common.h>
-
-#if GOOGLE_PROTOBUF_VERSION < 2004000
-#error This file was generated by a newer version of protoc which is
-#error incompatible with your Protocol Buffer headers. Please update
-#error your headers.
-#endif
-#if 2004001 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION
-#error This file was generated by an older version of protoc which is
-#error incompatible with your Protocol Buffer headers. Please
-#error regenerate this file with a newer version of protoc.
-#endif
-
-#include <google/protobuf/generated_message_util.h>
-#include <google/protobuf/repeated_field.h>
-#include <google/protobuf/extension_set.h>
-#include <google/protobuf/generated_message_reflection.h>
-// @@protoc_insertion_point(includes)
-
-namespace px {
-
-// Internal implementation detail -- do not call these.
-void protobuf_AddDesc_pixhawk_2eproto();
-void protobuf_AssignDesc_pixhawk_2eproto();
-void protobuf_ShutdownFile_pixhawk_2eproto();
-
-class HeaderInfo;
-class GLOverlay;
-class Obstacle;
-class ObstacleList;
-class ObstacleMap;
-class Path;
-class PointCloudXYZI;
-class PointCloudXYZI_PointXYZI;
-class PointCloudXYZRGB;
-class PointCloudXYZRGB_PointXYZRGB;
-class RGBDImage;
-class Waypoint;
-
-enum GLOverlay_CoordinateFrameType {
- GLOverlay_CoordinateFrameType_GLOBAL = 0,
- GLOverlay_CoordinateFrameType_LOCAL = 1
-};
-bool GLOverlay_CoordinateFrameType_IsValid(int value);
-const GLOverlay_CoordinateFrameType GLOverlay_CoordinateFrameType_CoordinateFrameType_MIN = GLOverlay_CoordinateFrameType_GLOBAL;
-const GLOverlay_CoordinateFrameType GLOverlay_CoordinateFrameType_CoordinateFrameType_MAX = GLOverlay_CoordinateFrameType_LOCAL;
-const int GLOverlay_CoordinateFrameType_CoordinateFrameType_ARRAYSIZE = GLOverlay_CoordinateFrameType_CoordinateFrameType_MAX + 1;
-
-const ::google::protobuf::EnumDescriptor* GLOverlay_CoordinateFrameType_descriptor();
-inline const ::std::string& GLOverlay_CoordinateFrameType_Name(GLOverlay_CoordinateFrameType value) {
- return ::google::protobuf::internal::NameOfEnum(
- GLOverlay_CoordinateFrameType_descriptor(), value);
-}
-inline bool GLOverlay_CoordinateFrameType_Parse(
- const ::std::string& name, GLOverlay_CoordinateFrameType* value) {
- return ::google::protobuf::internal::ParseNamedEnum<GLOverlay_CoordinateFrameType>(
- GLOverlay_CoordinateFrameType_descriptor(), name, value);
-}
-enum GLOverlay_Mode {
- GLOverlay_Mode_POINTS = 0,
- GLOverlay_Mode_LINES = 1,
- GLOverlay_Mode_LINE_STRIP = 2,
- GLOverlay_Mode_LINE_LOOP = 3,
- GLOverlay_Mode_TRIANGLES = 4,
- GLOverlay_Mode_TRIANGLE_STRIP = 5,
- GLOverlay_Mode_TRIANGLE_FAN = 6,
- GLOverlay_Mode_QUADS = 7,
- GLOverlay_Mode_QUAD_STRIP = 8,
- GLOverlay_Mode_POLYGON = 9,
- GLOverlay_Mode_SOLID_CIRCLE = 10,
- GLOverlay_Mode_WIRE_CIRCLE = 11,
- GLOverlay_Mode_SOLID_CUBE = 12,
- GLOverlay_Mode_WIRE_CUBE = 13
-};
-bool GLOverlay_Mode_IsValid(int value);
-const GLOverlay_Mode GLOverlay_Mode_Mode_MIN = GLOverlay_Mode_POINTS;
-const GLOverlay_Mode GLOverlay_Mode_Mode_MAX = GLOverlay_Mode_WIRE_CUBE;
-const int GLOverlay_Mode_Mode_ARRAYSIZE = GLOverlay_Mode_Mode_MAX + 1;
-
-const ::google::protobuf::EnumDescriptor* GLOverlay_Mode_descriptor();
-inline const ::std::string& GLOverlay_Mode_Name(GLOverlay_Mode value) {
- return ::google::protobuf::internal::NameOfEnum(
- GLOverlay_Mode_descriptor(), value);
-}
-inline bool GLOverlay_Mode_Parse(
- const ::std::string& name, GLOverlay_Mode* value) {
- return ::google::protobuf::internal::ParseNamedEnum<GLOverlay_Mode>(
- GLOverlay_Mode_descriptor(), name, value);
-}
-enum GLOverlay_Identifier {
- GLOverlay_Identifier_END = 14,
- GLOverlay_Identifier_VERTEX2F = 15,
- GLOverlay_Identifier_VERTEX3F = 16,
- GLOverlay_Identifier_ROTATEF = 17,
- GLOverlay_Identifier_TRANSLATEF = 18,
- GLOverlay_Identifier_SCALEF = 19,
- GLOverlay_Identifier_PUSH_MATRIX = 20,
- GLOverlay_Identifier_POP_MATRIX = 21,
- GLOverlay_Identifier_COLOR3F = 22,
- GLOverlay_Identifier_COLOR4F = 23,
- GLOverlay_Identifier_POINTSIZE = 24,
- GLOverlay_Identifier_LINEWIDTH = 25
-};
-bool GLOverlay_Identifier_IsValid(int value);
-const GLOverlay_Identifier GLOverlay_Identifier_Identifier_MIN = GLOverlay_Identifier_END;
-const GLOverlay_Identifier GLOverlay_Identifier_Identifier_MAX = GLOverlay_Identifier_LINEWIDTH;
-const int GLOverlay_Identifier_Identifier_ARRAYSIZE = GLOverlay_Identifier_Identifier_MAX + 1;
-
-const ::google::protobuf::EnumDescriptor* GLOverlay_Identifier_descriptor();
-inline const ::std::string& GLOverlay_Identifier_Name(GLOverlay_Identifier value) {
- return ::google::protobuf::internal::NameOfEnum(
- GLOverlay_Identifier_descriptor(), value);
-}
-inline bool GLOverlay_Identifier_Parse(
- const ::std::string& name, GLOverlay_Identifier* value) {
- return ::google::protobuf::internal::ParseNamedEnum<GLOverlay_Identifier>(
- GLOverlay_Identifier_descriptor(), name, value);
-}
-// ===================================================================
-
-class HeaderInfo : public ::google::protobuf::Message {
- public:
- HeaderInfo();
- virtual ~HeaderInfo();
-
- HeaderInfo(const HeaderInfo& from);
-
- inline HeaderInfo& operator=(const HeaderInfo& from) {
- CopyFrom(from);
- return *this;
- }
-
- inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const {
- return _unknown_fields_;
- }
-
- inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() {
- return &_unknown_fields_;
- }
-
- static const ::google::protobuf::Descriptor* descriptor();
- static const HeaderInfo& default_instance();
-
- void Swap(HeaderInfo* other);
-
- // implements Message ----------------------------------------------
-
- HeaderInfo* New() const;
- void CopyFrom(const ::google::protobuf::Message& from);
- void MergeFrom(const ::google::protobuf::Message& from);
- void CopyFrom(const HeaderInfo& from);
- void MergeFrom(const HeaderInfo& from);
- void Clear();
- bool IsInitialized() const;
-
- int ByteSize() const;
- bool MergePartialFromCodedStream(
- ::google::protobuf::io::CodedInputStream* input);
- void SerializeWithCachedSizes(
- ::google::protobuf::io::CodedOutputStream* output) const;
- ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const;
- int GetCachedSize() const { return _cached_size_; }
- private:
- void SharedCtor();
- void SharedDtor();
- void SetCachedSize(int size) const;
- public:
-
- ::google::protobuf::Metadata GetMetadata() const;
-
- // nested types ----------------------------------------------------
-
- // accessors -------------------------------------------------------
-
- // required int32 source_sysid = 1;
- inline bool has_source_sysid() const;
- inline void clear_source_sysid();
- static const int kSourceSysidFieldNumber = 1;
- inline ::google::protobuf::int32 source_sysid() const;
- inline void set_source_sysid(::google::protobuf::int32 value);
-
- // required int32 source_compid = 2;
- inline bool has_source_compid() const;
- inline void clear_source_compid();
- static const int kSourceCompidFieldNumber = 2;
- inline ::google::protobuf::int32 source_compid() const;
- inline void set_source_compid(::google::protobuf::int32 value);
-
- // required double timestamp = 3;
- inline bool has_timestamp() const;
- inline void clear_timestamp();
- static const int kTimestampFieldNumber = 3;
- inline double timestamp() const;
- inline void set_timestamp(double value);
-
- // @@protoc_insertion_point(class_scope:px.HeaderInfo)
- private:
- inline void set_has_source_sysid();
- inline void clear_has_source_sysid();
- inline void set_has_source_compid();
- inline void clear_has_source_compid();
- inline void set_has_timestamp();
- inline void clear_has_timestamp();
-
- ::google::protobuf::UnknownFieldSet _unknown_fields_;
-
- ::google::protobuf::int32 source_sysid_;
- ::google::protobuf::int32 source_compid_;
- double timestamp_;
-
- mutable int _cached_size_;
- ::google::protobuf::uint32 _has_bits_[(3 + 31) / 32];
-
- friend void protobuf_AddDesc_pixhawk_2eproto();
- friend void protobuf_AssignDesc_pixhawk_2eproto();
- friend void protobuf_ShutdownFile_pixhawk_2eproto();
-
- void InitAsDefaultInstance();
- static HeaderInfo* default_instance_;
-};
-// -------------------------------------------------------------------
-
-class GLOverlay : public ::google::protobuf::Message {
- public:
- GLOverlay();
- virtual ~GLOverlay();
-
- GLOverlay(const GLOverlay& from);
-
- inline GLOverlay& operator=(const GLOverlay& from) {
- CopyFrom(from);
- return *this;
- }
-
- inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const {
- return _unknown_fields_;
- }
-
- inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() {
- return &_unknown_fields_;
- }
-
- static const ::google::protobuf::Descriptor* descriptor();
- static const GLOverlay& default_instance();
-
- void Swap(GLOverlay* other);
-
- // implements Message ----------------------------------------------
-
- GLOverlay* New() const;
- void CopyFrom(const ::google::protobuf::Message& from);
- void MergeFrom(const ::google::protobuf::Message& from);
- void CopyFrom(const GLOverlay& from);
- void MergeFrom(const GLOverlay& from);
- void Clear();
- bool IsInitialized() const;
-
- int ByteSize() const;
- bool MergePartialFromCodedStream(
- ::google::protobuf::io::CodedInputStream* input);
- void SerializeWithCachedSizes(
- ::google::protobuf::io::CodedOutputStream* output) const;
- ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const;
- int GetCachedSize() const { return _cached_size_; }
- private:
- void SharedCtor();
- void SharedDtor();
- void SetCachedSize(int size) const;
- public:
-
- ::google::protobuf::Metadata GetMetadata() const;
-
- // nested types ----------------------------------------------------
-
- typedef GLOverlay_CoordinateFrameType CoordinateFrameType;
- static const CoordinateFrameType GLOBAL = GLOverlay_CoordinateFrameType_GLOBAL;
- static const CoordinateFrameType LOCAL = GLOverlay_CoordinateFrameType_LOCAL;
- static inline bool CoordinateFrameType_IsValid(int value) {
- return GLOverlay_CoordinateFrameType_IsValid(value);
- }
- static const CoordinateFrameType CoordinateFrameType_MIN =
- GLOverlay_CoordinateFrameType_CoordinateFrameType_MIN;
- static const CoordinateFrameType CoordinateFrameType_MAX =
- GLOverlay_CoordinateFrameType_CoordinateFrameType_MAX;
- static const int CoordinateFrameType_ARRAYSIZE =
- GLOverlay_CoordinateFrameType_CoordinateFrameType_ARRAYSIZE;
- static inline const ::google::protobuf::EnumDescriptor*
- CoordinateFrameType_descriptor() {
- return GLOverlay_CoordinateFrameType_descriptor();
- }
- static inline const ::std::string& CoordinateFrameType_Name(CoordinateFrameType value) {
- return GLOverlay_CoordinateFrameType_Name(value);
- }
- static inline bool CoordinateFrameType_Parse(const ::std::string& name,
- CoordinateFrameType* value) {
- return GLOverlay_CoordinateFrameType_Parse(name, value);
- }
-
- typedef GLOverlay_Mode Mode;
- static const Mode POINTS = GLOverlay_Mode_POINTS;
- static const Mode LINES = GLOverlay_Mode_LINES;
- static const Mode LINE_STRIP = GLOverlay_Mode_LINE_STRIP;
- static const Mode LINE_LOOP = GLOverlay_Mode_LINE_LOOP;
- static const Mode TRIANGLES = GLOverlay_Mode_TRIANGLES;
- static const Mode TRIANGLE_STRIP = GLOverlay_Mode_TRIANGLE_STRIP;
- static const Mode TRIANGLE_FAN = GLOverlay_Mode_TRIANGLE_FAN;
- static const Mode QUADS = GLOverlay_Mode_QUADS;
- static const Mode QUAD_STRIP = GLOverlay_Mode_QUAD_STRIP;
- static const Mode POLYGON = GLOverlay_Mode_POLYGON;
- static const Mode SOLID_CIRCLE = GLOverlay_Mode_SOLID_CIRCLE;
- static const Mode WIRE_CIRCLE = GLOverlay_Mode_WIRE_CIRCLE;
- static const Mode SOLID_CUBE = GLOverlay_Mode_SOLID_CUBE;
- static const Mode WIRE_CUBE = GLOverlay_Mode_WIRE_CUBE;
- static inline bool Mode_IsValid(int value) {
- return GLOverlay_Mode_IsValid(value);
- }
- static const Mode Mode_MIN =
- GLOverlay_Mode_Mode_MIN;
- static const Mode Mode_MAX =
- GLOverlay_Mode_Mode_MAX;
- static const int Mode_ARRAYSIZE =
- GLOverlay_Mode_Mode_ARRAYSIZE;
- static inline const ::google::protobuf::EnumDescriptor*
- Mode_descriptor() {
- return GLOverlay_Mode_descriptor();
- }
- static inline const ::std::string& Mode_Name(Mode value) {
- return GLOverlay_Mode_Name(value);
- }
- static inline bool Mode_Parse(const ::std::string& name,
- Mode* value) {
- return GLOverlay_Mode_Parse(name, value);
- }
-
- typedef GLOverlay_Identifier Identifier;
- static const Identifier END = GLOverlay_Identifier_END;
- static const Identifier VERTEX2F = GLOverlay_Identifier_VERTEX2F;
- static const Identifier VERTEX3F = GLOverlay_Identifier_VERTEX3F;
- static const Identifier ROTATEF = GLOverlay_Identifier_ROTATEF;
- static const Identifier TRANSLATEF = GLOverlay_Identifier_TRANSLATEF;
- static const Identifier SCALEF = GLOverlay_Identifier_SCALEF;
- static const Identifier PUSH_MATRIX = GLOverlay_Identifier_PUSH_MATRIX;
- static const Identifier POP_MATRIX = GLOverlay_Identifier_POP_MATRIX;
- static const Identifier COLOR3F = GLOverlay_Identifier_COLOR3F;
- static const Identifier COLOR4F = GLOverlay_Identifier_COLOR4F;
- static const Identifier POINTSIZE = GLOverlay_Identifier_POINTSIZE;
- static const Identifier LINEWIDTH = GLOverlay_Identifier_LINEWIDTH;
- static inline bool Identifier_IsValid(int value) {
- return GLOverlay_Identifier_IsValid(value);
- }
- static const Identifier Identifier_MIN =
- GLOverlay_Identifier_Identifier_MIN;
- static const Identifier Identifier_MAX =
- GLOverlay_Identifier_Identifier_MAX;
- static const int Identifier_ARRAYSIZE =
- GLOverlay_Identifier_Identifier_ARRAYSIZE;
- static inline const ::google::protobuf::EnumDescriptor*
- Identifier_descriptor() {
- return GLOverlay_Identifier_descriptor();
- }
- static inline const ::std::string& Identifier_Name(Identifier value) {
- return GLOverlay_Identifier_Name(value);
- }
- static inline bool Identifier_Parse(const ::std::string& name,
- Identifier* value) {
- return GLOverlay_Identifier_Parse(name, value);
- }
-
- // accessors -------------------------------------------------------
-
- // required .px.HeaderInfo header = 1;
- inline bool has_header() const;
- inline void clear_header();
- static const int kHeaderFieldNumber = 1;
- inline const ::px::HeaderInfo& header() const;
- inline ::px::HeaderInfo* mutable_header();
- inline ::px::HeaderInfo* release_header();
-
- // optional string name = 2;
- inline bool has_name() const;
- inline void clear_name();
- static const int kNameFieldNumber = 2;
- inline const ::std::string& name() const;
- inline void set_name(const ::std::string& value);
- inline void set_name(const char* value);
- inline void set_name(const char* value, size_t size);
- inline ::std::string* mutable_name();
- inline ::std::string* release_name();
-
- // optional .px.GLOverlay.CoordinateFrameType coordinateFrameType = 3;
- inline bool has_coordinateframetype() const;
- inline void clear_coordinateframetype();
- static const int kCoordinateFrameTypeFieldNumber = 3;
- inline ::px::GLOverlay_CoordinateFrameType coordinateframetype() const;
- inline void set_coordinateframetype(::px::GLOverlay_CoordinateFrameType value);
-
- // optional double origin_x = 4;
- inline bool has_origin_x() const;
- inline void clear_origin_x();
- static const int kOriginXFieldNumber = 4;
- inline double origin_x() const;
- inline void set_origin_x(double value);
-
- // optional double origin_y = 5;
- inline bool has_origin_y() const;
- inline void clear_origin_y();
- static const int kOriginYFieldNumber = 5;
- inline double origin_y() const;
- inline void set_origin_y(double value);
-
- // optional double origin_z = 6;
- inline bool has_origin_z() const;
- inline void clear_origin_z();
- static const int kOriginZFieldNumber = 6;
- inline double origin_z() const;
- inline void set_origin_z(double value);
-
- // optional bytes data = 7;
- inline bool has_data() const;
- inline void clear_data();
- static const int kDataFieldNumber = 7;
- inline const ::std::string& data() const;
- inline void set_data(const ::std::string& value);
- inline void set_data(const char* value);
- inline void set_data(const void* value, size_t size);
- inline ::std::string* mutable_data();
- inline ::std::string* release_data();
-
- // @@protoc_insertion_point(class_scope:px.GLOverlay)
- private:
- inline void set_has_header();
- inline void clear_has_header();
- inline void set_has_name();
- inline void clear_has_name();
- inline void set_has_coordinateframetype();
- inline void clear_has_coordinateframetype();
- inline void set_has_origin_x();
- inline void clear_has_origin_x();
- inline void set_has_origin_y();
- inline void clear_has_origin_y();
- inline void set_has_origin_z();
- inline void clear_has_origin_z();
- inline void set_has_data();
- inline void clear_has_data();
-
- ::google::protobuf::UnknownFieldSet _unknown_fields_;
-
- ::px::HeaderInfo* header_;
- ::std::string* name_;
- double origin_x_;
- double origin_y_;
- double origin_z_;
- ::std::string* data_;
- int coordinateframetype_;
-
- mutable int _cached_size_;
- ::google::protobuf::uint32 _has_bits_[(7 + 31) / 32];
-
- friend void protobuf_AddDesc_pixhawk_2eproto();
- friend void protobuf_AssignDesc_pixhawk_2eproto();
- friend void protobuf_ShutdownFile_pixhawk_2eproto();
-
- void InitAsDefaultInstance();
- static GLOverlay* default_instance_;
-};
-// -------------------------------------------------------------------
-
-class Obstacle : public ::google::protobuf::Message {
- public:
- Obstacle();
- virtual ~Obstacle();
-
- Obstacle(const Obstacle& from);
-
- inline Obstacle& operator=(const Obstacle& from) {
- CopyFrom(from);
- return *this;
- }
-
- inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const {
- return _unknown_fields_;
- }
-
- inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() {
- return &_unknown_fields_;
- }
-
- static const ::google::protobuf::Descriptor* descriptor();
- static const Obstacle& default_instance();
-
- void Swap(Obstacle* other);
-
- // implements Message ----------------------------------------------
-
- Obstacle* New() const;
- void CopyFrom(const ::google::protobuf::Message& from);
- void MergeFrom(const ::google::protobuf::Message& from);
- void CopyFrom(const Obstacle& from);
- void MergeFrom(const Obstacle& from);
- void Clear();
- bool IsInitialized() const;
-
- int ByteSize() const;
- bool MergePartialFromCodedStream(
- ::google::protobuf::io::CodedInputStream* input);
- void SerializeWithCachedSizes(
- ::google::protobuf::io::CodedOutputStream* output) const;
- ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const;
- int GetCachedSize() const { return _cached_size_; }
- private:
- void SharedCtor();
- void SharedDtor();
- void SetCachedSize(int size) const;
- public:
-
- ::google::protobuf::Metadata GetMetadata() const;
-
- // nested types ----------------------------------------------------
-
- // accessors -------------------------------------------------------
-
- // optional float x = 1;
- inline bool has_x() const;
- inline void clear_x();
- static const int kXFieldNumber = 1;
- inline float x() const;
- inline void set_x(float value);
-
- // optional float y = 2;
- inline bool has_y() const;
- inline void clear_y();
- static const int kYFieldNumber = 2;
- inline float y() const;
- inline void set_y(float value);
-
- // optional float z = 3;
- inline bool has_z() const;
- inline void clear_z();
- static const int kZFieldNumber = 3;
- inline float z() const;
- inline void set_z(float value);
-
- // optional float length = 4;
- inline bool has_length() const;
- inline void clear_length();
- static const int kLengthFieldNumber = 4;
- inline float length() const;
- inline void set_length(float value);
-
- // optional float width = 5;
- inline bool has_width() const;
- inline void clear_width();
- static const int kWidthFieldNumber = 5;
- inline float width() const;
- inline void set_width(float value);
-
- // optional float height = 6;
- inline bool has_height() const;
- inline void clear_height();
- static const int kHeightFieldNumber = 6;
- inline float height() const;
- inline void set_height(float value);
-
- // @@protoc_insertion_point(class_scope:px.Obstacle)
- private:
- inline void set_has_x();
- inline void clear_has_x();
- inline void set_has_y();
- inline void clear_has_y();
- inline void set_has_z();
- inline void clear_has_z();
- inline void set_has_length();
- inline void clear_has_length();
- inline void set_has_width();
- inline void clear_has_width();
- inline void set_has_height();
- inline void clear_has_height();
-
- ::google::protobuf::UnknownFieldSet _unknown_fields_;
-
- float x_;
- float y_;
- float z_;
- float length_;
- float width_;
- float height_;
-
- mutable int _cached_size_;
- ::google::protobuf::uint32 _has_bits_[(6 + 31) / 32];
-
- friend void protobuf_AddDesc_pixhawk_2eproto();
- friend void protobuf_AssignDesc_pixhawk_2eproto();
- friend void protobuf_ShutdownFile_pixhawk_2eproto();
-
- void InitAsDefaultInstance();
- static Obstacle* default_instance_;
-};
-// -------------------------------------------------------------------
-
-class ObstacleList : public ::google::protobuf::Message {
- public:
- ObstacleList();
- virtual ~ObstacleList();
-
- ObstacleList(const ObstacleList& from);
-
- inline ObstacleList& operator=(const ObstacleList& from) {
- CopyFrom(from);
- return *this;
- }
-
- inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const {
- return _unknown_fields_;
- }
-
- inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() {
- return &_unknown_fields_;
- }
-
- static const ::google::protobuf::Descriptor* descriptor();
- static const ObstacleList& default_instance();
-
- void Swap(ObstacleList* other);
-
- // implements Message ----------------------------------------------
-
- ObstacleList* New() const;
- void CopyFrom(const ::google::protobuf::Message& from);
- void MergeFrom(const ::google::protobuf::Message& from);
- void CopyFrom(const ObstacleList& from);
- void MergeFrom(const ObstacleList& from);
- void Clear();
- bool IsInitialized() const;
-
- int ByteSize() const;
- bool MergePartialFromCodedStream(
- ::google::protobuf::io::CodedInputStream* input);
- void SerializeWithCachedSizes(
- ::google::protobuf::io::CodedOutputStream* output) const;
- ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const;
- int GetCachedSize() const { return _cached_size_; }
- private:
- void SharedCtor();
- void SharedDtor();
- void SetCachedSize(int size) const;
- public:
-
- ::google::protobuf::Metadata GetMetadata() const;
-
- // nested types ----------------------------------------------------
-
- // accessors -------------------------------------------------------
-
- // required .px.HeaderInfo header = 1;
- inline bool has_header() const;
- inline void clear_header();
- static const int kHeaderFieldNumber = 1;
- inline const ::px::HeaderInfo& header() const;
- inline ::px::HeaderInfo* mutable_header();
- inline ::px::HeaderInfo* release_header();
-
- // repeated .px.Obstacle obstacles = 2;
- inline int obstacles_size() const;
- inline void clear_obstacles();
- static const int kObstaclesFieldNumber = 2;
- inline const ::px::Obstacle& obstacles(int index) const;
- inline ::px::Obstacle* mutable_obstacles(int index);
- inline ::px::Obstacle* add_obstacles();
- inline const ::google::protobuf::RepeatedPtrField< ::px::Obstacle >&
- obstacles() const;
- inline ::google::protobuf::RepeatedPtrField< ::px::Obstacle >*
- mutable_obstacles();
-
- // @@protoc_insertion_point(class_scope:px.ObstacleList)
- private:
- inline void set_has_header();
- inline void clear_has_header();
-
- ::google::protobuf::UnknownFieldSet _unknown_fields_;
-
- ::px::HeaderInfo* header_;
- ::google::protobuf::RepeatedPtrField< ::px::Obstacle > obstacles_;
-
- mutable int _cached_size_;
- ::google::protobuf::uint32 _has_bits_[(2 + 31) / 32];
-
- friend void protobuf_AddDesc_pixhawk_2eproto();
- friend void protobuf_AssignDesc_pixhawk_2eproto();
- friend void protobuf_ShutdownFile_pixhawk_2eproto();
-
- void InitAsDefaultInstance();
- static ObstacleList* default_instance_;
-};
-// -------------------------------------------------------------------
-
-class ObstacleMap : public ::google::protobuf::Message {
- public:
- ObstacleMap();
- virtual ~ObstacleMap();
-
- ObstacleMap(const ObstacleMap& from);
-
- inline ObstacleMap& operator=(const ObstacleMap& from) {
- CopyFrom(from);
- return *this;
- }
-
- inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const {
- return _unknown_fields_;
- }
-
- inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() {
- return &_unknown_fields_;
- }
-
- static const ::google::protobuf::Descriptor* descriptor();
- static const ObstacleMap& default_instance();
-
- void Swap(ObstacleMap* other);
-
- // implements Message ----------------------------------------------
-
- ObstacleMap* New() const;
- void CopyFrom(const ::google::protobuf::Message& from);
- void MergeFrom(const ::google::protobuf::Message& from);
- void CopyFrom(const ObstacleMap& from);
- void MergeFrom(const ObstacleMap& from);
- void Clear();
- bool IsInitialized() const;
-
- int ByteSize() const;
- bool MergePartialFromCodedStream(
- ::google::protobuf::io::CodedInputStream* input);
- void SerializeWithCachedSizes(
- ::google::protobuf::io::CodedOutputStream* output) const;
- ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const;
- int GetCachedSize() const { return _cached_size_; }
- private:
- void SharedCtor();
- void SharedDtor();
- void SetCachedSize(int size) const;
- public:
-
- ::google::protobuf::Metadata GetMetadata() const;
-
- // nested types ----------------------------------------------------
-
- // accessors -------------------------------------------------------
-
- // required .px.HeaderInfo header = 1;
- inline bool has_header() const;
- inline void clear_header();
- static const int kHeaderFieldNumber = 1;
- inline const ::px::HeaderInfo& header() const;
- inline ::px::HeaderInfo* mutable_header();
- inline ::px::HeaderInfo* release_header();
-
- // required int32 type = 2;
- inline bool has_type() const;
- inline void clear_type();
- static const int kTypeFieldNumber = 2;
- inline ::google::protobuf::int32 type() const;
- inline void set_type(::google::protobuf::int32 value);
-
- // optional float resolution = 3;
- inline bool has_resolution() const;
- inline void clear_resolution();
- static const int kResolutionFieldNumber = 3;
- inline float resolution() const;
- inline void set_resolution(float value);
-
- // optional int32 rows = 4;
- inline bool has_rows() const;
- inline void clear_rows();
- static const int kRowsFieldNumber = 4;
- inline ::google::protobuf::int32 rows() const;
- inline void set_rows(::google::protobuf::int32 value);
-
- // optional int32 cols = 5;
- inline bool has_cols() const;
- inline void clear_cols();
- static const int kColsFieldNumber = 5;
- inline ::google::protobuf::int32 cols() const;
- inline void set_cols(::google::protobuf::int32 value);
-
- // optional int32 mapR0 = 6;
- inline bool has_mapr0() const;
- inline void clear_mapr0();
- static const int kMapR0FieldNumber = 6;
- inline ::google::protobuf::int32 mapr0() const;
- inline void set_mapr0(::google::protobuf::int32 value);
-
- // optional int32 mapC0 = 7;
- inline bool has_mapc0() const;
- inline void clear_mapc0();
- static const int kMapC0FieldNumber = 7;
- inline ::google::protobuf::int32 mapc0() const;
- inline void set_mapc0(::google::protobuf::int32 value);
-
- // optional int32 arrayR0 = 8;
- inline bool has_arrayr0() const;
- inline void clear_arrayr0();
- static const int kArrayR0FieldNumber = 8;
- inline ::google::protobuf::int32 arrayr0() const;
- inline void set_arrayr0(::google::protobuf::int32 value);
-
- // optional int32 arrayC0 = 9;
- inline bool has_arrayc0() const;
- inline void clear_arrayc0();
- static const int kArrayC0FieldNumber = 9;
- inline ::google::protobuf::int32 arrayc0() const;
- inline void set_arrayc0(::google::protobuf::int32 value);
-
- // optional bytes data = 10;
- inline bool has_data() const;
- inline void clear_data();
- static const int kDataFieldNumber = 10;
- inline const ::std::string& data() const;
- inline void set_data(const ::std::string& value);
- inline void set_data(const char* value);
- inline void set_data(const void* value, size_t size);
- inline ::std::string* mutable_data();
- inline ::std::string* release_data();
-
- // @@protoc_insertion_point(class_scope:px.ObstacleMap)
- private:
- inline void set_has_header();
- inline void clear_has_header();
- inline void set_has_type();
- inline void clear_has_type();
- inline void set_has_resolution();
- inline void clear_has_resolution();
- inline void set_has_rows();
- inline void clear_has_rows();
- inline void set_has_cols();
- inline void clear_has_cols();
- inline void set_has_mapr0();
- inline void clear_has_mapr0();
- inline void set_has_mapc0();
- inline void clear_has_mapc0();
- inline void set_has_arrayr0();
- inline void clear_has_arrayr0();
- inline void set_has_arrayc0();
- inline void clear_has_arrayc0();
- inline void set_has_data();
- inline void clear_has_data();
-
- ::google::protobuf::UnknownFieldSet _unknown_fields_;
-
- ::px::HeaderInfo* header_;
- ::google::protobuf::int32 type_;
- float resolution_;
- ::google::protobuf::int32 rows_;
- ::google::protobuf::int32 cols_;
- ::google::protobuf::int32 mapr0_;
- ::google::protobuf::int32 mapc0_;
- ::google::protobuf::int32 arrayr0_;
- ::google::protobuf::int32 arrayc0_;
- ::std::string* data_;
-
- mutable int _cached_size_;
- ::google::protobuf::uint32 _has_bits_[(10 + 31) / 32];
-
- friend void protobuf_AddDesc_pixhawk_2eproto();
- friend void protobuf_AssignDesc_pixhawk_2eproto();
- friend void protobuf_ShutdownFile_pixhawk_2eproto();
-
- void InitAsDefaultInstance();
- static ObstacleMap* default_instance_;
-};
-// -------------------------------------------------------------------
-
-class Path : public ::google::protobuf::Message {
- public:
- Path();
- virtual ~Path();
-
- Path(const Path& from);
-
- inline Path& operator=(const Path& from) {
- CopyFrom(from);
- return *this;
- }
-
- inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const {
- return _unknown_fields_;
- }
-
- inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() {
- return &_unknown_fields_;
- }
-
- static const ::google::protobuf::Descriptor* descriptor();
- static const Path& default_instance();
-
- void Swap(Path* other);
-
- // implements Message ----------------------------------------------
-
- Path* New() const;
- void CopyFrom(const ::google::protobuf::Message& from);
- void MergeFrom(const ::google::protobuf::Message& from);
- void CopyFrom(const Path& from);
- void MergeFrom(const Path& from);
- void Clear();
- bool IsInitialized() const;
-
- int ByteSize() const;
- bool MergePartialFromCodedStream(
- ::google::protobuf::io::CodedInputStream* input);
- void SerializeWithCachedSizes(
- ::google::protobuf::io::CodedOutputStream* output) const;
- ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const;
- int GetCachedSize() const { return _cached_size_; }
- private:
- void SharedCtor();
- void SharedDtor();
- void SetCachedSize(int size) const;
- public:
-
- ::google::protobuf::Metadata GetMetadata() const;
-
- // nested types ----------------------------------------------------
-
- // accessors -------------------------------------------------------
-
- // required .px.HeaderInfo header = 1;
- inline bool has_header() const;
- inline void clear_header();
- static const int kHeaderFieldNumber = 1;
- inline const ::px::HeaderInfo& header() const;
- inline ::px::HeaderInfo* mutable_header();
- inline ::px::HeaderInfo* release_header();
-
- // repeated .px.Waypoint waypoints = 2;
- inline int waypoints_size() const;
- inline void clear_waypoints();
- static const int kWaypointsFieldNumber = 2;
- inline const ::px::Waypoint& waypoints(int index) const;
- inline ::px::Waypoint* mutable_waypoints(int index);
- inline ::px::Waypoint* add_waypoints();
- inline const ::google::protobuf::RepeatedPtrField< ::px::Waypoint >&
- waypoints() const;
- inline ::google::protobuf::RepeatedPtrField< ::px::Waypoint >*
- mutable_waypoints();
-
- // @@protoc_insertion_point(class_scope:px.Path)
- private:
- inline void set_has_header();
- inline void clear_has_header();
-
- ::google::protobuf::UnknownFieldSet _unknown_fields_;
-
- ::px::HeaderInfo* header_;
- ::google::protobuf::RepeatedPtrField< ::px::Waypoint > waypoints_;
-
- mutable int _cached_size_;
- ::google::protobuf::uint32 _has_bits_[(2 + 31) / 32];
-
- friend void protobuf_AddDesc_pixhawk_2eproto();
- friend void protobuf_AssignDesc_pixhawk_2eproto();
- friend void protobuf_ShutdownFile_pixhawk_2eproto();
-
- void InitAsDefaultInstance();
- static Path* default_instance_;
-};
-// -------------------------------------------------------------------
-
-class PointCloudXYZI_PointXYZI : public ::google::protobuf::Message {
- public:
- PointCloudXYZI_PointXYZI();
- virtual ~PointCloudXYZI_PointXYZI();
-
- PointCloudXYZI_PointXYZI(const PointCloudXYZI_PointXYZI& from);
-
- inline PointCloudXYZI_PointXYZI& operator=(const PointCloudXYZI_PointXYZI& from) {
- CopyFrom(from);
- return *this;
- }
-
- inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const {
- return _unknown_fields_;
- }
-
- inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() {
- return &_unknown_fields_;
- }
-
- static const ::google::protobuf::Descriptor* descriptor();
- static const PointCloudXYZI_PointXYZI& default_instance();
-
- void Swap(PointCloudXYZI_PointXYZI* other);
-
- // implements Message ----------------------------------------------
-
- PointCloudXYZI_PointXYZI* New() const;
- void CopyFrom(const ::google::protobuf::Message& from);
- void MergeFrom(const ::google::protobuf::Message& from);
- void CopyFrom(const PointCloudXYZI_PointXYZI& from);
- void MergeFrom(const PointCloudXYZI_PointXYZI& from);
- void Clear();
- bool IsInitialized() const;
-
- int ByteSize() const;
- bool MergePartialFromCodedStream(
- ::google::protobuf::io::CodedInputStream* input);
- void SerializeWithCachedSizes(
- ::google::protobuf::io::CodedOutputStream* output) const;
- ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const;
- int GetCachedSize() const { return _cached_size_; }
- private:
- void SharedCtor();
- void SharedDtor();
- void SetCachedSize(int size) const;
- public:
-
- ::google::protobuf::Metadata GetMetadata() const;
-
- // nested types ----------------------------------------------------
-
- // accessors -------------------------------------------------------
-
- // required float x = 1;
- inline bool has_x() const;
- inline void clear_x();
- static const int kXFieldNumber = 1;
- inline float x() const;
- inline void set_x(float value);
-
- // required float y = 2;
- inline bool has_y() const;
- inline void clear_y();
- static const int kYFieldNumber = 2;
- inline float y() const;
- inline void set_y(float value);
-
- // required float z = 3;
- inline bool has_z() const;
- inline void clear_z();
- static const int kZFieldNumber = 3;
- inline float z() const;
- inline void set_z(float value);
-
- // required float intensity = 4;
- inline bool has_intensity() const;
- inline void clear_intensity();
- static const int kIntensityFieldNumber = 4;
- inline float intensity() const;
- inline void set_intensity(float value);
-
- // @@protoc_insertion_point(class_scope:px.PointCloudXYZI.PointXYZI)
- private:
- inline void set_has_x();
- inline void clear_has_x();
- inline void set_has_y();
- inline void clear_has_y();
- inline void set_has_z();
- inline void clear_has_z();
- inline void set_has_intensity();
- inline void clear_has_intensity();
-
- ::google::protobuf::UnknownFieldSet _unknown_fields_;
-
- float x_;
- float y_;
- float z_;
- float intensity_;
-
- mutable int _cached_size_;
- ::google::protobuf::uint32 _has_bits_[(4 + 31) / 32];
-
- friend void protobuf_AddDesc_pixhawk_2eproto();
- friend void protobuf_AssignDesc_pixhawk_2eproto();
- friend void protobuf_ShutdownFile_pixhawk_2eproto();
-
- void InitAsDefaultInstance();
- static PointCloudXYZI_PointXYZI* default_instance_;
-};
-// -------------------------------------------------------------------
-
-class PointCloudXYZI : public ::google::protobuf::Message {
- public:
- PointCloudXYZI();
- virtual ~PointCloudXYZI();
-
- PointCloudXYZI(const PointCloudXYZI& from);
-
- inline PointCloudXYZI& operator=(const PointCloudXYZI& from) {
- CopyFrom(from);
- return *this;
- }
-
- inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const {
- return _unknown_fields_;
- }
-
- inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() {
- return &_unknown_fields_;
- }
-
- static const ::google::protobuf::Descriptor* descriptor();
- static const PointCloudXYZI& default_instance();
-
- void Swap(PointCloudXYZI* other);
-
- // implements Message ----------------------------------------------
-
- PointCloudXYZI* New() const;
- void CopyFrom(const ::google::protobuf::Message& from);
- void MergeFrom(const ::google::protobuf::Message& from);
- void CopyFrom(const PointCloudXYZI& from);
- void MergeFrom(const PointCloudXYZI& from);
- void Clear();
- bool IsInitialized() const;
-
- int ByteSize() const;
- bool MergePartialFromCodedStream(
- ::google::protobuf::io::CodedInputStream* input);
- void SerializeWithCachedSizes(
- ::google::protobuf::io::CodedOutputStream* output) const;
- ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const;
- int GetCachedSize() const { return _cached_size_; }
- private:
- void SharedCtor();
- void SharedDtor();
- void SetCachedSize(int size) const;
- public:
-
- ::google::protobuf::Metadata GetMetadata() const;
-
- // nested types ----------------------------------------------------
-
- typedef PointCloudXYZI_PointXYZI PointXYZI;
-
- // accessors -------------------------------------------------------
-
- // required .px.HeaderInfo header = 1;
- inline bool has_header() const;
- inline void clear_header();
- static const int kHeaderFieldNumber = 1;
- inline const ::px::HeaderInfo& header() const;
- inline ::px::HeaderInfo* mutable_header();
- inline ::px::HeaderInfo* release_header();
-
- // repeated .px.PointCloudXYZI.PointXYZI points = 2;
- inline int points_size() const;
- inline void clear_points();
- static const int kPointsFieldNumber = 2;
- inline const ::px::PointCloudXYZI_PointXYZI& points(int index) const;
- inline ::px::PointCloudXYZI_PointXYZI* mutable_points(int index);
- inline ::px::PointCloudXYZI_PointXYZI* add_points();
- inline const ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZI_PointXYZI >&
- points() const;
- inline ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZI_PointXYZI >*
- mutable_points();
-
- // @@protoc_insertion_point(class_scope:px.PointCloudXYZI)
- private:
- inline void set_has_header();
- inline void clear_has_header();
-
- ::google::protobuf::UnknownFieldSet _unknown_fields_;
-
- ::px::HeaderInfo* header_;
- ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZI_PointXYZI > points_;
-
- mutable int _cached_size_;
- ::google::protobuf::uint32 _has_bits_[(2 + 31) / 32];
-
- friend void protobuf_AddDesc_pixhawk_2eproto();
- friend void protobuf_AssignDesc_pixhawk_2eproto();
- friend void protobuf_ShutdownFile_pixhawk_2eproto();
-
- void InitAsDefaultInstance();
- static PointCloudXYZI* default_instance_;
-};
-// -------------------------------------------------------------------
-
-class PointCloudXYZRGB_PointXYZRGB : public ::google::protobuf::Message {
- public:
- PointCloudXYZRGB_PointXYZRGB();
- virtual ~PointCloudXYZRGB_PointXYZRGB();
-
- PointCloudXYZRGB_PointXYZRGB(const PointCloudXYZRGB_PointXYZRGB& from);
-
- inline PointCloudXYZRGB_PointXYZRGB& operator=(const PointCloudXYZRGB_PointXYZRGB& from) {
- CopyFrom(from);
- return *this;
- }
-
- inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const {
- return _unknown_fields_;
- }
-
- inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() {
- return &_unknown_fields_;
- }
-
- static const ::google::protobuf::Descriptor* descriptor();
- static const PointCloudXYZRGB_PointXYZRGB& default_instance();
-
- void Swap(PointCloudXYZRGB_PointXYZRGB* other);
-
- // implements Message ----------------------------------------------
-
- PointCloudXYZRGB_PointXYZRGB* New() const;
- void CopyFrom(const ::google::protobuf::Message& from);
- void MergeFrom(const ::google::protobuf::Message& from);
- void CopyFrom(const PointCloudXYZRGB_PointXYZRGB& from);
- void MergeFrom(const PointCloudXYZRGB_PointXYZRGB& from);
- void Clear();
- bool IsInitialized() const;
-
- int ByteSize() const;
- bool MergePartialFromCodedStream(
- ::google::protobuf::io::CodedInputStream* input);
- void SerializeWithCachedSizes(
- ::google::protobuf::io::CodedOutputStream* output) const;
- ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const;
- int GetCachedSize() const { return _cached_size_; }
- private:
- void SharedCtor();
- void SharedDtor();
- void SetCachedSize(int size) const;
- public:
-
- ::google::protobuf::Metadata GetMetadata() const;
-
- // nested types ----------------------------------------------------
-
- // accessors -------------------------------------------------------
-
- // required float x = 1;
- inline bool has_x() const;
- inline void clear_x();
- static const int kXFieldNumber = 1;
- inline float x() const;
- inline void set_x(float value);
-
- // required float y = 2;
- inline bool has_y() const;
- inline void clear_y();
- static const int kYFieldNumber = 2;
- inline float y() const;
- inline void set_y(float value);
-
- // required float z = 3;
- inline bool has_z() const;
- inline void clear_z();
- static const int kZFieldNumber = 3;
- inline float z() const;
- inline void set_z(float value);
-
- // required float rgb = 4;
- inline bool has_rgb() const;
- inline void clear_rgb();
- static const int kRgbFieldNumber = 4;
- inline float rgb() const;
- inline void set_rgb(float value);
-
- // @@protoc_insertion_point(class_scope:px.PointCloudXYZRGB.PointXYZRGB)
- private:
- inline void set_has_x();
- inline void clear_has_x();
- inline void set_has_y();
- inline void clear_has_y();
- inline void set_has_z();
- inline void clear_has_z();
- inline void set_has_rgb();
- inline void clear_has_rgb();
-
- ::google::protobuf::UnknownFieldSet _unknown_fields_;
-
- float x_;
- float y_;
- float z_;
- float rgb_;
-
- mutable int _cached_size_;
- ::google::protobuf::uint32 _has_bits_[(4 + 31) / 32];
-
- friend void protobuf_AddDesc_pixhawk_2eproto();
- friend void protobuf_AssignDesc_pixhawk_2eproto();
- friend void protobuf_ShutdownFile_pixhawk_2eproto();
-
- void InitAsDefaultInstance();
- static PointCloudXYZRGB_PointXYZRGB* default_instance_;
-};
-// -------------------------------------------------------------------
-
-class PointCloudXYZRGB : public ::google::protobuf::Message {
- public:
- PointCloudXYZRGB();
- virtual ~PointCloudXYZRGB();
-
- PointCloudXYZRGB(const PointCloudXYZRGB& from);
-
- inline PointCloudXYZRGB& operator=(const PointCloudXYZRGB& from) {
- CopyFrom(from);
- return *this;
- }
-
- inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const {
- return _unknown_fields_;
- }
-
- inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() {
- return &_unknown_fields_;
- }
-
- static const ::google::protobuf::Descriptor* descriptor();
- static const PointCloudXYZRGB& default_instance();
-
- void Swap(PointCloudXYZRGB* other);
-
- // implements Message ----------------------------------------------
-
- PointCloudXYZRGB* New() const;
- void CopyFrom(const ::google::protobuf::Message& from);
- void MergeFrom(const ::google::protobuf::Message& from);
- void CopyFrom(const PointCloudXYZRGB& from);
- void MergeFrom(const PointCloudXYZRGB& from);
- void Clear();
- bool IsInitialized() const;
-
- int ByteSize() const;
- bool MergePartialFromCodedStream(
- ::google::protobuf::io::CodedInputStream* input);
- void SerializeWithCachedSizes(
- ::google::protobuf::io::CodedOutputStream* output) const;
- ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const;
- int GetCachedSize() const { return _cached_size_; }
- private:
- void SharedCtor();
- void SharedDtor();
- void SetCachedSize(int size) const;
- public:
-
- ::google::protobuf::Metadata GetMetadata() const;
-
- // nested types ----------------------------------------------------
-
- typedef PointCloudXYZRGB_PointXYZRGB PointXYZRGB;
-
- // accessors -------------------------------------------------------
-
- // required .px.HeaderInfo header = 1;
- inline bool has_header() const;
- inline void clear_header();
- static const int kHeaderFieldNumber = 1;
- inline const ::px::HeaderInfo& header() const;
- inline ::px::HeaderInfo* mutable_header();
- inline ::px::HeaderInfo* release_header();
-
- // repeated .px.PointCloudXYZRGB.PointXYZRGB points = 2;
- inline int points_size() const;
- inline void clear_points();
- static const int kPointsFieldNumber = 2;
- inline const ::px::PointCloudXYZRGB_PointXYZRGB& points(int index) const;
- inline ::px::PointCloudXYZRGB_PointXYZRGB* mutable_points(int index);
- inline ::px::PointCloudXYZRGB_PointXYZRGB* add_points();
- inline const ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZRGB_PointXYZRGB >&
- points() const;
- inline ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZRGB_PointXYZRGB >*
- mutable_points();
-
- // @@protoc_insertion_point(class_scope:px.PointCloudXYZRGB)
- private:
- inline void set_has_header();
- inline void clear_has_header();
-
- ::google::protobuf::UnknownFieldSet _unknown_fields_;
-
- ::px::HeaderInfo* header_;
- ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZRGB_PointXYZRGB > points_;
-
- mutable int _cached_size_;
- ::google::protobuf::uint32 _has_bits_[(2 + 31) / 32];
-
- friend void protobuf_AddDesc_pixhawk_2eproto();
- friend void protobuf_AssignDesc_pixhawk_2eproto();
- friend void protobuf_ShutdownFile_pixhawk_2eproto();
-
- void InitAsDefaultInstance();
- static PointCloudXYZRGB* default_instance_;
-};
-// -------------------------------------------------------------------
-
-class RGBDImage : public ::google::protobuf::Message {
- public:
- RGBDImage();
- virtual ~RGBDImage();
-
- RGBDImage(const RGBDImage& from);
-
- inline RGBDImage& operator=(const RGBDImage& from) {
- CopyFrom(from);
- return *this;
- }
-
- inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const {
- return _unknown_fields_;
- }
-
- inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() {
- return &_unknown_fields_;
- }
-
- static const ::google::protobuf::Descriptor* descriptor();
- static const RGBDImage& default_instance();
-
- void Swap(RGBDImage* other);
-
- // implements Message ----------------------------------------------
-
- RGBDImage* New() const;
- void CopyFrom(const ::google::protobuf::Message& from);
- void MergeFrom(const ::google::protobuf::Message& from);
- void CopyFrom(const RGBDImage& from);
- void MergeFrom(const RGBDImage& from);
- void Clear();
- bool IsInitialized() const;
-
- int ByteSize() const;
- bool MergePartialFromCodedStream(
- ::google::protobuf::io::CodedInputStream* input);
- void SerializeWithCachedSizes(
- ::google::protobuf::io::CodedOutputStream* output) const;
- ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const;
- int GetCachedSize() const { return _cached_size_; }
- private:
- void SharedCtor();
- void SharedDtor();
- void SetCachedSize(int size) const;
- public:
-
- ::google::protobuf::Metadata GetMetadata() const;
-
- // nested types ----------------------------------------------------
-
- // accessors -------------------------------------------------------
-
- // required .px.HeaderInfo header = 1;
- inline bool has_header() const;
- inline void clear_header();
- static const int kHeaderFieldNumber = 1;
- inline const ::px::HeaderInfo& header() const;
- inline ::px::HeaderInfo* mutable_header();
- inline ::px::HeaderInfo* release_header();
-
- // required uint32 cols = 2;
- inline bool has_cols() const;
- inline void clear_cols();
- static const int kColsFieldNumber = 2;
- inline ::google::protobuf::uint32 cols() const;
- inline void set_cols(::google::protobuf::uint32 value);
-
- // required uint32 rows = 3;
- inline bool has_rows() const;
- inline void clear_rows();
- static const int kRowsFieldNumber = 3;
- inline ::google::protobuf::uint32 rows() const;
- inline void set_rows(::google::protobuf::uint32 value);
-
- // required uint32 step1 = 4;
- inline bool has_step1() const;
- inline void clear_step1();
- static const int kStep1FieldNumber = 4;
- inline ::google::protobuf::uint32 step1() const;
- inline void set_step1(::google::protobuf::uint32 value);
-
- // required uint32 type1 = 5;
- inline bool has_type1() const;
- inline void clear_type1();
- static const int kType1FieldNumber = 5;
- inline ::google::protobuf::uint32 type1() const;
- inline void set_type1(::google::protobuf::uint32 value);
-
- // required bytes imageData1 = 6;
- inline bool has_imagedata1() const;
- inline void clear_imagedata1();
- static const int kImageData1FieldNumber = 6;
- inline const ::std::string& imagedata1() const;
- inline void set_imagedata1(const ::std::string& value);
- inline void set_imagedata1(const char* value);
- inline void set_imagedata1(const void* value, size_t size);
- inline ::std::string* mutable_imagedata1();
- inline ::std::string* release_imagedata1();
-
- // required uint32 step2 = 7;
- inline bool has_step2() const;
- inline void clear_step2();
- static const int kStep2FieldNumber = 7;
- inline ::google::protobuf::uint32 step2() const;
- inline void set_step2(::google::protobuf::uint32 value);
-
- // required uint32 type2 = 8;
- inline bool has_type2() const;
- inline void clear_type2();
- static const int kType2FieldNumber = 8;
- inline ::google::protobuf::uint32 type2() const;
- inline void set_type2(::google::protobuf::uint32 value);
-
- // required bytes imageData2 = 9;
- inline bool has_imagedata2() const;
- inline void clear_imagedata2();
- static const int kImageData2FieldNumber = 9;
- inline const ::std::string& imagedata2() const;
- inline void set_imagedata2(const ::std::string& value);
- inline void set_imagedata2(const char* value);
- inline void set_imagedata2(const void* value, size_t size);
- inline ::std::string* mutable_imagedata2();
- inline ::std::string* release_imagedata2();
-
- // optional uint32 camera_config = 10;
- inline bool has_camera_config() const;
- inline void clear_camera_config();
- static const int kCameraConfigFieldNumber = 10;
- inline ::google::protobuf::uint32 camera_config() const;
- inline void set_camera_config(::google::protobuf::uint32 value);
-
- // optional uint32 camera_type = 11;
- inline bool has_camera_type() const;
- inline void clear_camera_type();
- static const int kCameraTypeFieldNumber = 11;
- inline ::google::protobuf::uint32 camera_type() const;
- inline void set_camera_type(::google::protobuf::uint32 value);
-
- // optional float roll = 12;
- inline bool has_roll() const;
- inline void clear_roll();
- static const int kRollFieldNumber = 12;
- inline float roll() const;
- inline void set_roll(float value);
-
- // optional float pitch = 13;
- inline bool has_pitch() const;
- inline void clear_pitch();
- static const int kPitchFieldNumber = 13;
- inline float pitch() const;
- inline void set_pitch(float value);
-
- // optional float yaw = 14;
- inline bool has_yaw() const;
- inline void clear_yaw();
- static const int kYawFieldNumber = 14;
- inline float yaw() const;
- inline void set_yaw(float value);
-
- // optional float lon = 15;
- inline bool has_lon() const;
- inline void clear_lon();
- static const int kLonFieldNumber = 15;
- inline float lon() const;
- inline void set_lon(float value);
-
- // optional float lat = 16;
- inline bool has_lat() const;
- inline void clear_lat();
- static const int kLatFieldNumber = 16;
- inline float lat() const;
- inline void set_lat(float value);
-
- // optional float alt = 17;
- inline bool has_alt() const;
- inline void clear_alt();
- static const int kAltFieldNumber = 17;
- inline float alt() const;
- inline void set_alt(float value);
-
- // optional float ground_x = 18;
- inline bool has_ground_x() const;
- inline void clear_ground_x();
- static const int kGroundXFieldNumber = 18;
- inline float ground_x() const;
- inline void set_ground_x(float value);
-
- // optional float ground_y = 19;
- inline bool has_ground_y() const;
- inline void clear_ground_y();
- static const int kGroundYFieldNumber = 19;
- inline float ground_y() const;
- inline void set_ground_y(float value);
-
- // optional float ground_z = 20;
- inline bool has_ground_z() const;
- inline void clear_ground_z();
- static const int kGroundZFieldNumber = 20;
- inline float ground_z() const;
- inline void set_ground_z(float value);
-
- // repeated float camera_matrix = 21;
- inline int camera_matrix_size() const;
- inline void clear_camera_matrix();
- static const int kCameraMatrixFieldNumber = 21;
- inline float camera_matrix(int index) const;
- inline void set_camera_matrix(int index, float value);
- inline void add_camera_matrix(float value);
- inline const ::google::protobuf::RepeatedField< float >&
- camera_matrix() const;
- inline ::google::protobuf::RepeatedField< float >*
- mutable_camera_matrix();
-
- // @@protoc_insertion_point(class_scope:px.RGBDImage)
- private:
- inline void set_has_header();
- inline void clear_has_header();
- inline void set_has_cols();
- inline void clear_has_cols();
- inline void set_has_rows();
- inline void clear_has_rows();
- inline void set_has_step1();
- inline void clear_has_step1();
- inline void set_has_type1();
- inline void clear_has_type1();
- inline void set_has_imagedata1();
- inline void clear_has_imagedata1();
- inline void set_has_step2();
- inline void clear_has_step2();
- inline void set_has_type2();
- inline void clear_has_type2();
- inline void set_has_imagedata2();
- inline void clear_has_imagedata2();
- inline void set_has_camera_config();
- inline void clear_has_camera_config();
- inline void set_has_camera_type();
- inline void clear_has_camera_type();
- inline void set_has_roll();
- inline void clear_has_roll();
- inline void set_has_pitch();
- inline void clear_has_pitch();
- inline void set_has_yaw();
- inline void clear_has_yaw();
- inline void set_has_lon();
- inline void clear_has_lon();
- inline void set_has_lat();
- inline void clear_has_lat();
- inline void set_has_alt();
- inline void clear_has_alt();
- inline void set_has_ground_x();
- inline void clear_has_ground_x();
- inline void set_has_ground_y();
- inline void clear_has_ground_y();
- inline void set_has_ground_z();
- inline void clear_has_ground_z();
-
- ::google::protobuf::UnknownFieldSet _unknown_fields_;
-
- ::px::HeaderInfo* header_;
- ::google::protobuf::uint32 cols_;
- ::google::protobuf::uint32 rows_;
- ::google::protobuf::uint32 step1_;
- ::google::protobuf::uint32 type1_;
- ::std::string* imagedata1_;
- ::google::protobuf::uint32 step2_;
- ::google::protobuf::uint32 type2_;
- ::std::string* imagedata2_;
- ::google::protobuf::uint32 camera_config_;
- ::google::protobuf::uint32 camera_type_;
- float roll_;
- float pitch_;
- float yaw_;
- float lon_;
- float lat_;
- float alt_;
- float ground_x_;
- float ground_y_;
- ::google::protobuf::RepeatedField< float > camera_matrix_;
- float ground_z_;
-
- mutable int _cached_size_;
- ::google::protobuf::uint32 _has_bits_[(21 + 31) / 32];
-
- friend void protobuf_AddDesc_pixhawk_2eproto();
- friend void protobuf_AssignDesc_pixhawk_2eproto();
- friend void protobuf_ShutdownFile_pixhawk_2eproto();
-
- void InitAsDefaultInstance();
- static RGBDImage* default_instance_;
-};
-// -------------------------------------------------------------------
-
-class Waypoint : public ::google::protobuf::Message {
- public:
- Waypoint();
- virtual ~Waypoint();
-
- Waypoint(const Waypoint& from);
-
- inline Waypoint& operator=(const Waypoint& from) {
- CopyFrom(from);
- return *this;
- }
-
- inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const {
- return _unknown_fields_;
- }
-
- inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() {
- return &_unknown_fields_;
- }
-
- static const ::google::protobuf::Descriptor* descriptor();
- static const Waypoint& default_instance();
-
- void Swap(Waypoint* other);
-
- // implements Message ----------------------------------------------
-
- Waypoint* New() const;
- void CopyFrom(const ::google::protobuf::Message& from);
- void MergeFrom(const ::google::protobuf::Message& from);
- void CopyFrom(const Waypoint& from);
- void MergeFrom(const Waypoint& from);
- void Clear();
- bool IsInitialized() const;
-
- int ByteSize() const;
- bool MergePartialFromCodedStream(
- ::google::protobuf::io::CodedInputStream* input);
- void SerializeWithCachedSizes(
- ::google::protobuf::io::CodedOutputStream* output) const;
- ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const;
- int GetCachedSize() const { return _cached_size_; }
- private:
- void SharedCtor();
- void SharedDtor();
- void SetCachedSize(int size) const;
- public:
-
- ::google::protobuf::Metadata GetMetadata() const;
-
- // nested types ----------------------------------------------------
-
- // accessors -------------------------------------------------------
-
- // required double x = 1;
- inline bool has_x() const;
- inline void clear_x();
- static const int kXFieldNumber = 1;
- inline double x() const;
- inline void set_x(double value);
-
- // required double y = 2;
- inline bool has_y() const;
- inline void clear_y();
- static const int kYFieldNumber = 2;
- inline double y() const;
- inline void set_y(double value);
-
- // optional double z = 3;
- inline bool has_z() const;
- inline void clear_z();
- static const int kZFieldNumber = 3;
- inline double z() const;
- inline void set_z(double value);
-
- // optional double roll = 4;
- inline bool has_roll() const;
- inline void clear_roll();
- static const int kRollFieldNumber = 4;
- inline double roll() const;
- inline void set_roll(double value);
-
- // optional double pitch = 5;
- inline bool has_pitch() const;
- inline void clear_pitch();
- static const int kPitchFieldNumber = 5;
- inline double pitch() const;
- inline void set_pitch(double value);
-
- // optional double yaw = 6;
- inline bool has_yaw() const;
- inline void clear_yaw();
- static const int kYawFieldNumber = 6;
- inline double yaw() const;
- inline void set_yaw(double value);
-
- // @@protoc_insertion_point(class_scope:px.Waypoint)
- private:
- inline void set_has_x();
- inline void clear_has_x();
- inline void set_has_y();
- inline void clear_has_y();
- inline void set_has_z();
- inline void clear_has_z();
- inline void set_has_roll();
- inline void clear_has_roll();
- inline void set_has_pitch();
- inline void clear_has_pitch();
- inline void set_has_yaw();
- inline void clear_has_yaw();
-
- ::google::protobuf::UnknownFieldSet _unknown_fields_;
-
- double x_;
- double y_;
- double z_;
- double roll_;
- double pitch_;
- double yaw_;
-
- mutable int _cached_size_;
- ::google::protobuf::uint32 _has_bits_[(6 + 31) / 32];
-
- friend void protobuf_AddDesc_pixhawk_2eproto();
- friend void protobuf_AssignDesc_pixhawk_2eproto();
- friend void protobuf_ShutdownFile_pixhawk_2eproto();
-
- void InitAsDefaultInstance();
- static Waypoint* default_instance_;
-};
-// ===================================================================
-
-
-// ===================================================================
-
-// HeaderInfo
-
-// required int32 source_sysid = 1;
-inline bool HeaderInfo::has_source_sysid() const {
- return (_has_bits_[0] & 0x00000001u) != 0;
-}
-inline void HeaderInfo::set_has_source_sysid() {
- _has_bits_[0] |= 0x00000001u;
-}
-inline void HeaderInfo::clear_has_source_sysid() {
- _has_bits_[0] &= ~0x00000001u;
-}
-inline void HeaderInfo::clear_source_sysid() {
- source_sysid_ = 0;
- clear_has_source_sysid();
-}
-inline ::google::protobuf::int32 HeaderInfo::source_sysid() const {
- return source_sysid_;
-}
-inline void HeaderInfo::set_source_sysid(::google::protobuf::int32 value) {
- set_has_source_sysid();
- source_sysid_ = value;
-}
-
-// required int32 source_compid = 2;
-inline bool HeaderInfo::has_source_compid() const {
- return (_has_bits_[0] & 0x00000002u) != 0;
-}
-inline void HeaderInfo::set_has_source_compid() {
- _has_bits_[0] |= 0x00000002u;
-}
-inline void HeaderInfo::clear_has_source_compid() {
- _has_bits_[0] &= ~0x00000002u;
-}
-inline void HeaderInfo::clear_source_compid() {
- source_compid_ = 0;
- clear_has_source_compid();
-}
-inline ::google::protobuf::int32 HeaderInfo::source_compid() const {
- return source_compid_;
-}
-inline void HeaderInfo::set_source_compid(::google::protobuf::int32 value) {
- set_has_source_compid();
- source_compid_ = value;
-}
-
-// required double timestamp = 3;
-inline bool HeaderInfo::has_timestamp() const {
- return (_has_bits_[0] & 0x00000004u) != 0;
-}
-inline void HeaderInfo::set_has_timestamp() {
- _has_bits_[0] |= 0x00000004u;
-}
-inline void HeaderInfo::clear_has_timestamp() {
- _has_bits_[0] &= ~0x00000004u;
-}
-inline void HeaderInfo::clear_timestamp() {
- timestamp_ = 0;
- clear_has_timestamp();
-}
-inline double HeaderInfo::timestamp() const {
- return timestamp_;
-}
-inline void HeaderInfo::set_timestamp(double value) {
- set_has_timestamp();
- timestamp_ = value;
-}
-
-// -------------------------------------------------------------------
-
-// GLOverlay
-
-// required .px.HeaderInfo header = 1;
-inline bool GLOverlay::has_header() const {
- return (_has_bits_[0] & 0x00000001u) != 0;
-}
-inline void GLOverlay::set_has_header() {
- _has_bits_[0] |= 0x00000001u;
-}
-inline void GLOverlay::clear_has_header() {
- _has_bits_[0] &= ~0x00000001u;
-}
-inline void GLOverlay::clear_header() {
- if (header_ != NULL) header_->::px::HeaderInfo::Clear();
- clear_has_header();
-}
-inline const ::px::HeaderInfo& GLOverlay::header() const {
- return header_ != NULL ? *header_ : *default_instance_->header_;
-}
-inline ::px::HeaderInfo* GLOverlay::mutable_header() {
- set_has_header();
- if (header_ == NULL) header_ = new ::px::HeaderInfo;
- return header_;
-}
-inline ::px::HeaderInfo* GLOverlay::release_header() {
- clear_has_header();
- ::px::HeaderInfo* temp = header_;
- header_ = NULL;
- return temp;
-}
-
-// optional string name = 2;
-inline bool GLOverlay::has_name() const {
- return (_has_bits_[0] & 0x00000002u) != 0;
-}
-inline void GLOverlay::set_has_name() {
- _has_bits_[0] |= 0x00000002u;
-}
-inline void GLOverlay::clear_has_name() {
- _has_bits_[0] &= ~0x00000002u;
-}
-inline void GLOverlay::clear_name() {
- if (name_ != &::google::protobuf::internal::kEmptyString) {
- name_->clear();
- }
- clear_has_name();
-}
-inline const ::std::string& GLOverlay::name() const {
- return *name_;
-}
-inline void GLOverlay::set_name(const ::std::string& value) {
- set_has_name();
- if (name_ == &::google::protobuf::internal::kEmptyString) {
- name_ = new ::std::string;
- }
- name_->assign(value);
-}
-inline void GLOverlay::set_name(const char* value) {
- set_has_name();
- if (name_ == &::google::protobuf::internal::kEmptyString) {
- name_ = new ::std::string;
- }
- name_->assign(value);
-}
-inline void GLOverlay::set_name(const char* value, size_t size) {
- set_has_name();
- if (name_ == &::google::protobuf::internal::kEmptyString) {
- name_ = new ::std::string;
- }
- name_->assign(reinterpret_cast<const char*>(value), size);
-}
-inline ::std::string* GLOverlay::mutable_name() {
- set_has_name();
- if (name_ == &::google::protobuf::internal::kEmptyString) {
- name_ = new ::std::string;
- }
- return name_;
-}
-inline ::std::string* GLOverlay::release_name() {
- clear_has_name();
- if (name_ == &::google::protobuf::internal::kEmptyString) {
- return NULL;
- } else {
- ::std::string* temp = name_;
- name_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString);
- return temp;
- }
-}
-
-// optional .px.GLOverlay.CoordinateFrameType coordinateFrameType = 3;
-inline bool GLOverlay::has_coordinateframetype() const {
- return (_has_bits_[0] & 0x00000004u) != 0;
-}
-inline void GLOverlay::set_has_coordinateframetype() {
- _has_bits_[0] |= 0x00000004u;
-}
-inline void GLOverlay::clear_has_coordinateframetype() {
- _has_bits_[0] &= ~0x00000004u;
-}
-inline void GLOverlay::clear_coordinateframetype() {
- coordinateframetype_ = 0;
- clear_has_coordinateframetype();
-}
-inline ::px::GLOverlay_CoordinateFrameType GLOverlay::coordinateframetype() const {
- return static_cast< ::px::GLOverlay_CoordinateFrameType >(coordinateframetype_);
-}
-inline void GLOverlay::set_coordinateframetype(::px::GLOverlay_CoordinateFrameType value) {
- GOOGLE_DCHECK(::px::GLOverlay_CoordinateFrameType_IsValid(value));
- set_has_coordinateframetype();
- coordinateframetype_ = value;
-}
-
-// optional double origin_x = 4;
-inline bool GLOverlay::has_origin_x() const {
- return (_has_bits_[0] & 0x00000008u) != 0;
-}
-inline void GLOverlay::set_has_origin_x() {
- _has_bits_[0] |= 0x00000008u;
-}
-inline void GLOverlay::clear_has_origin_x() {
- _has_bits_[0] &= ~0x00000008u;
-}
-inline void GLOverlay::clear_origin_x() {
- origin_x_ = 0;
- clear_has_origin_x();
-}
-inline double GLOverlay::origin_x() const {
- return origin_x_;
-}
-inline void GLOverlay::set_origin_x(double value) {
- set_has_origin_x();
- origin_x_ = value;
-}
-
-// optional double origin_y = 5;
-inline bool GLOverlay::has_origin_y() const {
- return (_has_bits_[0] & 0x00000010u) != 0;
-}
-inline void GLOverlay::set_has_origin_y() {
- _has_bits_[0] |= 0x00000010u;
-}
-inline void GLOverlay::clear_has_origin_y() {
- _has_bits_[0] &= ~0x00000010u;
-}
-inline void GLOverlay::clear_origin_y() {
- origin_y_ = 0;
- clear_has_origin_y();
-}
-inline double GLOverlay::origin_y() const {
- return origin_y_;
-}
-inline void GLOverlay::set_origin_y(double value) {
- set_has_origin_y();
- origin_y_ = value;
-}
-
-// optional double origin_z = 6;
-inline bool GLOverlay::has_origin_z() const {
- return (_has_bits_[0] & 0x00000020u) != 0;
-}
-inline void GLOverlay::set_has_origin_z() {
- _has_bits_[0] |= 0x00000020u;
-}
-inline void GLOverlay::clear_has_origin_z() {
- _has_bits_[0] &= ~0x00000020u;
-}
-inline void GLOverlay::clear_origin_z() {
- origin_z_ = 0;
- clear_has_origin_z();
-}
-inline double GLOverlay::origin_z() const {
- return origin_z_;
-}
-inline void GLOverlay::set_origin_z(double value) {
- set_has_origin_z();
- origin_z_ = value;
-}
-
-// optional bytes data = 7;
-inline bool GLOverlay::has_data() const {
- return (_has_bits_[0] & 0x00000040u) != 0;
-}
-inline void GLOverlay::set_has_data() {
- _has_bits_[0] |= 0x00000040u;
-}
-inline void GLOverlay::clear_has_data() {
- _has_bits_[0] &= ~0x00000040u;
-}
-inline void GLOverlay::clear_data() {
- if (data_ != &::google::protobuf::internal::kEmptyString) {
- data_->clear();
- }
- clear_has_data();
-}
-inline const ::std::string& GLOverlay::data() const {
- return *data_;
-}
-inline void GLOverlay::set_data(const ::std::string& value) {
- set_has_data();
- if (data_ == &::google::protobuf::internal::kEmptyString) {
- data_ = new ::std::string;
- }
- data_->assign(value);
-}
-inline void GLOverlay::set_data(const char* value) {
- set_has_data();
- if (data_ == &::google::protobuf::internal::kEmptyString) {
- data_ = new ::std::string;
- }
- data_->assign(value);
-}
-inline void GLOverlay::set_data(const void* value, size_t size) {
- set_has_data();
- if (data_ == &::google::protobuf::internal::kEmptyString) {
- data_ = new ::std::string;
- }
- data_->assign(reinterpret_cast<const char*>(value), size);
-}
-inline ::std::string* GLOverlay::mutable_data() {
- set_has_data();
- if (data_ == &::google::protobuf::internal::kEmptyString) {
- data_ = new ::std::string;
- }
- return data_;
-}
-inline ::std::string* GLOverlay::release_data() {
- clear_has_data();
- if (data_ == &::google::protobuf::internal::kEmptyString) {
- return NULL;
- } else {
- ::std::string* temp = data_;
- data_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString);
- return temp;
- }
-}
-
-// -------------------------------------------------------------------
-
-// Obstacle
-
-// optional float x = 1;
-inline bool Obstacle::has_x() const {
- return (_has_bits_[0] & 0x00000001u) != 0;
-}
-inline void Obstacle::set_has_x() {
- _has_bits_[0] |= 0x00000001u;
-}
-inline void Obstacle::clear_has_x() {
- _has_bits_[0] &= ~0x00000001u;
-}
-inline void Obstacle::clear_x() {
- x_ = 0;
- clear_has_x();
-}
-inline float Obstacle::x() const {
- return x_;
-}
-inline void Obstacle::set_x(float value) {
- set_has_x();
- x_ = value;
-}
-
-// optional float y = 2;
-inline bool Obstacle::has_y() const {
- return (_has_bits_[0] & 0x00000002u) != 0;
-}
-inline void Obstacle::set_has_y() {
- _has_bits_[0] |= 0x00000002u;
-}
-inline void Obstacle::clear_has_y() {
- _has_bits_[0] &= ~0x00000002u;
-}
-inline void Obstacle::clear_y() {
- y_ = 0;
- clear_has_y();
-}
-inline float Obstacle::y() const {
- return y_;
-}
-inline void Obstacle::set_y(float value) {
- set_has_y();
- y_ = value;
-}
-
-// optional float z = 3;
-inline bool Obstacle::has_z() const {
- return (_has_bits_[0] & 0x00000004u) != 0;
-}
-inline void Obstacle::set_has_z() {
- _has_bits_[0] |= 0x00000004u;
-}
-inline void Obstacle::clear_has_z() {
- _has_bits_[0] &= ~0x00000004u;
-}
-inline void Obstacle::clear_z() {
- z_ = 0;
- clear_has_z();
-}
-inline float Obstacle::z() const {
- return z_;
-}
-inline void Obstacle::set_z(float value) {
- set_has_z();
- z_ = value;
-}
-
-// optional float length = 4;
-inline bool Obstacle::has_length() const {
- return (_has_bits_[0] & 0x00000008u) != 0;
-}
-inline void Obstacle::set_has_length() {
- _has_bits_[0] |= 0x00000008u;
-}
-inline void Obstacle::clear_has_length() {
- _has_bits_[0] &= ~0x00000008u;
-}
-inline void Obstacle::clear_length() {
- length_ = 0;
- clear_has_length();
-}
-inline float Obstacle::length() const {
- return length_;
-}
-inline void Obstacle::set_length(float value) {
- set_has_length();
- length_ = value;
-}
-
-// optional float width = 5;
-inline bool Obstacle::has_width() const {
- return (_has_bits_[0] & 0x00000010u) != 0;
-}
-inline void Obstacle::set_has_width() {
- _has_bits_[0] |= 0x00000010u;
-}
-inline void Obstacle::clear_has_width() {
- _has_bits_[0] &= ~0x00000010u;
-}
-inline void Obstacle::clear_width() {
- width_ = 0;
- clear_has_width();
-}
-inline float Obstacle::width() const {
- return width_;
-}
-inline void Obstacle::set_width(float value) {
- set_has_width();
- width_ = value;
-}
-
-// optional float height = 6;
-inline bool Obstacle::has_height() const {
- return (_has_bits_[0] & 0x00000020u) != 0;
-}
-inline void Obstacle::set_has_height() {
- _has_bits_[0] |= 0x00000020u;
-}
-inline void Obstacle::clear_has_height() {
- _has_bits_[0] &= ~0x00000020u;
-}
-inline void Obstacle::clear_height() {
- height_ = 0;
- clear_has_height();
-}
-inline float Obstacle::height() const {
- return height_;
-}
-inline void Obstacle::set_height(float value) {
- set_has_height();
- height_ = value;
-}
-
-// -------------------------------------------------------------------
-
-// ObstacleList
-
-// required .px.HeaderInfo header = 1;
-inline bool ObstacleList::has_header() const {
- return (_has_bits_[0] & 0x00000001u) != 0;
-}
-inline void ObstacleList::set_has_header() {
- _has_bits_[0] |= 0x00000001u;
-}
-inline void ObstacleList::clear_has_header() {
- _has_bits_[0] &= ~0x00000001u;
-}
-inline void ObstacleList::clear_header() {
- if (header_ != NULL) header_->::px::HeaderInfo::Clear();
- clear_has_header();
-}
-inline const ::px::HeaderInfo& ObstacleList::header() const {
- return header_ != NULL ? *header_ : *default_instance_->header_;
-}
-inline ::px::HeaderInfo* ObstacleList::mutable_header() {
- set_has_header();
- if (header_ == NULL) header_ = new ::px::HeaderInfo;
- return header_;
-}
-inline ::px::HeaderInfo* ObstacleList::release_header() {
- clear_has_header();
- ::px::HeaderInfo* temp = header_;
- header_ = NULL;
- return temp;
-}
-
-// repeated .px.Obstacle obstacles = 2;
-inline int ObstacleList::obstacles_size() const {
- return obstacles_.size();
-}
-inline void ObstacleList::clear_obstacles() {
- obstacles_.Clear();
-}
-inline const ::px::Obstacle& ObstacleList::obstacles(int index) const {
- return obstacles_.Get(index);
-}
-inline ::px::Obstacle* ObstacleList::mutable_obstacles(int index) {
- return obstacles_.Mutable(index);
-}
-inline ::px::Obstacle* ObstacleList::add_obstacles() {
- return obstacles_.Add();
-}
-inline const ::google::protobuf::RepeatedPtrField< ::px::Obstacle >&
-ObstacleList::obstacles() const {
- return obstacles_;
-}
-inline ::google::protobuf::RepeatedPtrField< ::px::Obstacle >*
-ObstacleList::mutable_obstacles() {
- return &obstacles_;
-}
-
-// -------------------------------------------------------------------
-
-// ObstacleMap
-
-// required .px.HeaderInfo header = 1;
-inline bool ObstacleMap::has_header() const {
- return (_has_bits_[0] & 0x00000001u) != 0;
-}
-inline void ObstacleMap::set_has_header() {
- _has_bits_[0] |= 0x00000001u;
-}
-inline void ObstacleMap::clear_has_header() {
- _has_bits_[0] &= ~0x00000001u;
-}
-inline void ObstacleMap::clear_header() {
- if (header_ != NULL) header_->::px::HeaderInfo::Clear();
- clear_has_header();
-}
-inline const ::px::HeaderInfo& ObstacleMap::header() const {
- return header_ != NULL ? *header_ : *default_instance_->header_;
-}
-inline ::px::HeaderInfo* ObstacleMap::mutable_header() {
- set_has_header();
- if (header_ == NULL) header_ = new ::px::HeaderInfo;
- return header_;
-}
-inline ::px::HeaderInfo* ObstacleMap::release_header() {
- clear_has_header();
- ::px::HeaderInfo* temp = header_;
- header_ = NULL;
- return temp;
-}
-
-// required int32 type = 2;
-inline bool ObstacleMap::has_type() const {
- return (_has_bits_[0] & 0x00000002u) != 0;
-}
-inline void ObstacleMap::set_has_type() {
- _has_bits_[0] |= 0x00000002u;
-}
-inline void ObstacleMap::clear_has_type() {
- _has_bits_[0] &= ~0x00000002u;
-}
-inline void ObstacleMap::clear_type() {
- type_ = 0;
- clear_has_type();
-}
-inline ::google::protobuf::int32 ObstacleMap::type() const {
- return type_;
-}
-inline void ObstacleMap::set_type(::google::protobuf::int32 value) {
- set_has_type();
- type_ = value;
-}
-
-// optional float resolution = 3;
-inline bool ObstacleMap::has_resolution() const {
- return (_has_bits_[0] & 0x00000004u) != 0;
-}
-inline void ObstacleMap::set_has_resolution() {
- _has_bits_[0] |= 0x00000004u;
-}
-inline void ObstacleMap::clear_has_resolution() {
- _has_bits_[0] &= ~0x00000004u;
-}
-inline void ObstacleMap::clear_resolution() {
- resolution_ = 0;
- clear_has_resolution();
-}
-inline float ObstacleMap::resolution() const {
- return resolution_;
-}
-inline void ObstacleMap::set_resolution(float value) {
- set_has_resolution();
- resolution_ = value;
-}
-
-// optional int32 rows = 4;
-inline bool ObstacleMap::has_rows() const {
- return (_has_bits_[0] & 0x00000008u) != 0;
-}
-inline void ObstacleMap::set_has_rows() {
- _has_bits_[0] |= 0x00000008u;
-}
-inline void ObstacleMap::clear_has_rows() {
- _has_bits_[0] &= ~0x00000008u;
-}
-inline void ObstacleMap::clear_rows() {
- rows_ = 0;
- clear_has_rows();
-}
-inline ::google::protobuf::int32 ObstacleMap::rows() const {
- return rows_;
-}
-inline void ObstacleMap::set_rows(::google::protobuf::int32 value) {
- set_has_rows();
- rows_ = value;
-}
-
-// optional int32 cols = 5;
-inline bool ObstacleMap::has_cols() const {
- return (_has_bits_[0] & 0x00000010u) != 0;
-}
-inline void ObstacleMap::set_has_cols() {
- _has_bits_[0] |= 0x00000010u;
-}
-inline void ObstacleMap::clear_has_cols() {
- _has_bits_[0] &= ~0x00000010u;
-}
-inline void ObstacleMap::clear_cols() {
- cols_ = 0;
- clear_has_cols();
-}
-inline ::google::protobuf::int32 ObstacleMap::cols() const {
- return cols_;
-}
-inline void ObstacleMap::set_cols(::google::protobuf::int32 value) {
- set_has_cols();
- cols_ = value;
-}
-
-// optional int32 mapR0 = 6;
-inline bool ObstacleMap::has_mapr0() const {
- return (_has_bits_[0] & 0x00000020u) != 0;
-}
-inline void ObstacleMap::set_has_mapr0() {
- _has_bits_[0] |= 0x00000020u;
-}
-inline void ObstacleMap::clear_has_mapr0() {
- _has_bits_[0] &= ~0x00000020u;
-}
-inline void ObstacleMap::clear_mapr0() {
- mapr0_ = 0;
- clear_has_mapr0();
-}
-inline ::google::protobuf::int32 ObstacleMap::mapr0() const {
- return mapr0_;
-}
-inline void ObstacleMap::set_mapr0(::google::protobuf::int32 value) {
- set_has_mapr0();
- mapr0_ = value;
-}
-
-// optional int32 mapC0 = 7;
-inline bool ObstacleMap::has_mapc0() const {
- return (_has_bits_[0] & 0x00000040u) != 0;
-}
-inline void ObstacleMap::set_has_mapc0() {
- _has_bits_[0] |= 0x00000040u;
-}
-inline void ObstacleMap::clear_has_mapc0() {
- _has_bits_[0] &= ~0x00000040u;
-}
-inline void ObstacleMap::clear_mapc0() {
- mapc0_ = 0;
- clear_has_mapc0();
-}
-inline ::google::protobuf::int32 ObstacleMap::mapc0() const {
- return mapc0_;
-}
-inline void ObstacleMap::set_mapc0(::google::protobuf::int32 value) {
- set_has_mapc0();
- mapc0_ = value;
-}
-
-// optional int32 arrayR0 = 8;
-inline bool ObstacleMap::has_arrayr0() const {
- return (_has_bits_[0] & 0x00000080u) != 0;
-}
-inline void ObstacleMap::set_has_arrayr0() {
- _has_bits_[0] |= 0x00000080u;
-}
-inline void ObstacleMap::clear_has_arrayr0() {
- _has_bits_[0] &= ~0x00000080u;
-}
-inline void ObstacleMap::clear_arrayr0() {
- arrayr0_ = 0;
- clear_has_arrayr0();
-}
-inline ::google::protobuf::int32 ObstacleMap::arrayr0() const {
- return arrayr0_;
-}
-inline void ObstacleMap::set_arrayr0(::google::protobuf::int32 value) {
- set_has_arrayr0();
- arrayr0_ = value;
-}
-
-// optional int32 arrayC0 = 9;
-inline bool ObstacleMap::has_arrayc0() const {
- return (_has_bits_[0] & 0x00000100u) != 0;
-}
-inline void ObstacleMap::set_has_arrayc0() {
- _has_bits_[0] |= 0x00000100u;
-}
-inline void ObstacleMap::clear_has_arrayc0() {
- _has_bits_[0] &= ~0x00000100u;
-}
-inline void ObstacleMap::clear_arrayc0() {
- arrayc0_ = 0;
- clear_has_arrayc0();
-}
-inline ::google::protobuf::int32 ObstacleMap::arrayc0() const {
- return arrayc0_;
-}
-inline void ObstacleMap::set_arrayc0(::google::protobuf::int32 value) {
- set_has_arrayc0();
- arrayc0_ = value;
-}
-
-// optional bytes data = 10;
-inline bool ObstacleMap::has_data() const {
- return (_has_bits_[0] & 0x00000200u) != 0;
-}
-inline void ObstacleMap::set_has_data() {
- _has_bits_[0] |= 0x00000200u;
-}
-inline void ObstacleMap::clear_has_data() {
- _has_bits_[0] &= ~0x00000200u;
-}
-inline void ObstacleMap::clear_data() {
- if (data_ != &::google::protobuf::internal::kEmptyString) {
- data_->clear();
- }
- clear_has_data();
-}
-inline const ::std::string& ObstacleMap::data() const {
- return *data_;
-}
-inline void ObstacleMap::set_data(const ::std::string& value) {
- set_has_data();
- if (data_ == &::google::protobuf::internal::kEmptyString) {
- data_ = new ::std::string;
- }
- data_->assign(value);
-}
-inline void ObstacleMap::set_data(const char* value) {
- set_has_data();
- if (data_ == &::google::protobuf::internal::kEmptyString) {
- data_ = new ::std::string;
- }
- data_->assign(value);
-}
-inline void ObstacleMap::set_data(const void* value, size_t size) {
- set_has_data();
- if (data_ == &::google::protobuf::internal::kEmptyString) {
- data_ = new ::std::string;
- }
- data_->assign(reinterpret_cast<const char*>(value), size);
-}
-inline ::std::string* ObstacleMap::mutable_data() {
- set_has_data();
- if (data_ == &::google::protobuf::internal::kEmptyString) {
- data_ = new ::std::string;
- }
- return data_;
-}
-inline ::std::string* ObstacleMap::release_data() {
- clear_has_data();
- if (data_ == &::google::protobuf::internal::kEmptyString) {
- return NULL;
- } else {
- ::std::string* temp = data_;
- data_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString);
- return temp;
- }
-}
-
-// -------------------------------------------------------------------
-
-// Path
-
-// required .px.HeaderInfo header = 1;
-inline bool Path::has_header() const {
- return (_has_bits_[0] & 0x00000001u) != 0;
-}
-inline void Path::set_has_header() {
- _has_bits_[0] |= 0x00000001u;
-}
-inline void Path::clear_has_header() {
- _has_bits_[0] &= ~0x00000001u;
-}
-inline void Path::clear_header() {
- if (header_ != NULL) header_->::px::HeaderInfo::Clear();
- clear_has_header();
-}
-inline const ::px::HeaderInfo& Path::header() const {
- return header_ != NULL ? *header_ : *default_instance_->header_;
-}
-inline ::px::HeaderInfo* Path::mutable_header() {
- set_has_header();
- if (header_ == NULL) header_ = new ::px::HeaderInfo;
- return header_;
-}
-inline ::px::HeaderInfo* Path::release_header() {
- clear_has_header();
- ::px::HeaderInfo* temp = header_;
- header_ = NULL;
- return temp;
-}
-
-// repeated .px.Waypoint waypoints = 2;
-inline int Path::waypoints_size() const {
- return waypoints_.size();
-}
-inline void Path::clear_waypoints() {
- waypoints_.Clear();
-}
-inline const ::px::Waypoint& Path::waypoints(int index) const {
- return waypoints_.Get(index);
-}
-inline ::px::Waypoint* Path::mutable_waypoints(int index) {
- return waypoints_.Mutable(index);
-}
-inline ::px::Waypoint* Path::add_waypoints() {
- return waypoints_.Add();
-}
-inline const ::google::protobuf::RepeatedPtrField< ::px::Waypoint >&
-Path::waypoints() const {
- return waypoints_;
-}
-inline ::google::protobuf::RepeatedPtrField< ::px::Waypoint >*
-Path::mutable_waypoints() {
- return &waypoints_;
-}
-
-// -------------------------------------------------------------------
-
-// PointCloudXYZI_PointXYZI
-
-// required float x = 1;
-inline bool PointCloudXYZI_PointXYZI::has_x() const {
- return (_has_bits_[0] & 0x00000001u) != 0;
-}
-inline void PointCloudXYZI_PointXYZI::set_has_x() {
- _has_bits_[0] |= 0x00000001u;
-}
-inline void PointCloudXYZI_PointXYZI::clear_has_x() {
- _has_bits_[0] &= ~0x00000001u;
-}
-inline void PointCloudXYZI_PointXYZI::clear_x() {
- x_ = 0;
- clear_has_x();
-}
-inline float PointCloudXYZI_PointXYZI::x() const {
- return x_;
-}
-inline void PointCloudXYZI_PointXYZI::set_x(float value) {
- set_has_x();
- x_ = value;
-}
-
-// required float y = 2;
-inline bool PointCloudXYZI_PointXYZI::has_y() const {
- return (_has_bits_[0] & 0x00000002u) != 0;
-}
-inline void PointCloudXYZI_PointXYZI::set_has_y() {
- _has_bits_[0] |= 0x00000002u;
-}
-inline void PointCloudXYZI_PointXYZI::clear_has_y() {
- _has_bits_[0] &= ~0x00000002u;
-}
-inline void PointCloudXYZI_PointXYZI::clear_y() {
- y_ = 0;
- clear_has_y();
-}
-inline float PointCloudXYZI_PointXYZI::y() const {
- return y_;
-}
-inline void PointCloudXYZI_PointXYZI::set_y(float value) {
- set_has_y();
- y_ = value;
-}
-
-// required float z = 3;
-inline bool PointCloudXYZI_PointXYZI::has_z() const {
- return (_has_bits_[0] & 0x00000004u) != 0;
-}
-inline void PointCloudXYZI_PointXYZI::set_has_z() {
- _has_bits_[0] |= 0x00000004u;
-}
-inline void PointCloudXYZI_PointXYZI::clear_has_z() {
- _has_bits_[0] &= ~0x00000004u;
-}
-inline void PointCloudXYZI_PointXYZI::clear_z() {
- z_ = 0;
- clear_has_z();
-}
-inline float PointCloudXYZI_PointXYZI::z() const {
- return z_;
-}
-inline void PointCloudXYZI_PointXYZI::set_z(float value) {
- set_has_z();
- z_ = value;
-}
-
-// required float intensity = 4;
-inline bool PointCloudXYZI_PointXYZI::has_intensity() const {
- return (_has_bits_[0] & 0x00000008u) != 0;
-}
-inline void PointCloudXYZI_PointXYZI::set_has_intensity() {
- _has_bits_[0] |= 0x00000008u;
-}
-inline void PointCloudXYZI_PointXYZI::clear_has_intensity() {
- _has_bits_[0] &= ~0x00000008u;
-}
-inline void PointCloudXYZI_PointXYZI::clear_intensity() {
- intensity_ = 0;
- clear_has_intensity();
-}
-inline float PointCloudXYZI_PointXYZI::intensity() const {
- return intensity_;
-}
-inline void PointCloudXYZI_PointXYZI::set_intensity(float value) {
- set_has_intensity();
- intensity_ = value;
-}
-
-// -------------------------------------------------------------------
-
-// PointCloudXYZI
-
-// required .px.HeaderInfo header = 1;
-inline bool PointCloudXYZI::has_header() const {
- return (_has_bits_[0] & 0x00000001u) != 0;
-}
-inline void PointCloudXYZI::set_has_header() {
- _has_bits_[0] |= 0x00000001u;
-}
-inline void PointCloudXYZI::clear_has_header() {
- _has_bits_[0] &= ~0x00000001u;
-}
-inline void PointCloudXYZI::clear_header() {
- if (header_ != NULL) header_->::px::HeaderInfo::Clear();
- clear_has_header();
-}
-inline const ::px::HeaderInfo& PointCloudXYZI::header() const {
- return header_ != NULL ? *header_ : *default_instance_->header_;
-}
-inline ::px::HeaderInfo* PointCloudXYZI::mutable_header() {
- set_has_header();
- if (header_ == NULL) header_ = new ::px::HeaderInfo;
- return header_;
-}
-inline ::px::HeaderInfo* PointCloudXYZI::release_header() {
- clear_has_header();
- ::px::HeaderInfo* temp = header_;
- header_ = NULL;
- return temp;
-}
-
-// repeated .px.PointCloudXYZI.PointXYZI points = 2;
-inline int PointCloudXYZI::points_size() const {
- return points_.size();
-}
-inline void PointCloudXYZI::clear_points() {
- points_.Clear();
-}
-inline const ::px::PointCloudXYZI_PointXYZI& PointCloudXYZI::points(int index) const {
- return points_.Get(index);
-}
-inline ::px::PointCloudXYZI_PointXYZI* PointCloudXYZI::mutable_points(int index) {
- return points_.Mutable(index);
-}
-inline ::px::PointCloudXYZI_PointXYZI* PointCloudXYZI::add_points() {
- return points_.Add();
-}
-inline const ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZI_PointXYZI >&
-PointCloudXYZI::points() const {
- return points_;
-}
-inline ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZI_PointXYZI >*
-PointCloudXYZI::mutable_points() {
- return &points_;
-}
-
-// -------------------------------------------------------------------
-
-// PointCloudXYZRGB_PointXYZRGB
-
-// required float x = 1;
-inline bool PointCloudXYZRGB_PointXYZRGB::has_x() const {
- return (_has_bits_[0] & 0x00000001u) != 0;
-}
-inline void PointCloudXYZRGB_PointXYZRGB::set_has_x() {
- _has_bits_[0] |= 0x00000001u;
-}
-inline void PointCloudXYZRGB_PointXYZRGB::clear_has_x() {
- _has_bits_[0] &= ~0x00000001u;
-}
-inline void PointCloudXYZRGB_PointXYZRGB::clear_x() {
- x_ = 0;
- clear_has_x();
-}
-inline float PointCloudXYZRGB_PointXYZRGB::x() const {
- return x_;
-}
-inline void PointCloudXYZRGB_PointXYZRGB::set_x(float value) {
- set_has_x();
- x_ = value;
-}
-
-// required float y = 2;
-inline bool PointCloudXYZRGB_PointXYZRGB::has_y() const {
- return (_has_bits_[0] & 0x00000002u) != 0;
-}
-inline void PointCloudXYZRGB_PointXYZRGB::set_has_y() {
- _has_bits_[0] |= 0x00000002u;
-}
-inline void PointCloudXYZRGB_PointXYZRGB::clear_has_y() {
- _has_bits_[0] &= ~0x00000002u;
-}
-inline void PointCloudXYZRGB_PointXYZRGB::clear_y() {
- y_ = 0;
- clear_has_y();
-}
-inline float PointCloudXYZRGB_PointXYZRGB::y() const {
- return y_;
-}
-inline void PointCloudXYZRGB_PointXYZRGB::set_y(float value) {
- set_has_y();
- y_ = value;
-}
-
-// required float z = 3;
-inline bool PointCloudXYZRGB_PointXYZRGB::has_z() const {
- return (_has_bits_[0] & 0x00000004u) != 0;
-}
-inline void PointCloudXYZRGB_PointXYZRGB::set_has_z() {
- _has_bits_[0] |= 0x00000004u;
-}
-inline void PointCloudXYZRGB_PointXYZRGB::clear_has_z() {
- _has_bits_[0] &= ~0x00000004u;
-}
-inline void PointCloudXYZRGB_PointXYZRGB::clear_z() {
- z_ = 0;
- clear_has_z();
-}
-inline float PointCloudXYZRGB_PointXYZRGB::z() const {
- return z_;
-}
-inline void PointCloudXYZRGB_PointXYZRGB::set_z(float value) {
- set_has_z();
- z_ = value;
-}
-
-// required float rgb = 4;
-inline bool PointCloudXYZRGB_PointXYZRGB::has_rgb() const {
- return (_has_bits_[0] & 0x00000008u) != 0;
-}
-inline void PointCloudXYZRGB_PointXYZRGB::set_has_rgb() {
- _has_bits_[0] |= 0x00000008u;
-}
-inline void PointCloudXYZRGB_PointXYZRGB::clear_has_rgb() {
- _has_bits_[0] &= ~0x00000008u;
-}
-inline void PointCloudXYZRGB_PointXYZRGB::clear_rgb() {
- rgb_ = 0;
- clear_has_rgb();
-}
-inline float PointCloudXYZRGB_PointXYZRGB::rgb() const {
- return rgb_;
-}
-inline void PointCloudXYZRGB_PointXYZRGB::set_rgb(float value) {
- set_has_rgb();
- rgb_ = value;
-}
-
-// -------------------------------------------------------------------
-
-// PointCloudXYZRGB
-
-// required .px.HeaderInfo header = 1;
-inline bool PointCloudXYZRGB::has_header() const {
- return (_has_bits_[0] & 0x00000001u) != 0;
-}
-inline void PointCloudXYZRGB::set_has_header() {
- _has_bits_[0] |= 0x00000001u;
-}
-inline void PointCloudXYZRGB::clear_has_header() {
- _has_bits_[0] &= ~0x00000001u;
-}
-inline void PointCloudXYZRGB::clear_header() {
- if (header_ != NULL) header_->::px::HeaderInfo::Clear();
- clear_has_header();
-}
-inline const ::px::HeaderInfo& PointCloudXYZRGB::header() const {
- return header_ != NULL ? *header_ : *default_instance_->header_;
-}
-inline ::px::HeaderInfo* PointCloudXYZRGB::mutable_header() {
- set_has_header();
- if (header_ == NULL) header_ = new ::px::HeaderInfo;
- return header_;
-}
-inline ::px::HeaderInfo* PointCloudXYZRGB::release_header() {
- clear_has_header();
- ::px::HeaderInfo* temp = header_;
- header_ = NULL;
- return temp;
-}
-
-// repeated .px.PointCloudXYZRGB.PointXYZRGB points = 2;
-inline int PointCloudXYZRGB::points_size() const {
- return points_.size();
-}
-inline void PointCloudXYZRGB::clear_points() {
- points_.Clear();
-}
-inline const ::px::PointCloudXYZRGB_PointXYZRGB& PointCloudXYZRGB::points(int index) const {
- return points_.Get(index);
-}
-inline ::px::PointCloudXYZRGB_PointXYZRGB* PointCloudXYZRGB::mutable_points(int index) {
- return points_.Mutable(index);
-}
-inline ::px::PointCloudXYZRGB_PointXYZRGB* PointCloudXYZRGB::add_points() {
- return points_.Add();
-}
-inline const ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZRGB_PointXYZRGB >&
-PointCloudXYZRGB::points() const {
- return points_;
-}
-inline ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZRGB_PointXYZRGB >*
-PointCloudXYZRGB::mutable_points() {
- return &points_;
-}
-
-// -------------------------------------------------------------------
-
-// RGBDImage
-
-// required .px.HeaderInfo header = 1;
-inline bool RGBDImage::has_header() const {
- return (_has_bits_[0] & 0x00000001u) != 0;
-}
-inline void RGBDImage::set_has_header() {
- _has_bits_[0] |= 0x00000001u;
-}
-inline void RGBDImage::clear_has_header() {
- _has_bits_[0] &= ~0x00000001u;
-}
-inline void RGBDImage::clear_header() {
- if (header_ != NULL) header_->::px::HeaderInfo::Clear();
- clear_has_header();
-}
-inline const ::px::HeaderInfo& RGBDImage::header() const {
- return header_ != NULL ? *header_ : *default_instance_->header_;
-}
-inline ::px::HeaderInfo* RGBDImage::mutable_header() {
- set_has_header();
- if (header_ == NULL) header_ = new ::px::HeaderInfo;
- return header_;
-}
-inline ::px::HeaderInfo* RGBDImage::release_header() {
- clear_has_header();
- ::px::HeaderInfo* temp = header_;
- header_ = NULL;
- return temp;
-}
-
-// required uint32 cols = 2;
-inline bool RGBDImage::has_cols() const {
- return (_has_bits_[0] & 0x00000002u) != 0;
-}
-inline void RGBDImage::set_has_cols() {
- _has_bits_[0] |= 0x00000002u;
-}
-inline void RGBDImage::clear_has_cols() {
- _has_bits_[0] &= ~0x00000002u;
-}
-inline void RGBDImage::clear_cols() {
- cols_ = 0u;
- clear_has_cols();
-}
-inline ::google::protobuf::uint32 RGBDImage::cols() const {
- return cols_;
-}
-inline void RGBDImage::set_cols(::google::protobuf::uint32 value) {
- set_has_cols();
- cols_ = value;
-}
-
-// required uint32 rows = 3;
-inline bool RGBDImage::has_rows() const {
- return (_has_bits_[0] & 0x00000004u) != 0;
-}
-inline void RGBDImage::set_has_rows() {
- _has_bits_[0] |= 0x00000004u;
-}
-inline void RGBDImage::clear_has_rows() {
- _has_bits_[0] &= ~0x00000004u;
-}
-inline void RGBDImage::clear_rows() {
- rows_ = 0u;
- clear_has_rows();
-}
-inline ::google::protobuf::uint32 RGBDImage::rows() const {
- return rows_;
-}
-inline void RGBDImage::set_rows(::google::protobuf::uint32 value) {
- set_has_rows();
- rows_ = value;
-}
-
-// required uint32 step1 = 4;
-inline bool RGBDImage::has_step1() const {
- return (_has_bits_[0] & 0x00000008u) != 0;
-}
-inline void RGBDImage::set_has_step1() {
- _has_bits_[0] |= 0x00000008u;
-}
-inline void RGBDImage::clear_has_step1() {
- _has_bits_[0] &= ~0x00000008u;
-}
-inline void RGBDImage::clear_step1() {
- step1_ = 0u;
- clear_has_step1();
-}
-inline ::google::protobuf::uint32 RGBDImage::step1() const {
- return step1_;
-}
-inline void RGBDImage::set_step1(::google::protobuf::uint32 value) {
- set_has_step1();
- step1_ = value;
-}
-
-// required uint32 type1 = 5;
-inline bool RGBDImage::has_type1() const {
- return (_has_bits_[0] & 0x00000010u) != 0;
-}
-inline void RGBDImage::set_has_type1() {
- _has_bits_[0] |= 0x00000010u;
-}
-inline void RGBDImage::clear_has_type1() {
- _has_bits_[0] &= ~0x00000010u;
-}
-inline void RGBDImage::clear_type1() {
- type1_ = 0u;
- clear_has_type1();
-}
-inline ::google::protobuf::uint32 RGBDImage::type1() const {
- return type1_;
-}
-inline void RGBDImage::set_type1(::google::protobuf::uint32 value) {
- set_has_type1();
- type1_ = value;
-}
-
-// required bytes imageData1 = 6;
-inline bool RGBDImage::has_imagedata1() const {
- return (_has_bits_[0] & 0x00000020u) != 0;
-}
-inline void RGBDImage::set_has_imagedata1() {
- _has_bits_[0] |= 0x00000020u;
-}
-inline void RGBDImage::clear_has_imagedata1() {
- _has_bits_[0] &= ~0x00000020u;
-}
-inline void RGBDImage::clear_imagedata1() {
- if (imagedata1_ != &::google::protobuf::internal::kEmptyString) {
- imagedata1_->clear();
- }
- clear_has_imagedata1();
-}
-inline const ::std::string& RGBDImage::imagedata1() const {
- return *imagedata1_;
-}
-inline void RGBDImage::set_imagedata1(const ::std::string& value) {
- set_has_imagedata1();
- if (imagedata1_ == &::google::protobuf::internal::kEmptyString) {
- imagedata1_ = new ::std::string;
- }
- imagedata1_->assign(value);
-}
-inline void RGBDImage::set_imagedata1(const char* value) {
- set_has_imagedata1();
- if (imagedata1_ == &::google::protobuf::internal::kEmptyString) {
- imagedata1_ = new ::std::string;
- }
- imagedata1_->assign(value);
-}
-inline void RGBDImage::set_imagedata1(const void* value, size_t size) {
- set_has_imagedata1();
- if (imagedata1_ == &::google::protobuf::internal::kEmptyString) {
- imagedata1_ = new ::std::string;
- }
- imagedata1_->assign(reinterpret_cast<const char*>(value), size);
-}
-inline ::std::string* RGBDImage::mutable_imagedata1() {
- set_has_imagedata1();
- if (imagedata1_ == &::google::protobuf::internal::kEmptyString) {
- imagedata1_ = new ::std::string;
- }
- return imagedata1_;
-}
-inline ::std::string* RGBDImage::release_imagedata1() {
- clear_has_imagedata1();
- if (imagedata1_ == &::google::protobuf::internal::kEmptyString) {
- return NULL;
- } else {
- ::std::string* temp = imagedata1_;
- imagedata1_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString);
- return temp;
- }
-}
-
-// required uint32 step2 = 7;
-inline bool RGBDImage::has_step2() const {
- return (_has_bits_[0] & 0x00000040u) != 0;
-}
-inline void RGBDImage::set_has_step2() {
- _has_bits_[0] |= 0x00000040u;
-}
-inline void RGBDImage::clear_has_step2() {
- _has_bits_[0] &= ~0x00000040u;
-}
-inline void RGBDImage::clear_step2() {
- step2_ = 0u;
- clear_has_step2();
-}
-inline ::google::protobuf::uint32 RGBDImage::step2() const {
- return step2_;
-}
-inline void RGBDImage::set_step2(::google::protobuf::uint32 value) {
- set_has_step2();
- step2_ = value;
-}
-
-// required uint32 type2 = 8;
-inline bool RGBDImage::has_type2() const {
- return (_has_bits_[0] & 0x00000080u) != 0;
-}
-inline void RGBDImage::set_has_type2() {
- _has_bits_[0] |= 0x00000080u;
-}
-inline void RGBDImage::clear_has_type2() {
- _has_bits_[0] &= ~0x00000080u;
-}
-inline void RGBDImage::clear_type2() {
- type2_ = 0u;
- clear_has_type2();
-}
-inline ::google::protobuf::uint32 RGBDImage::type2() const {
- return type2_;
-}
-inline void RGBDImage::set_type2(::google::protobuf::uint32 value) {
- set_has_type2();
- type2_ = value;
-}
-
-// required bytes imageData2 = 9;
-inline bool RGBDImage::has_imagedata2() const {
- return (_has_bits_[0] & 0x00000100u) != 0;
-}
-inline void RGBDImage::set_has_imagedata2() {
- _has_bits_[0] |= 0x00000100u;
-}
-inline void RGBDImage::clear_has_imagedata2() {
- _has_bits_[0] &= ~0x00000100u;
-}
-inline void RGBDImage::clear_imagedata2() {
- if (imagedata2_ != &::google::protobuf::internal::kEmptyString) {
- imagedata2_->clear();
- }
- clear_has_imagedata2();
-}
-inline const ::std::string& RGBDImage::imagedata2() const {
- return *imagedata2_;
-}
-inline void RGBDImage::set_imagedata2(const ::std::string& value) {
- set_has_imagedata2();
- if (imagedata2_ == &::google::protobuf::internal::kEmptyString) {
- imagedata2_ = new ::std::string;
- }
- imagedata2_->assign(value);
-}
-inline void RGBDImage::set_imagedata2(const char* value) {
- set_has_imagedata2();
- if (imagedata2_ == &::google::protobuf::internal::kEmptyString) {
- imagedata2_ = new ::std::string;
- }
- imagedata2_->assign(value);
-}
-inline void RGBDImage::set_imagedata2(const void* value, size_t size) {
- set_has_imagedata2();
- if (imagedata2_ == &::google::protobuf::internal::kEmptyString) {
- imagedata2_ = new ::std::string;
- }
- imagedata2_->assign(reinterpret_cast<const char*>(value), size);
-}
-inline ::std::string* RGBDImage::mutable_imagedata2() {
- set_has_imagedata2();
- if (imagedata2_ == &::google::protobuf::internal::kEmptyString) {
- imagedata2_ = new ::std::string;
- }
- return imagedata2_;
-}
-inline ::std::string* RGBDImage::release_imagedata2() {
- clear_has_imagedata2();
- if (imagedata2_ == &::google::protobuf::internal::kEmptyString) {
- return NULL;
- } else {
- ::std::string* temp = imagedata2_;
- imagedata2_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString);
- return temp;
- }
-}
-
-// optional uint32 camera_config = 10;
-inline bool RGBDImage::has_camera_config() const {
- return (_has_bits_[0] & 0x00000200u) != 0;
-}
-inline void RGBDImage::set_has_camera_config() {
- _has_bits_[0] |= 0x00000200u;
-}
-inline void RGBDImage::clear_has_camera_config() {
- _has_bits_[0] &= ~0x00000200u;
-}
-inline void RGBDImage::clear_camera_config() {
- camera_config_ = 0u;
- clear_has_camera_config();
-}
-inline ::google::protobuf::uint32 RGBDImage::camera_config() const {
- return camera_config_;
-}
-inline void RGBDImage::set_camera_config(::google::protobuf::uint32 value) {
- set_has_camera_config();
- camera_config_ = value;
-}
-
-// optional uint32 camera_type = 11;
-inline bool RGBDImage::has_camera_type() const {
- return (_has_bits_[0] & 0x00000400u) != 0;
-}
-inline void RGBDImage::set_has_camera_type() {
- _has_bits_[0] |= 0x00000400u;
-}
-inline void RGBDImage::clear_has_camera_type() {
- _has_bits_[0] &= ~0x00000400u;
-}
-inline void RGBDImage::clear_camera_type() {
- camera_type_ = 0u;
- clear_has_camera_type();
-}
-inline ::google::protobuf::uint32 RGBDImage::camera_type() const {
- return camera_type_;
-}
-inline void RGBDImage::set_camera_type(::google::protobuf::uint32 value) {
- set_has_camera_type();
- camera_type_ = value;
-}
-
-// optional float roll = 12;
-inline bool RGBDImage::has_roll() const {
- return (_has_bits_[0] & 0x00000800u) != 0;
-}
-inline void RGBDImage::set_has_roll() {
- _has_bits_[0] |= 0x00000800u;
-}
-inline void RGBDImage::clear_has_roll() {
- _has_bits_[0] &= ~0x00000800u;
-}
-inline void RGBDImage::clear_roll() {
- roll_ = 0;
- clear_has_roll();
-}
-inline float RGBDImage::roll() const {
- return roll_;
-}
-inline void RGBDImage::set_roll(float value) {
- set_has_roll();
- roll_ = value;
-}
-
-// optional float pitch = 13;
-inline bool RGBDImage::has_pitch() const {
- return (_has_bits_[0] & 0x00001000u) != 0;
-}
-inline void RGBDImage::set_has_pitch() {
- _has_bits_[0] |= 0x00001000u;
-}
-inline void RGBDImage::clear_has_pitch() {
- _has_bits_[0] &= ~0x00001000u;
-}
-inline void RGBDImage::clear_pitch() {
- pitch_ = 0;
- clear_has_pitch();
-}
-inline float RGBDImage::pitch() const {
- return pitch_;
-}
-inline void RGBDImage::set_pitch(float value) {
- set_has_pitch();
- pitch_ = value;
-}
-
-// optional float yaw = 14;
-inline bool RGBDImage::has_yaw() const {
- return (_has_bits_[0] & 0x00002000u) != 0;
-}
-inline void RGBDImage::set_has_yaw() {
- _has_bits_[0] |= 0x00002000u;
-}
-inline void RGBDImage::clear_has_yaw() {
- _has_bits_[0] &= ~0x00002000u;
-}
-inline void RGBDImage::clear_yaw() {
- yaw_ = 0;
- clear_has_yaw();
-}
-inline float RGBDImage::yaw() const {
- return yaw_;
-}
-inline void RGBDImage::set_yaw(float value) {
- set_has_yaw();
- yaw_ = value;
-}
-
-// optional float lon = 15;
-inline bool RGBDImage::has_lon() const {
- return (_has_bits_[0] & 0x00004000u) != 0;
-}
-inline void RGBDImage::set_has_lon() {
- _has_bits_[0] |= 0x00004000u;
-}
-inline void RGBDImage::clear_has_lon() {
- _has_bits_[0] &= ~0x00004000u;
-}
-inline void RGBDImage::clear_lon() {
- lon_ = 0;
- clear_has_lon();
-}
-inline float RGBDImage::lon() const {
- return lon_;
-}
-inline void RGBDImage::set_lon(float value) {
- set_has_lon();
- lon_ = value;
-}
-
-// optional float lat = 16;
-inline bool RGBDImage::has_lat() const {
- return (_has_bits_[0] & 0x00008000u) != 0;
-}
-inline void RGBDImage::set_has_lat() {
- _has_bits_[0] |= 0x00008000u;
-}
-inline void RGBDImage::clear_has_lat() {
- _has_bits_[0] &= ~0x00008000u;
-}
-inline void RGBDImage::clear_lat() {
- lat_ = 0;
- clear_has_lat();
-}
-inline float RGBDImage::lat() const {
- return lat_;
-}
-inline void RGBDImage::set_lat(float value) {
- set_has_lat();
- lat_ = value;
-}
-
-// optional float alt = 17;
-inline bool RGBDImage::has_alt() const {
- return (_has_bits_[0] & 0x00010000u) != 0;
-}
-inline void RGBDImage::set_has_alt() {
- _has_bits_[0] |= 0x00010000u;
-}
-inline void RGBDImage::clear_has_alt() {
- _has_bits_[0] &= ~0x00010000u;
-}
-inline void RGBDImage::clear_alt() {
- alt_ = 0;
- clear_has_alt();
-}
-inline float RGBDImage::alt() const {
- return alt_;
-}
-inline void RGBDImage::set_alt(float value) {
- set_has_alt();
- alt_ = value;
-}
-
-// optional float ground_x = 18;
-inline bool RGBDImage::has_ground_x() const {
- return (_has_bits_[0] & 0x00020000u) != 0;
-}
-inline void RGBDImage::set_has_ground_x() {
- _has_bits_[0] |= 0x00020000u;
-}
-inline void RGBDImage::clear_has_ground_x() {
- _has_bits_[0] &= ~0x00020000u;
-}
-inline void RGBDImage::clear_ground_x() {
- ground_x_ = 0;
- clear_has_ground_x();
-}
-inline float RGBDImage::ground_x() const {
- return ground_x_;
-}
-inline void RGBDImage::set_ground_x(float value) {
- set_has_ground_x();
- ground_x_ = value;
-}
-
-// optional float ground_y = 19;
-inline bool RGBDImage::has_ground_y() const {
- return (_has_bits_[0] & 0x00040000u) != 0;
-}
-inline void RGBDImage::set_has_ground_y() {
- _has_bits_[0] |= 0x00040000u;
-}
-inline void RGBDImage::clear_has_ground_y() {
- _has_bits_[0] &= ~0x00040000u;
-}
-inline void RGBDImage::clear_ground_y() {
- ground_y_ = 0;
- clear_has_ground_y();
-}
-inline float RGBDImage::ground_y() const {
- return ground_y_;
-}
-inline void RGBDImage::set_ground_y(float value) {
- set_has_ground_y();
- ground_y_ = value;
-}
-
-// optional float ground_z = 20;
-inline bool RGBDImage::has_ground_z() const {
- return (_has_bits_[0] & 0x00080000u) != 0;
-}
-inline void RGBDImage::set_has_ground_z() {
- _has_bits_[0] |= 0x00080000u;
-}
-inline void RGBDImage::clear_has_ground_z() {
- _has_bits_[0] &= ~0x00080000u;
-}
-inline void RGBDImage::clear_ground_z() {
- ground_z_ = 0;
- clear_has_ground_z();
-}
-inline float RGBDImage::ground_z() const {
- return ground_z_;
-}
-inline void RGBDImage::set_ground_z(float value) {
- set_has_ground_z();
- ground_z_ = value;
-}
-
-// repeated float camera_matrix = 21;
-inline int RGBDImage::camera_matrix_size() const {
- return camera_matrix_.size();
-}
-inline void RGBDImage::clear_camera_matrix() {
- camera_matrix_.Clear();
-}
-inline float RGBDImage::camera_matrix(int index) const {
- return camera_matrix_.Get(index);
-}
-inline void RGBDImage::set_camera_matrix(int index, float value) {
- camera_matrix_.Set(index, value);
-}
-inline void RGBDImage::add_camera_matrix(float value) {
- camera_matrix_.Add(value);
-}
-inline const ::google::protobuf::RepeatedField< float >&
-RGBDImage::camera_matrix() const {
- return camera_matrix_;
-}
-inline ::google::protobuf::RepeatedField< float >*
-RGBDImage::mutable_camera_matrix() {
- return &camera_matrix_;
-}
-
-// -------------------------------------------------------------------
-
-// Waypoint
-
-// required double x = 1;
-inline bool Waypoint::has_x() const {
- return (_has_bits_[0] & 0x00000001u) != 0;
-}
-inline void Waypoint::set_has_x() {
- _has_bits_[0] |= 0x00000001u;
-}
-inline void Waypoint::clear_has_x() {
- _has_bits_[0] &= ~0x00000001u;
-}
-inline void Waypoint::clear_x() {
- x_ = 0;
- clear_has_x();
-}
-inline double Waypoint::x() const {
- return x_;
-}
-inline void Waypoint::set_x(double value) {
- set_has_x();
- x_ = value;
-}
-
-// required double y = 2;
-inline bool Waypoint::has_y() const {
- return (_has_bits_[0] & 0x00000002u) != 0;
-}
-inline void Waypoint::set_has_y() {
- _has_bits_[0] |= 0x00000002u;
-}
-inline void Waypoint::clear_has_y() {
- _has_bits_[0] &= ~0x00000002u;
-}
-inline void Waypoint::clear_y() {
- y_ = 0;
- clear_has_y();
-}
-inline double Waypoint::y() const {
- return y_;
-}
-inline void Waypoint::set_y(double value) {
- set_has_y();
- y_ = value;
-}
-
-// optional double z = 3;
-inline bool Waypoint::has_z() const {
- return (_has_bits_[0] & 0x00000004u) != 0;
-}
-inline void Waypoint::set_has_z() {
- _has_bits_[0] |= 0x00000004u;
-}
-inline void Waypoint::clear_has_z() {
- _has_bits_[0] &= ~0x00000004u;
-}
-inline void Waypoint::clear_z() {
- z_ = 0;
- clear_has_z();
-}
-inline double Waypoint::z() const {
- return z_;
-}
-inline void Waypoint::set_z(double value) {
- set_has_z();
- z_ = value;
-}
-
-// optional double roll = 4;
-inline bool Waypoint::has_roll() const {
- return (_has_bits_[0] & 0x00000008u) != 0;
-}
-inline void Waypoint::set_has_roll() {
- _has_bits_[0] |= 0x00000008u;
-}
-inline void Waypoint::clear_has_roll() {
- _has_bits_[0] &= ~0x00000008u;
-}
-inline void Waypoint::clear_roll() {
- roll_ = 0;
- clear_has_roll();
-}
-inline double Waypoint::roll() const {
- return roll_;
-}
-inline void Waypoint::set_roll(double value) {
- set_has_roll();
- roll_ = value;
-}
-
-// optional double pitch = 5;
-inline bool Waypoint::has_pitch() const {
- return (_has_bits_[0] & 0x00000010u) != 0;
-}
-inline void Waypoint::set_has_pitch() {
- _has_bits_[0] |= 0x00000010u;
-}
-inline void Waypoint::clear_has_pitch() {
- _has_bits_[0] &= ~0x00000010u;
-}
-inline void Waypoint::clear_pitch() {
- pitch_ = 0;
- clear_has_pitch();
-}
-inline double Waypoint::pitch() const {
- return pitch_;
-}
-inline void Waypoint::set_pitch(double value) {
- set_has_pitch();
- pitch_ = value;
-}
-
-// optional double yaw = 6;
-inline bool Waypoint::has_yaw() const {
- return (_has_bits_[0] & 0x00000020u) != 0;
-}
-inline void Waypoint::set_has_yaw() {
- _has_bits_[0] |= 0x00000020u;
-}
-inline void Waypoint::clear_has_yaw() {
- _has_bits_[0] &= ~0x00000020u;
-}
-inline void Waypoint::clear_yaw() {
- yaw_ = 0;
- clear_has_yaw();
-}
-inline double Waypoint::yaw() const {
- return yaw_;
-}
-inline void Waypoint::set_yaw(double value) {
- set_has_yaw();
- yaw_ = value;
-}
-
-
-// @@protoc_insertion_point(namespace_scope)
-
-} // namespace px
-
-#ifndef SWIG
-namespace google {
-namespace protobuf {
-
-template <>
-inline const EnumDescriptor* GetEnumDescriptor< ::px::GLOverlay_CoordinateFrameType>() {
- return ::px::GLOverlay_CoordinateFrameType_descriptor();
-}
-template <>
-inline const EnumDescriptor* GetEnumDescriptor< ::px::GLOverlay_Mode>() {
- return ::px::GLOverlay_Mode_descriptor();
-}
-template <>
-inline const EnumDescriptor* GetEnumDescriptor< ::px::GLOverlay_Identifier>() {
- return ::px::GLOverlay_Identifier_descriptor();
-}
-
-} // namespace google
-} // namespace protobuf
-#endif // SWIG
-
-// @@protoc_insertion_point(global_scope)
-
-#endif // PROTOBUF_pixhawk_2eproto__INCLUDED
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/protocol.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/protocol.h
deleted file mode 100644
index 7b3e3c0bd..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/protocol.h
+++ /dev/null
@@ -1,322 +0,0 @@
-#ifndef _MAVLINK_PROTOCOL_H_
-#define _MAVLINK_PROTOCOL_H_
-
-#include "string.h"
-#include "mavlink_types.h"
-
-/*
- If you want MAVLink on a system that is native big-endian,
- you need to define NATIVE_BIG_ENDIAN
-*/
-#ifdef NATIVE_BIG_ENDIAN
-# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN == MAVLINK_LITTLE_ENDIAN)
-#else
-# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN != MAVLINK_LITTLE_ENDIAN)
-#endif
-
-#ifndef MAVLINK_STACK_BUFFER
-#define MAVLINK_STACK_BUFFER 0
-#endif
-
-#ifndef MAVLINK_AVOID_GCC_STACK_BUG
-# define MAVLINK_AVOID_GCC_STACK_BUG defined(__GNUC__)
-#endif
-
-#ifndef MAVLINK_ASSERT
-#define MAVLINK_ASSERT(x)
-#endif
-
-#ifndef MAVLINK_START_UART_SEND
-#define MAVLINK_START_UART_SEND(chan, length)
-#endif
-
-#ifndef MAVLINK_END_UART_SEND
-#define MAVLINK_END_UART_SEND(chan, length)
-#endif
-
-#ifdef MAVLINK_SEPARATE_HELPERS
-#define MAVLINK_HELPER
-#else
-#define MAVLINK_HELPER static inline
-#include "mavlink_helpers.h"
-#endif // MAVLINK_SEPARATE_HELPERS
-
-/* always include the prototypes to ensure we don't get out of sync */
-MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan);
-#if MAVLINK_CRC_EXTRA
-MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
- uint8_t chan, uint8_t length, uint8_t crc_extra);
-MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
- uint8_t length, uint8_t crc_extra);
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet,
- uint8_t length, uint8_t crc_extra);
-#endif
-#else
-MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
- uint8_t chan, uint8_t length);
-MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
- uint8_t length);
-MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length);
-#endif // MAVLINK_CRC_EXTRA
-MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg);
-MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg);
-MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c);
-MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status);
-MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index,
- uint8_t* r_bit_index, uint8_t* buffer);
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len);
-#endif
-
-/**
- * @brief Get the required buffer size for this message
- */
-static inline uint16_t mavlink_msg_get_send_buffer_length(const mavlink_message_t* msg)
-{
- return msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES;
-}
-
-#if MAVLINK_NEED_BYTE_SWAP
-static inline void byte_swap_2(char *dst, const char *src)
-{
- dst[0] = src[1];
- dst[1] = src[0];
-}
-static inline void byte_swap_4(char *dst, const char *src)
-{
- dst[0] = src[3];
- dst[1] = src[2];
- dst[2] = src[1];
- dst[3] = src[0];
-}
-static inline void byte_swap_8(char *dst, const char *src)
-{
- dst[0] = src[7];
- dst[1] = src[6];
- dst[2] = src[5];
- dst[3] = src[4];
- dst[4] = src[3];
- dst[5] = src[2];
- dst[6] = src[1];
- dst[7] = src[0];
-}
-#elif !MAVLINK_ALIGNED_FIELDS
-static inline void byte_copy_2(char *dst, const char *src)
-{
- dst[0] = src[0];
- dst[1] = src[1];
-}
-static inline void byte_copy_4(char *dst, const char *src)
-{
- dst[0] = src[0];
- dst[1] = src[1];
- dst[2] = src[2];
- dst[3] = src[3];
-}
-static inline void byte_copy_8(char *dst, const char *src)
-{
- memcpy(dst, src, 8);
-}
-#endif
-
-#define _mav_put_uint8_t(buf, wire_offset, b) buf[wire_offset] = (uint8_t)b
-#define _mav_put_int8_t(buf, wire_offset, b) buf[wire_offset] = (int8_t)b
-#define _mav_put_char(buf, wire_offset, b) buf[wire_offset] = b
-
-#if MAVLINK_NEED_BYTE_SWAP
-#define _mav_put_uint16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b)
-#define _mav_put_int16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b)
-#define _mav_put_uint32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b)
-#define _mav_put_int32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b)
-#define _mav_put_uint64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b)
-#define _mav_put_int64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b)
-#define _mav_put_float(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b)
-#define _mav_put_double(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b)
-#elif !MAVLINK_ALIGNED_FIELDS
-#define _mav_put_uint16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b)
-#define _mav_put_int16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b)
-#define _mav_put_uint32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b)
-#define _mav_put_int32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b)
-#define _mav_put_uint64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b)
-#define _mav_put_int64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b)
-#define _mav_put_float(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b)
-#define _mav_put_double(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b)
-#else
-#define _mav_put_uint16_t(buf, wire_offset, b) *(uint16_t *)&buf[wire_offset] = b
-#define _mav_put_int16_t(buf, wire_offset, b) *(int16_t *)&buf[wire_offset] = b
-#define _mav_put_uint32_t(buf, wire_offset, b) *(uint32_t *)&buf[wire_offset] = b
-#define _mav_put_int32_t(buf, wire_offset, b) *(int32_t *)&buf[wire_offset] = b
-#define _mav_put_uint64_t(buf, wire_offset, b) *(uint64_t *)&buf[wire_offset] = b
-#define _mav_put_int64_t(buf, wire_offset, b) *(int64_t *)&buf[wire_offset] = b
-#define _mav_put_float(buf, wire_offset, b) *(float *)&buf[wire_offset] = b
-#define _mav_put_double(buf, wire_offset, b) *(double *)&buf[wire_offset] = b
-#endif
-
-/*
- like memcpy(), but if src is NULL, do a memset to zero
-*/
-static void mav_array_memcpy(void *dest, const void *src, size_t n)
-{
- if (src == NULL) {
- memset(dest, 0, n);
- } else {
- memcpy(dest, src, n);
- }
-}
-
-/*
- * Place a char array into a buffer
- */
-static inline void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length)
-{
- mav_array_memcpy(&buf[wire_offset], b, array_length);
-
-}
-
-/*
- * Place a uint8_t array into a buffer
- */
-static inline void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length)
-{
- mav_array_memcpy(&buf[wire_offset], b, array_length);
-
-}
-
-/*
- * Place a int8_t array into a buffer
- */
-static inline void _mav_put_int8_t_array(char *buf, uint8_t wire_offset, const int8_t *b, uint8_t array_length)
-{
- mav_array_memcpy(&buf[wire_offset], b, array_length);
-
-}
-
-#if MAVLINK_NEED_BYTE_SWAP
-#define _MAV_PUT_ARRAY(TYPE, V) \
-static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \
-{ \
- if (b == NULL) { \
- memset(&buf[wire_offset], 0, array_length*sizeof(TYPE)); \
- } else { \
- uint16_t i; \
- for (i=0; i<array_length; i++) { \
- _mav_put_## TYPE (buf, wire_offset+(i*sizeof(TYPE)), b[i]); \
- } \
- } \
-}
-#else
-#define _MAV_PUT_ARRAY(TYPE, V) \
-static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \
-{ \
- mav_array_memcpy(&buf[wire_offset], b, array_length*sizeof(TYPE)); \
-}
-#endif
-
-_MAV_PUT_ARRAY(uint16_t, u16)
-_MAV_PUT_ARRAY(uint32_t, u32)
-_MAV_PUT_ARRAY(uint64_t, u64)
-_MAV_PUT_ARRAY(int16_t, i16)
-_MAV_PUT_ARRAY(int32_t, i32)
-_MAV_PUT_ARRAY(int64_t, i64)
-_MAV_PUT_ARRAY(float, f)
-_MAV_PUT_ARRAY(double, d)
-
-#define _MAV_RETURN_char(msg, wire_offset) (const char)_MAV_PAYLOAD(msg)[wire_offset]
-#define _MAV_RETURN_int8_t(msg, wire_offset) (const int8_t)_MAV_PAYLOAD(msg)[wire_offset]
-#define _MAV_RETURN_uint8_t(msg, wire_offset) (const uint8_t)_MAV_PAYLOAD(msg)[wire_offset]
-
-#if MAVLINK_NEED_BYTE_SWAP
-#define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \
-static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
-{ TYPE r; byte_swap_## SIZE((char*)&r, &_MAV_PAYLOAD(msg)[ofs]); return r; }
-
-_MAV_MSG_RETURN_TYPE(uint16_t, 2)
-_MAV_MSG_RETURN_TYPE(int16_t, 2)
-_MAV_MSG_RETURN_TYPE(uint32_t, 4)
-_MAV_MSG_RETURN_TYPE(int32_t, 4)
-_MAV_MSG_RETURN_TYPE(uint64_t, 8)
-_MAV_MSG_RETURN_TYPE(int64_t, 8)
-_MAV_MSG_RETURN_TYPE(float, 4)
-_MAV_MSG_RETURN_TYPE(double, 8)
-
-#elif !MAVLINK_ALIGNED_FIELDS
-#define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \
-static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
-{ TYPE r; byte_copy_## SIZE((char*)&r, &_MAV_PAYLOAD(msg)[ofs]); return r; }
-
-_MAV_MSG_RETURN_TYPE(uint16_t, 2)
-_MAV_MSG_RETURN_TYPE(int16_t, 2)
-_MAV_MSG_RETURN_TYPE(uint32_t, 4)
-_MAV_MSG_RETURN_TYPE(int32_t, 4)
-_MAV_MSG_RETURN_TYPE(uint64_t, 8)
-_MAV_MSG_RETURN_TYPE(int64_t, 8)
-_MAV_MSG_RETURN_TYPE(float, 4)
-_MAV_MSG_RETURN_TYPE(double, 8)
-#else // nicely aligned, no swap
-#define _MAV_MSG_RETURN_TYPE(TYPE) \
-static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
-{ return *(const TYPE *)(&_MAV_PAYLOAD(msg)[ofs]);}
-
-_MAV_MSG_RETURN_TYPE(uint16_t)
-_MAV_MSG_RETURN_TYPE(int16_t)
-_MAV_MSG_RETURN_TYPE(uint32_t)
-_MAV_MSG_RETURN_TYPE(int32_t)
-_MAV_MSG_RETURN_TYPE(uint64_t)
-_MAV_MSG_RETURN_TYPE(int64_t)
-_MAV_MSG_RETURN_TYPE(float)
-_MAV_MSG_RETURN_TYPE(double)
-#endif // MAVLINK_NEED_BYTE_SWAP
-
-static inline uint16_t _MAV_RETURN_char_array(const mavlink_message_t *msg, char *value,
- uint8_t array_length, uint8_t wire_offset)
-{
- memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length);
- return array_length;
-}
-
-static inline uint16_t _MAV_RETURN_uint8_t_array(const mavlink_message_t *msg, uint8_t *value,
- uint8_t array_length, uint8_t wire_offset)
-{
- memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length);
- return array_length;
-}
-
-static inline uint16_t _MAV_RETURN_int8_t_array(const mavlink_message_t *msg, int8_t *value,
- uint8_t array_length, uint8_t wire_offset)
-{
- memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length);
- return array_length;
-}
-
-#if MAVLINK_NEED_BYTE_SWAP
-#define _MAV_RETURN_ARRAY(TYPE, V) \
-static inline uint16_t _MAV_RETURN_## TYPE ##_array(const mavlink_message_t *msg, TYPE *value, \
- uint8_t array_length, uint8_t wire_offset) \
-{ \
- uint16_t i; \
- for (i=0; i<array_length; i++) { \
- value[i] = _MAV_RETURN_## TYPE (msg, wire_offset+(i*sizeof(value[0]))); \
- } \
- return array_length*sizeof(value[0]); \
-}
-#else
-#define _MAV_RETURN_ARRAY(TYPE, V) \
-static inline uint16_t _MAV_RETURN_## TYPE ##_array(const mavlink_message_t *msg, TYPE *value, \
- uint8_t array_length, uint8_t wire_offset) \
-{ \
- memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length*sizeof(TYPE)); \
- return array_length*sizeof(TYPE); \
-}
-#endif
-
-_MAV_RETURN_ARRAY(uint16_t, u16)
-_MAV_RETURN_ARRAY(uint32_t, u32)
-_MAV_RETURN_ARRAY(uint64_t, u64)
-_MAV_RETURN_ARRAY(int16_t, i16)
-_MAV_RETURN_ARRAY(int32_t, i32)
-_MAV_RETURN_ARRAY(int64_t, i64)
-_MAV_RETURN_ARRAY(float, f)
-_MAV_RETURN_ARRAY(double, d)
-
-#endif // _MAVLINK_PROTOCOL_H_
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/mavlink.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/mavlink.h
deleted file mode 100644
index e596b8fba..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/mavlink.h
+++ /dev/null
@@ -1,27 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol built from test.xml
- * @see http://pixhawk.ethz.ch/software/mavlink
- */
-#ifndef MAVLINK_H
-#define MAVLINK_H
-
-#ifndef MAVLINK_STX
-#define MAVLINK_STX 254
-#endif
-
-#ifndef MAVLINK_ENDIAN
-#define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN
-#endif
-
-#ifndef MAVLINK_ALIGNED_FIELDS
-#define MAVLINK_ALIGNED_FIELDS 1
-#endif
-
-#ifndef MAVLINK_CRC_EXTRA
-#define MAVLINK_CRC_EXTRA 1
-#endif
-
-#include "version.h"
-#include "test.h"
-
-#endif // MAVLINK_H
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/mavlink_msg_test_types.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/mavlink_msg_test_types.h
deleted file mode 100644
index 2a3a89ff9..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/mavlink_msg_test_types.h
+++ /dev/null
@@ -1,610 +0,0 @@
-// MESSAGE TEST_TYPES PACKING
-
-#define MAVLINK_MSG_ID_TEST_TYPES 0
-
-typedef struct __mavlink_test_types_t
-{
- uint64_t u64; ///< uint64_t
- int64_t s64; ///< int64_t
- double d; ///< double
- uint64_t u64_array[3]; ///< uint64_t_array
- int64_t s64_array[3]; ///< int64_t_array
- double d_array[3]; ///< double_array
- uint32_t u32; ///< uint32_t
- int32_t s32; ///< int32_t
- float f; ///< float
- uint32_t u32_array[3]; ///< uint32_t_array
- int32_t s32_array[3]; ///< int32_t_array
- float f_array[3]; ///< float_array
- uint16_t u16; ///< uint16_t
- int16_t s16; ///< int16_t
- uint16_t u16_array[3]; ///< uint16_t_array
- int16_t s16_array[3]; ///< int16_t_array
- char c; ///< char
- char s[10]; ///< string
- uint8_t u8; ///< uint8_t
- int8_t s8; ///< int8_t
- uint8_t u8_array[3]; ///< uint8_t_array
- int8_t s8_array[3]; ///< int8_t_array
-} mavlink_test_types_t;
-
-#define MAVLINK_MSG_ID_TEST_TYPES_LEN 179
-#define MAVLINK_MSG_ID_0_LEN 179
-
-#define MAVLINK_MSG_TEST_TYPES_FIELD_U64_ARRAY_LEN 3
-#define MAVLINK_MSG_TEST_TYPES_FIELD_S64_ARRAY_LEN 3
-#define MAVLINK_MSG_TEST_TYPES_FIELD_D_ARRAY_LEN 3
-#define MAVLINK_MSG_TEST_TYPES_FIELD_U32_ARRAY_LEN 3
-#define MAVLINK_MSG_TEST_TYPES_FIELD_S32_ARRAY_LEN 3
-#define MAVLINK_MSG_TEST_TYPES_FIELD_F_ARRAY_LEN 3
-#define MAVLINK_MSG_TEST_TYPES_FIELD_U16_ARRAY_LEN 3
-#define MAVLINK_MSG_TEST_TYPES_FIELD_S16_ARRAY_LEN 3
-#define MAVLINK_MSG_TEST_TYPES_FIELD_S_LEN 10
-#define MAVLINK_MSG_TEST_TYPES_FIELD_U8_ARRAY_LEN 3
-#define MAVLINK_MSG_TEST_TYPES_FIELD_S8_ARRAY_LEN 3
-
-#define MAVLINK_MESSAGE_INFO_TEST_TYPES { \
- "TEST_TYPES", \
- 22, \
- { { "u64", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_test_types_t, u64) }, \
- { "s64", NULL, MAVLINK_TYPE_INT64_T, 0, 8, offsetof(mavlink_test_types_t, s64) }, \
- { "d", NULL, MAVLINK_TYPE_DOUBLE, 0, 16, offsetof(mavlink_test_types_t, d) }, \
- { "u64_array", NULL, MAVLINK_TYPE_UINT64_T, 3, 24, offsetof(mavlink_test_types_t, u64_array) }, \
- { "s64_array", NULL, MAVLINK_TYPE_INT64_T, 3, 48, offsetof(mavlink_test_types_t, s64_array) }, \
- { "d_array", NULL, MAVLINK_TYPE_DOUBLE, 3, 72, offsetof(mavlink_test_types_t, d_array) }, \
- { "u32", "0x%08x", MAVLINK_TYPE_UINT32_T, 0, 96, offsetof(mavlink_test_types_t, u32) }, \
- { "s32", NULL, MAVLINK_TYPE_INT32_T, 0, 100, offsetof(mavlink_test_types_t, s32) }, \
- { "f", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_test_types_t, f) }, \
- { "u32_array", NULL, MAVLINK_TYPE_UINT32_T, 3, 108, offsetof(mavlink_test_types_t, u32_array) }, \
- { "s32_array", NULL, MAVLINK_TYPE_INT32_T, 3, 120, offsetof(mavlink_test_types_t, s32_array) }, \
- { "f_array", NULL, MAVLINK_TYPE_FLOAT, 3, 132, offsetof(mavlink_test_types_t, f_array) }, \
- { "u16", NULL, MAVLINK_TYPE_UINT16_T, 0, 144, offsetof(mavlink_test_types_t, u16) }, \
- { "s16", NULL, MAVLINK_TYPE_INT16_T, 0, 146, offsetof(mavlink_test_types_t, s16) }, \
- { "u16_array", NULL, MAVLINK_TYPE_UINT16_T, 3, 148, offsetof(mavlink_test_types_t, u16_array) }, \
- { "s16_array", NULL, MAVLINK_TYPE_INT16_T, 3, 154, offsetof(mavlink_test_types_t, s16_array) }, \
- { "c", NULL, MAVLINK_TYPE_CHAR, 0, 160, offsetof(mavlink_test_types_t, c) }, \
- { "s", NULL, MAVLINK_TYPE_CHAR, 10, 161, offsetof(mavlink_test_types_t, s) }, \
- { "u8", NULL, MAVLINK_TYPE_UINT8_T, 0, 171, offsetof(mavlink_test_types_t, u8) }, \
- { "s8", NULL, MAVLINK_TYPE_INT8_T, 0, 172, offsetof(mavlink_test_types_t, s8) }, \
- { "u8_array", NULL, MAVLINK_TYPE_UINT8_T, 3, 173, offsetof(mavlink_test_types_t, u8_array) }, \
- { "s8_array", NULL, MAVLINK_TYPE_INT8_T, 3, 176, offsetof(mavlink_test_types_t, s8_array) }, \
- } \
-}
-
-
-/**
- * @brief Pack a test_types message
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param msg The MAVLink message to compress the data into
- *
- * @param c char
- * @param s string
- * @param u8 uint8_t
- * @param u16 uint16_t
- * @param u32 uint32_t
- * @param u64 uint64_t
- * @param s8 int8_t
- * @param s16 int16_t
- * @param s32 int32_t
- * @param s64 int64_t
- * @param f float
- * @param d double
- * @param u8_array uint8_t_array
- * @param u16_array uint16_t_array
- * @param u32_array uint32_t_array
- * @param u64_array uint64_t_array
- * @param s8_array int8_t_array
- * @param s16_array int16_t_array
- * @param s32_array int32_t_array
- * @param s64_array int64_t_array
- * @param f_array float_array
- * @param d_array double_array
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_test_types_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- char c, const char *s, uint8_t u8, uint16_t u16, uint32_t u32, uint64_t u64, int8_t s8, int16_t s16, int32_t s32, int64_t s64, float f, double d, const uint8_t *u8_array, const uint16_t *u16_array, const uint32_t *u32_array, const uint64_t *u64_array, const int8_t *s8_array, const int16_t *s16_array, const int32_t *s32_array, const int64_t *s64_array, const float *f_array, const double *d_array)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[179];
- _mav_put_uint64_t(buf, 0, u64);
- _mav_put_int64_t(buf, 8, s64);
- _mav_put_double(buf, 16, d);
- _mav_put_uint32_t(buf, 96, u32);
- _mav_put_int32_t(buf, 100, s32);
- _mav_put_float(buf, 104, f);
- _mav_put_uint16_t(buf, 144, u16);
- _mav_put_int16_t(buf, 146, s16);
- _mav_put_char(buf, 160, c);
- _mav_put_uint8_t(buf, 171, u8);
- _mav_put_int8_t(buf, 172, s8);
- _mav_put_uint64_t_array(buf, 24, u64_array, 3);
- _mav_put_int64_t_array(buf, 48, s64_array, 3);
- _mav_put_double_array(buf, 72, d_array, 3);
- _mav_put_uint32_t_array(buf, 108, u32_array, 3);
- _mav_put_int32_t_array(buf, 120, s32_array, 3);
- _mav_put_float_array(buf, 132, f_array, 3);
- _mav_put_uint16_t_array(buf, 148, u16_array, 3);
- _mav_put_int16_t_array(buf, 154, s16_array, 3);
- _mav_put_char_array(buf, 161, s, 10);
- _mav_put_uint8_t_array(buf, 173, u8_array, 3);
- _mav_put_int8_t_array(buf, 176, s8_array, 3);
- memcpy(_MAV_PAYLOAD(msg), buf, 179);
-#else
- mavlink_test_types_t packet;
- packet.u64 = u64;
- packet.s64 = s64;
- packet.d = d;
- packet.u32 = u32;
- packet.s32 = s32;
- packet.f = f;
- packet.u16 = u16;
- packet.s16 = s16;
- packet.c = c;
- packet.u8 = u8;
- packet.s8 = s8;
- mav_array_memcpy(packet.u64_array, u64_array, sizeof(uint64_t)*3);
- mav_array_memcpy(packet.s64_array, s64_array, sizeof(int64_t)*3);
- mav_array_memcpy(packet.d_array, d_array, sizeof(double)*3);
- mav_array_memcpy(packet.u32_array, u32_array, sizeof(uint32_t)*3);
- mav_array_memcpy(packet.s32_array, s32_array, sizeof(int32_t)*3);
- mav_array_memcpy(packet.f_array, f_array, sizeof(float)*3);
- mav_array_memcpy(packet.u16_array, u16_array, sizeof(uint16_t)*3);
- mav_array_memcpy(packet.s16_array, s16_array, sizeof(int16_t)*3);
- mav_array_memcpy(packet.s, s, sizeof(char)*10);
- mav_array_memcpy(packet.u8_array, u8_array, sizeof(uint8_t)*3);
- mav_array_memcpy(packet.s8_array, s8_array, sizeof(int8_t)*3);
- memcpy(_MAV_PAYLOAD(msg), &packet, 179);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_TEST_TYPES;
- return mavlink_finalize_message(msg, system_id, component_id, 179, 103);
-}
-
-/**
- * @brief Pack a test_types message on a channel
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
- * @param msg The MAVLink message to compress the data into
- * @param c char
- * @param s string
- * @param u8 uint8_t
- * @param u16 uint16_t
- * @param u32 uint32_t
- * @param u64 uint64_t
- * @param s8 int8_t
- * @param s16 int16_t
- * @param s32 int32_t
- * @param s64 int64_t
- * @param f float
- * @param d double
- * @param u8_array uint8_t_array
- * @param u16_array uint16_t_array
- * @param u32_array uint32_t_array
- * @param u64_array uint64_t_array
- * @param s8_array int8_t_array
- * @param s16_array int16_t_array
- * @param s32_array int32_t_array
- * @param s64_array int64_t_array
- * @param f_array float_array
- * @param d_array double_array
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_test_types_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- char c,const char *s,uint8_t u8,uint16_t u16,uint32_t u32,uint64_t u64,int8_t s8,int16_t s16,int32_t s32,int64_t s64,float f,double d,const uint8_t *u8_array,const uint16_t *u16_array,const uint32_t *u32_array,const uint64_t *u64_array,const int8_t *s8_array,const int16_t *s16_array,const int32_t *s32_array,const int64_t *s64_array,const float *f_array,const double *d_array)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[179];
- _mav_put_uint64_t(buf, 0, u64);
- _mav_put_int64_t(buf, 8, s64);
- _mav_put_double(buf, 16, d);
- _mav_put_uint32_t(buf, 96, u32);
- _mav_put_int32_t(buf, 100, s32);
- _mav_put_float(buf, 104, f);
- _mav_put_uint16_t(buf, 144, u16);
- _mav_put_int16_t(buf, 146, s16);
- _mav_put_char(buf, 160, c);
- _mav_put_uint8_t(buf, 171, u8);
- _mav_put_int8_t(buf, 172, s8);
- _mav_put_uint64_t_array(buf, 24, u64_array, 3);
- _mav_put_int64_t_array(buf, 48, s64_array, 3);
- _mav_put_double_array(buf, 72, d_array, 3);
- _mav_put_uint32_t_array(buf, 108, u32_array, 3);
- _mav_put_int32_t_array(buf, 120, s32_array, 3);
- _mav_put_float_array(buf, 132, f_array, 3);
- _mav_put_uint16_t_array(buf, 148, u16_array, 3);
- _mav_put_int16_t_array(buf, 154, s16_array, 3);
- _mav_put_char_array(buf, 161, s, 10);
- _mav_put_uint8_t_array(buf, 173, u8_array, 3);
- _mav_put_int8_t_array(buf, 176, s8_array, 3);
- memcpy(_MAV_PAYLOAD(msg), buf, 179);
-#else
- mavlink_test_types_t packet;
- packet.u64 = u64;
- packet.s64 = s64;
- packet.d = d;
- packet.u32 = u32;
- packet.s32 = s32;
- packet.f = f;
- packet.u16 = u16;
- packet.s16 = s16;
- packet.c = c;
- packet.u8 = u8;
- packet.s8 = s8;
- mav_array_memcpy(packet.u64_array, u64_array, sizeof(uint64_t)*3);
- mav_array_memcpy(packet.s64_array, s64_array, sizeof(int64_t)*3);
- mav_array_memcpy(packet.d_array, d_array, sizeof(double)*3);
- mav_array_memcpy(packet.u32_array, u32_array, sizeof(uint32_t)*3);
- mav_array_memcpy(packet.s32_array, s32_array, sizeof(int32_t)*3);
- mav_array_memcpy(packet.f_array, f_array, sizeof(float)*3);
- mav_array_memcpy(packet.u16_array, u16_array, sizeof(uint16_t)*3);
- mav_array_memcpy(packet.s16_array, s16_array, sizeof(int16_t)*3);
- mav_array_memcpy(packet.s, s, sizeof(char)*10);
- mav_array_memcpy(packet.u8_array, u8_array, sizeof(uint8_t)*3);
- mav_array_memcpy(packet.s8_array, s8_array, sizeof(int8_t)*3);
- memcpy(_MAV_PAYLOAD(msg), &packet, 179);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_TEST_TYPES;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 179, 103);
-}
-
-/**
- * @brief Encode a test_types struct into a message
- *
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param msg The MAVLink message to compress the data into
- * @param test_types C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_test_types_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_test_types_t* test_types)
-{
- return mavlink_msg_test_types_pack(system_id, component_id, msg, test_types->c, test_types->s, test_types->u8, test_types->u16, test_types->u32, test_types->u64, test_types->s8, test_types->s16, test_types->s32, test_types->s64, test_types->f, test_types->d, test_types->u8_array, test_types->u16_array, test_types->u32_array, test_types->u64_array, test_types->s8_array, test_types->s16_array, test_types->s32_array, test_types->s64_array, test_types->f_array, test_types->d_array);
-}
-
-/**
- * @brief Send a test_types message
- * @param chan MAVLink channel to send the message
- *
- * @param c char
- * @param s string
- * @param u8 uint8_t
- * @param u16 uint16_t
- * @param u32 uint32_t
- * @param u64 uint64_t
- * @param s8 int8_t
- * @param s16 int16_t
- * @param s32 int32_t
- * @param s64 int64_t
- * @param f float
- * @param d double
- * @param u8_array uint8_t_array
- * @param u16_array uint16_t_array
- * @param u32_array uint32_t_array
- * @param u64_array uint64_t_array
- * @param s8_array int8_t_array
- * @param s16_array int16_t_array
- * @param s32_array int32_t_array
- * @param s64_array int64_t_array
- * @param f_array float_array
- * @param d_array double_array
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_test_types_send(mavlink_channel_t chan, char c, const char *s, uint8_t u8, uint16_t u16, uint32_t u32, uint64_t u64, int8_t s8, int16_t s16, int32_t s32, int64_t s64, float f, double d, const uint8_t *u8_array, const uint16_t *u16_array, const uint32_t *u32_array, const uint64_t *u64_array, const int8_t *s8_array, const int16_t *s16_array, const int32_t *s32_array, const int64_t *s64_array, const float *f_array, const double *d_array)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[179];
- _mav_put_uint64_t(buf, 0, u64);
- _mav_put_int64_t(buf, 8, s64);
- _mav_put_double(buf, 16, d);
- _mav_put_uint32_t(buf, 96, u32);
- _mav_put_int32_t(buf, 100, s32);
- _mav_put_float(buf, 104, f);
- _mav_put_uint16_t(buf, 144, u16);
- _mav_put_int16_t(buf, 146, s16);
- _mav_put_char(buf, 160, c);
- _mav_put_uint8_t(buf, 171, u8);
- _mav_put_int8_t(buf, 172, s8);
- _mav_put_uint64_t_array(buf, 24, u64_array, 3);
- _mav_put_int64_t_array(buf, 48, s64_array, 3);
- _mav_put_double_array(buf, 72, d_array, 3);
- _mav_put_uint32_t_array(buf, 108, u32_array, 3);
- _mav_put_int32_t_array(buf, 120, s32_array, 3);
- _mav_put_float_array(buf, 132, f_array, 3);
- _mav_put_uint16_t_array(buf, 148, u16_array, 3);
- _mav_put_int16_t_array(buf, 154, s16_array, 3);
- _mav_put_char_array(buf, 161, s, 10);
- _mav_put_uint8_t_array(buf, 173, u8_array, 3);
- _mav_put_int8_t_array(buf, 176, s8_array, 3);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TYPES, buf, 179, 103);
-#else
- mavlink_test_types_t packet;
- packet.u64 = u64;
- packet.s64 = s64;
- packet.d = d;
- packet.u32 = u32;
- packet.s32 = s32;
- packet.f = f;
- packet.u16 = u16;
- packet.s16 = s16;
- packet.c = c;
- packet.u8 = u8;
- packet.s8 = s8;
- mav_array_memcpy(packet.u64_array, u64_array, sizeof(uint64_t)*3);
- mav_array_memcpy(packet.s64_array, s64_array, sizeof(int64_t)*3);
- mav_array_memcpy(packet.d_array, d_array, sizeof(double)*3);
- mav_array_memcpy(packet.u32_array, u32_array, sizeof(uint32_t)*3);
- mav_array_memcpy(packet.s32_array, s32_array, sizeof(int32_t)*3);
- mav_array_memcpy(packet.f_array, f_array, sizeof(float)*3);
- mav_array_memcpy(packet.u16_array, u16_array, sizeof(uint16_t)*3);
- mav_array_memcpy(packet.s16_array, s16_array, sizeof(int16_t)*3);
- mav_array_memcpy(packet.s, s, sizeof(char)*10);
- mav_array_memcpy(packet.u8_array, u8_array, sizeof(uint8_t)*3);
- mav_array_memcpy(packet.s8_array, s8_array, sizeof(int8_t)*3);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TYPES, (const char *)&packet, 179, 103);
-#endif
-}
-
-#endif
-
-// MESSAGE TEST_TYPES UNPACKING
-
-
-/**
- * @brief Get field c from test_types message
- *
- * @return char
- */
-static inline char mavlink_msg_test_types_get_c(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_char(msg, 160);
-}
-
-/**
- * @brief Get field s from test_types message
- *
- * @return string
- */
-static inline uint16_t mavlink_msg_test_types_get_s(const mavlink_message_t* msg, char *s)
-{
- return _MAV_RETURN_char_array(msg, s, 10, 161);
-}
-
-/**
- * @brief Get field u8 from test_types message
- *
- * @return uint8_t
- */
-static inline uint8_t mavlink_msg_test_types_get_u8(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 171);
-}
-
-/**
- * @brief Get field u16 from test_types message
- *
- * @return uint16_t
- */
-static inline uint16_t mavlink_msg_test_types_get_u16(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 144);
-}
-
-/**
- * @brief Get field u32 from test_types message
- *
- * @return uint32_t
- */
-static inline uint32_t mavlink_msg_test_types_get_u32(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint32_t(msg, 96);
-}
-
-/**
- * @brief Get field u64 from test_types message
- *
- * @return uint64_t
- */
-static inline uint64_t mavlink_msg_test_types_get_u64(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field s8 from test_types message
- *
- * @return int8_t
- */
-static inline int8_t mavlink_msg_test_types_get_s8(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int8_t(msg, 172);
-}
-
-/**
- * @brief Get field s16 from test_types message
- *
- * @return int16_t
- */
-static inline int16_t mavlink_msg_test_types_get_s16(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int16_t(msg, 146);
-}
-
-/**
- * @brief Get field s32 from test_types message
- *
- * @return int32_t
- */
-static inline int32_t mavlink_msg_test_types_get_s32(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 100);
-}
-
-/**
- * @brief Get field s64 from test_types message
- *
- * @return int64_t
- */
-static inline int64_t mavlink_msg_test_types_get_s64(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int64_t(msg, 8);
-}
-
-/**
- * @brief Get field f from test_types message
- *
- * @return float
- */
-static inline float mavlink_msg_test_types_get_f(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 104);
-}
-
-/**
- * @brief Get field d from test_types message
- *
- * @return double
- */
-static inline double mavlink_msg_test_types_get_d(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_double(msg, 16);
-}
-
-/**
- * @brief Get field u8_array from test_types message
- *
- * @return uint8_t_array
- */
-static inline uint16_t mavlink_msg_test_types_get_u8_array(const mavlink_message_t* msg, uint8_t *u8_array)
-{
- return _MAV_RETURN_uint8_t_array(msg, u8_array, 3, 173);
-}
-
-/**
- * @brief Get field u16_array from test_types message
- *
- * @return uint16_t_array
- */
-static inline uint16_t mavlink_msg_test_types_get_u16_array(const mavlink_message_t* msg, uint16_t *u16_array)
-{
- return _MAV_RETURN_uint16_t_array(msg, u16_array, 3, 148);
-}
-
-/**
- * @brief Get field u32_array from test_types message
- *
- * @return uint32_t_array
- */
-static inline uint16_t mavlink_msg_test_types_get_u32_array(const mavlink_message_t* msg, uint32_t *u32_array)
-{
- return _MAV_RETURN_uint32_t_array(msg, u32_array, 3, 108);
-}
-
-/**
- * @brief Get field u64_array from test_types message
- *
- * @return uint64_t_array
- */
-static inline uint16_t mavlink_msg_test_types_get_u64_array(const mavlink_message_t* msg, uint64_t *u64_array)
-{
- return _MAV_RETURN_uint64_t_array(msg, u64_array, 3, 24);
-}
-
-/**
- * @brief Get field s8_array from test_types message
- *
- * @return int8_t_array
- */
-static inline uint16_t mavlink_msg_test_types_get_s8_array(const mavlink_message_t* msg, int8_t *s8_array)
-{
- return _MAV_RETURN_int8_t_array(msg, s8_array, 3, 176);
-}
-
-/**
- * @brief Get field s16_array from test_types message
- *
- * @return int16_t_array
- */
-static inline uint16_t mavlink_msg_test_types_get_s16_array(const mavlink_message_t* msg, int16_t *s16_array)
-{
- return _MAV_RETURN_int16_t_array(msg, s16_array, 3, 154);
-}
-
-/**
- * @brief Get field s32_array from test_types message
- *
- * @return int32_t_array
- */
-static inline uint16_t mavlink_msg_test_types_get_s32_array(const mavlink_message_t* msg, int32_t *s32_array)
-{
- return _MAV_RETURN_int32_t_array(msg, s32_array, 3, 120);
-}
-
-/**
- * @brief Get field s64_array from test_types message
- *
- * @return int64_t_array
- */
-static inline uint16_t mavlink_msg_test_types_get_s64_array(const mavlink_message_t* msg, int64_t *s64_array)
-{
- return _MAV_RETURN_int64_t_array(msg, s64_array, 3, 48);
-}
-
-/**
- * @brief Get field f_array from test_types message
- *
- * @return float_array
- */
-static inline uint16_t mavlink_msg_test_types_get_f_array(const mavlink_message_t* msg, float *f_array)
-{
- return _MAV_RETURN_float_array(msg, f_array, 3, 132);
-}
-
-/**
- * @brief Get field d_array from test_types message
- *
- * @return double_array
- */
-static inline uint16_t mavlink_msg_test_types_get_d_array(const mavlink_message_t* msg, double *d_array)
-{
- return _MAV_RETURN_double_array(msg, d_array, 3, 72);
-}
-
-/**
- * @brief Decode a test_types message into a struct
- *
- * @param msg The message to decode
- * @param test_types C-struct to decode the message contents into
- */
-static inline void mavlink_msg_test_types_decode(const mavlink_message_t* msg, mavlink_test_types_t* test_types)
-{
-#if MAVLINK_NEED_BYTE_SWAP
- test_types->u64 = mavlink_msg_test_types_get_u64(msg);
- test_types->s64 = mavlink_msg_test_types_get_s64(msg);
- test_types->d = mavlink_msg_test_types_get_d(msg);
- mavlink_msg_test_types_get_u64_array(msg, test_types->u64_array);
- mavlink_msg_test_types_get_s64_array(msg, test_types->s64_array);
- mavlink_msg_test_types_get_d_array(msg, test_types->d_array);
- test_types->u32 = mavlink_msg_test_types_get_u32(msg);
- test_types->s32 = mavlink_msg_test_types_get_s32(msg);
- test_types->f = mavlink_msg_test_types_get_f(msg);
- mavlink_msg_test_types_get_u32_array(msg, test_types->u32_array);
- mavlink_msg_test_types_get_s32_array(msg, test_types->s32_array);
- mavlink_msg_test_types_get_f_array(msg, test_types->f_array);
- test_types->u16 = mavlink_msg_test_types_get_u16(msg);
- test_types->s16 = mavlink_msg_test_types_get_s16(msg);
- mavlink_msg_test_types_get_u16_array(msg, test_types->u16_array);
- mavlink_msg_test_types_get_s16_array(msg, test_types->s16_array);
- test_types->c = mavlink_msg_test_types_get_c(msg);
- mavlink_msg_test_types_get_s(msg, test_types->s);
- test_types->u8 = mavlink_msg_test_types_get_u8(msg);
- test_types->s8 = mavlink_msg_test_types_get_s8(msg);
- mavlink_msg_test_types_get_u8_array(msg, test_types->u8_array);
- mavlink_msg_test_types_get_s8_array(msg, test_types->s8_array);
-#else
- memcpy(test_types, _MAV_PAYLOAD(msg), 179);
-#endif
-}
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/test.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/test.h
deleted file mode 100644
index 4dc04f889..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/test.h
+++ /dev/null
@@ -1,53 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol generated from test.xml
- * @see http://qgroundcontrol.org/mavlink/
- */
-#ifndef TEST_H
-#define TEST_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-// MESSAGE LENGTHS AND CRCS
-
-#ifndef MAVLINK_MESSAGE_LENGTHS
-#define MAVLINK_MESSAGE_LENGTHS {179, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
-#endif
-
-#ifndef MAVLINK_MESSAGE_CRCS
-#define MAVLINK_MESSAGE_CRCS {103, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
-#endif
-
-#ifndef MAVLINK_MESSAGE_INFO
-#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_TEST_TYPES, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}}
-#endif
-
-#include "../protocol.h"
-
-#define MAVLINK_ENABLED_TEST
-
-
-
-// MAVLINK VERSION
-
-#ifndef MAVLINK_VERSION
-#define MAVLINK_VERSION 3
-#endif
-
-#if (MAVLINK_VERSION == 0)
-#undef MAVLINK_VERSION
-#define MAVLINK_VERSION 3
-#endif
-
-// ENUM DEFINITIONS
-
-
-
-// MESSAGE DEFINITIONS
-#include "./mavlink_msg_test_types.h"
-
-#ifdef __cplusplus
-}
-#endif // __cplusplus
-#endif // TEST_H
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/testsuite.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/testsuite.h
deleted file mode 100644
index 658e1ae07..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/testsuite.h
+++ /dev/null
@@ -1,120 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol testsuite generated from test.xml
- * @see http://qgroundcontrol.org/mavlink/
- */
-#ifndef TEST_TESTSUITE_H
-#define TEST_TESTSUITE_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-#ifndef MAVLINK_TEST_ALL
-#define MAVLINK_TEST_ALL
-
-static void mavlink_test_test(uint8_t, uint8_t, mavlink_message_t *last_msg);
-
-static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
-{
-
- mavlink_test_test(system_id, component_id, last_msg);
-}
-#endif
-
-
-
-
-static void mavlink_test_test_types(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
-{
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_test_types_t packet_in = {
- 93372036854775807ULL,
- 93372036854776311LL,
- 235.0,
- { 93372036854777319, 93372036854777320, 93372036854777321 },
- { 93372036854778831, 93372036854778832, 93372036854778833 },
- { 627.0, 628.0, 629.0 },
- 963502456,
- 963502664,
- 745.0,
- { 963503080, 963503081, 963503082 },
- { 963503704, 963503705, 963503706 },
- { 941.0, 942.0, 943.0 },
- 24723,
- 24827,
- { 24931, 24932, 24933 },
- { 25243, 25244, 25245 },
- 'E',
- "FGHIJKLMN",
- 198,
- 9,
- { 76, 77, 78 },
- { 21, 22, 23 },
- };
- mavlink_test_types_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.u64 = packet_in.u64;
- packet1.s64 = packet_in.s64;
- packet1.d = packet_in.d;
- packet1.u32 = packet_in.u32;
- packet1.s32 = packet_in.s32;
- packet1.f = packet_in.f;
- packet1.u16 = packet_in.u16;
- packet1.s16 = packet_in.s16;
- packet1.c = packet_in.c;
- packet1.u8 = packet_in.u8;
- packet1.s8 = packet_in.s8;
-
- mav_array_memcpy(packet1.u64_array, packet_in.u64_array, sizeof(uint64_t)*3);
- mav_array_memcpy(packet1.s64_array, packet_in.s64_array, sizeof(int64_t)*3);
- mav_array_memcpy(packet1.d_array, packet_in.d_array, sizeof(double)*3);
- mav_array_memcpy(packet1.u32_array, packet_in.u32_array, sizeof(uint32_t)*3);
- mav_array_memcpy(packet1.s32_array, packet_in.s32_array, sizeof(int32_t)*3);
- mav_array_memcpy(packet1.f_array, packet_in.f_array, sizeof(float)*3);
- mav_array_memcpy(packet1.u16_array, packet_in.u16_array, sizeof(uint16_t)*3);
- mav_array_memcpy(packet1.s16_array, packet_in.s16_array, sizeof(int16_t)*3);
- mav_array_memcpy(packet1.s, packet_in.s, sizeof(char)*10);
- mav_array_memcpy(packet1.u8_array, packet_in.u8_array, sizeof(uint8_t)*3);
- mav_array_memcpy(packet1.s8_array, packet_in.s8_array, sizeof(int8_t)*3);
-
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_test_types_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_test_types_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_test_types_pack(system_id, component_id, &msg , packet1.c , packet1.s , packet1.u8 , packet1.u16 , packet1.u32 , packet1.u64 , packet1.s8 , packet1.s16 , packet1.s32 , packet1.s64 , packet1.f , packet1.d , packet1.u8_array , packet1.u16_array , packet1.u32_array , packet1.u64_array , packet1.s8_array , packet1.s16_array , packet1.s32_array , packet1.s64_array , packet1.f_array , packet1.d_array );
- mavlink_msg_test_types_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_test_types_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.c , packet1.s , packet1.u8 , packet1.u16 , packet1.u32 , packet1.u64 , packet1.s8 , packet1.s16 , packet1.s32 , packet1.s64 , packet1.f , packet1.d , packet1.u8_array , packet1.u16_array , packet1.u32_array , packet1.u64_array , packet1.s8_array , packet1.s16_array , packet1.s32_array , packet1.s64_array , packet1.f_array , packet1.d_array );
- mavlink_msg_test_types_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_to_send_buffer(buffer, &msg);
- for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_test_types_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_test_types_send(MAVLINK_COMM_1 , packet1.c , packet1.s , packet1.u8 , packet1.u16 , packet1.u32 , packet1.u64 , packet1.s8 , packet1.s16 , packet1.s32 , packet1.s64 , packet1.f , packet1.d , packet1.u8_array , packet1.u16_array , packet1.u32_array , packet1.u64_array , packet1.s8_array , packet1.s16_array , packet1.s32_array , packet1.s64_array , packet1.f_array , packet1.d_array );
- mavlink_msg_test_types_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_test(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
-{
- mavlink_test_test_types(system_id, component_id, last_msg);
-}
-
-#ifdef __cplusplus
-}
-#endif // __cplusplus
-#endif // TEST_TESTSUITE_H
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/version.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/version.h
deleted file mode 100644
index 867641e21..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/version.h
+++ /dev/null
@@ -1,12 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol built from test.xml
- * @see http://pixhawk.ethz.ch/software/mavlink
- */
-#ifndef MAVLINK_VERSION_H
-#define MAVLINK_VERSION_H
-
-#define MAVLINK_BUILD_DATE "Thu Mar 1 15:11:58 2012"
-#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
-#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 179
-
-#endif // MAVLINK_VERSION_H
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/src_v1.0/pixhawk/pixhawk.pb.cc b/mavlink/share/pyshared/pymavlink/generator/C/src_v1.0/pixhawk/pixhawk.pb.cc
deleted file mode 100644
index e984f512a..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/src_v1.0/pixhawk/pixhawk.pb.cc
+++ /dev/null
@@ -1,5431 +0,0 @@
-// Generated by the protocol buffer compiler. DO NOT EDIT!
-
-#define INTERNAL_SUPPRESS_PROTOBUF_FIELD_DEPRECATION
-#include "pixhawk.pb.h"
-
-#include <algorithm>
-
-#include <google/protobuf/stubs/once.h>
-#include <google/protobuf/io/coded_stream.h>
-#include <google/protobuf/wire_format_lite_inl.h>
-#include <google/protobuf/descriptor.h>
-#include <google/protobuf/reflection_ops.h>
-#include <google/protobuf/wire_format.h>
-// @@protoc_insertion_point(includes)
-
-namespace px {
-
-namespace {
-
-const ::google::protobuf::Descriptor* HeaderInfo_descriptor_ = NULL;
-const ::google::protobuf::internal::GeneratedMessageReflection*
- HeaderInfo_reflection_ = NULL;
-const ::google::protobuf::Descriptor* GLOverlay_descriptor_ = NULL;
-const ::google::protobuf::internal::GeneratedMessageReflection*
- GLOverlay_reflection_ = NULL;
-const ::google::protobuf::EnumDescriptor* GLOverlay_CoordinateFrameType_descriptor_ = NULL;
-const ::google::protobuf::EnumDescriptor* GLOverlay_Mode_descriptor_ = NULL;
-const ::google::protobuf::EnumDescriptor* GLOverlay_Identifier_descriptor_ = NULL;
-const ::google::protobuf::Descriptor* Obstacle_descriptor_ = NULL;
-const ::google::protobuf::internal::GeneratedMessageReflection*
- Obstacle_reflection_ = NULL;
-const ::google::protobuf::Descriptor* ObstacleList_descriptor_ = NULL;
-const ::google::protobuf::internal::GeneratedMessageReflection*
- ObstacleList_reflection_ = NULL;
-const ::google::protobuf::Descriptor* ObstacleMap_descriptor_ = NULL;
-const ::google::protobuf::internal::GeneratedMessageReflection*
- ObstacleMap_reflection_ = NULL;
-const ::google::protobuf::Descriptor* Path_descriptor_ = NULL;
-const ::google::protobuf::internal::GeneratedMessageReflection*
- Path_reflection_ = NULL;
-const ::google::protobuf::Descriptor* PointCloudXYZI_descriptor_ = NULL;
-const ::google::protobuf::internal::GeneratedMessageReflection*
- PointCloudXYZI_reflection_ = NULL;
-const ::google::protobuf::Descriptor* PointCloudXYZI_PointXYZI_descriptor_ = NULL;
-const ::google::protobuf::internal::GeneratedMessageReflection*
- PointCloudXYZI_PointXYZI_reflection_ = NULL;
-const ::google::protobuf::Descriptor* PointCloudXYZRGB_descriptor_ = NULL;
-const ::google::protobuf::internal::GeneratedMessageReflection*
- PointCloudXYZRGB_reflection_ = NULL;
-const ::google::protobuf::Descriptor* PointCloudXYZRGB_PointXYZRGB_descriptor_ = NULL;
-const ::google::protobuf::internal::GeneratedMessageReflection*
- PointCloudXYZRGB_PointXYZRGB_reflection_ = NULL;
-const ::google::protobuf::Descriptor* RGBDImage_descriptor_ = NULL;
-const ::google::protobuf::internal::GeneratedMessageReflection*
- RGBDImage_reflection_ = NULL;
-const ::google::protobuf::Descriptor* Waypoint_descriptor_ = NULL;
-const ::google::protobuf::internal::GeneratedMessageReflection*
- Waypoint_reflection_ = NULL;
-
-} // namespace
-
-
-void protobuf_AssignDesc_pixhawk_2eproto() {
- protobuf_AddDesc_pixhawk_2eproto();
- const ::google::protobuf::FileDescriptor* file =
- ::google::protobuf::DescriptorPool::generated_pool()->FindFileByName(
- "pixhawk.proto");
- GOOGLE_CHECK(file != NULL);
- HeaderInfo_descriptor_ = file->message_type(0);
- static const int HeaderInfo_offsets_[3] = {
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(HeaderInfo, source_sysid_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(HeaderInfo, source_compid_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(HeaderInfo, timestamp_),
- };
- HeaderInfo_reflection_ =
- new ::google::protobuf::internal::GeneratedMessageReflection(
- HeaderInfo_descriptor_,
- HeaderInfo::default_instance_,
- HeaderInfo_offsets_,
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(HeaderInfo, _has_bits_[0]),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(HeaderInfo, _unknown_fields_),
- -1,
- ::google::protobuf::DescriptorPool::generated_pool(),
- ::google::protobuf::MessageFactory::generated_factory(),
- sizeof(HeaderInfo));
- GLOverlay_descriptor_ = file->message_type(1);
- static const int GLOverlay_offsets_[7] = {
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, header_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, name_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, coordinateframetype_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, origin_x_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, origin_y_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, origin_z_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, data_),
- };
- GLOverlay_reflection_ =
- new ::google::protobuf::internal::GeneratedMessageReflection(
- GLOverlay_descriptor_,
- GLOverlay::default_instance_,
- GLOverlay_offsets_,
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, _has_bits_[0]),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, _unknown_fields_),
- -1,
- ::google::protobuf::DescriptorPool::generated_pool(),
- ::google::protobuf::MessageFactory::generated_factory(),
- sizeof(GLOverlay));
- GLOverlay_CoordinateFrameType_descriptor_ = GLOverlay_descriptor_->enum_type(0);
- GLOverlay_Mode_descriptor_ = GLOverlay_descriptor_->enum_type(1);
- GLOverlay_Identifier_descriptor_ = GLOverlay_descriptor_->enum_type(2);
- Obstacle_descriptor_ = file->message_type(2);
- static const int Obstacle_offsets_[6] = {
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, x_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, y_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, z_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, length_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, width_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, height_),
- };
- Obstacle_reflection_ =
- new ::google::protobuf::internal::GeneratedMessageReflection(
- Obstacle_descriptor_,
- Obstacle::default_instance_,
- Obstacle_offsets_,
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, _has_bits_[0]),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, _unknown_fields_),
- -1,
- ::google::protobuf::DescriptorPool::generated_pool(),
- ::google::protobuf::MessageFactory::generated_factory(),
- sizeof(Obstacle));
- ObstacleList_descriptor_ = file->message_type(3);
- static const int ObstacleList_offsets_[2] = {
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleList, header_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleList, obstacles_),
- };
- ObstacleList_reflection_ =
- new ::google::protobuf::internal::GeneratedMessageReflection(
- ObstacleList_descriptor_,
- ObstacleList::default_instance_,
- ObstacleList_offsets_,
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleList, _has_bits_[0]),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleList, _unknown_fields_),
- -1,
- ::google::protobuf::DescriptorPool::generated_pool(),
- ::google::protobuf::MessageFactory::generated_factory(),
- sizeof(ObstacleList));
- ObstacleMap_descriptor_ = file->message_type(4);
- static const int ObstacleMap_offsets_[10] = {
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, header_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, type_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, resolution_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, rows_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, cols_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, mapr0_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, mapc0_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, arrayr0_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, arrayc0_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, data_),
- };
- ObstacleMap_reflection_ =
- new ::google::protobuf::internal::GeneratedMessageReflection(
- ObstacleMap_descriptor_,
- ObstacleMap::default_instance_,
- ObstacleMap_offsets_,
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, _has_bits_[0]),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, _unknown_fields_),
- -1,
- ::google::protobuf::DescriptorPool::generated_pool(),
- ::google::protobuf::MessageFactory::generated_factory(),
- sizeof(ObstacleMap));
- Path_descriptor_ = file->message_type(5);
- static const int Path_offsets_[2] = {
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Path, header_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Path, waypoints_),
- };
- Path_reflection_ =
- new ::google::protobuf::internal::GeneratedMessageReflection(
- Path_descriptor_,
- Path::default_instance_,
- Path_offsets_,
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Path, _has_bits_[0]),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Path, _unknown_fields_),
- -1,
- ::google::protobuf::DescriptorPool::generated_pool(),
- ::google::protobuf::MessageFactory::generated_factory(),
- sizeof(Path));
- PointCloudXYZI_descriptor_ = file->message_type(6);
- static const int PointCloudXYZI_offsets_[2] = {
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI, header_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI, points_),
- };
- PointCloudXYZI_reflection_ =
- new ::google::protobuf::internal::GeneratedMessageReflection(
- PointCloudXYZI_descriptor_,
- PointCloudXYZI::default_instance_,
- PointCloudXYZI_offsets_,
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI, _has_bits_[0]),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI, _unknown_fields_),
- -1,
- ::google::protobuf::DescriptorPool::generated_pool(),
- ::google::protobuf::MessageFactory::generated_factory(),
- sizeof(PointCloudXYZI));
- PointCloudXYZI_PointXYZI_descriptor_ = PointCloudXYZI_descriptor_->nested_type(0);
- static const int PointCloudXYZI_PointXYZI_offsets_[4] = {
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI_PointXYZI, x_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI_PointXYZI, y_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI_PointXYZI, z_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI_PointXYZI, intensity_),
- };
- PointCloudXYZI_PointXYZI_reflection_ =
- new ::google::protobuf::internal::GeneratedMessageReflection(
- PointCloudXYZI_PointXYZI_descriptor_,
- PointCloudXYZI_PointXYZI::default_instance_,
- PointCloudXYZI_PointXYZI_offsets_,
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI_PointXYZI, _has_bits_[0]),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI_PointXYZI, _unknown_fields_),
- -1,
- ::google::protobuf::DescriptorPool::generated_pool(),
- ::google::protobuf::MessageFactory::generated_factory(),
- sizeof(PointCloudXYZI_PointXYZI));
- PointCloudXYZRGB_descriptor_ = file->message_type(7);
- static const int PointCloudXYZRGB_offsets_[2] = {
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB, header_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB, points_),
- };
- PointCloudXYZRGB_reflection_ =
- new ::google::protobuf::internal::GeneratedMessageReflection(
- PointCloudXYZRGB_descriptor_,
- PointCloudXYZRGB::default_instance_,
- PointCloudXYZRGB_offsets_,
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB, _has_bits_[0]),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB, _unknown_fields_),
- -1,
- ::google::protobuf::DescriptorPool::generated_pool(),
- ::google::protobuf::MessageFactory::generated_factory(),
- sizeof(PointCloudXYZRGB));
- PointCloudXYZRGB_PointXYZRGB_descriptor_ = PointCloudXYZRGB_descriptor_->nested_type(0);
- static const int PointCloudXYZRGB_PointXYZRGB_offsets_[4] = {
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB_PointXYZRGB, x_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB_PointXYZRGB, y_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB_PointXYZRGB, z_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB_PointXYZRGB, rgb_),
- };
- PointCloudXYZRGB_PointXYZRGB_reflection_ =
- new ::google::protobuf::internal::GeneratedMessageReflection(
- PointCloudXYZRGB_PointXYZRGB_descriptor_,
- PointCloudXYZRGB_PointXYZRGB::default_instance_,
- PointCloudXYZRGB_PointXYZRGB_offsets_,
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB_PointXYZRGB, _has_bits_[0]),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB_PointXYZRGB, _unknown_fields_),
- -1,
- ::google::protobuf::DescriptorPool::generated_pool(),
- ::google::protobuf::MessageFactory::generated_factory(),
- sizeof(PointCloudXYZRGB_PointXYZRGB));
- RGBDImage_descriptor_ = file->message_type(8);
- static const int RGBDImage_offsets_[21] = {
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, header_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, cols_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, rows_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, step1_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, type1_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, imagedata1_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, step2_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, type2_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, imagedata2_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, camera_config_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, camera_type_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, roll_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, pitch_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, yaw_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, lon_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, lat_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, alt_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, ground_x_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, ground_y_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, ground_z_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, camera_matrix_),
- };
- RGBDImage_reflection_ =
- new ::google::protobuf::internal::GeneratedMessageReflection(
- RGBDImage_descriptor_,
- RGBDImage::default_instance_,
- RGBDImage_offsets_,
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, _has_bits_[0]),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, _unknown_fields_),
- -1,
- ::google::protobuf::DescriptorPool::generated_pool(),
- ::google::protobuf::MessageFactory::generated_factory(),
- sizeof(RGBDImage));
- Waypoint_descriptor_ = file->message_type(9);
- static const int Waypoint_offsets_[6] = {
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, x_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, y_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, z_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, roll_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, pitch_),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, yaw_),
- };
- Waypoint_reflection_ =
- new ::google::protobuf::internal::GeneratedMessageReflection(
- Waypoint_descriptor_,
- Waypoint::default_instance_,
- Waypoint_offsets_,
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, _has_bits_[0]),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, _unknown_fields_),
- -1,
- ::google::protobuf::DescriptorPool::generated_pool(),
- ::google::protobuf::MessageFactory::generated_factory(),
- sizeof(Waypoint));
-}
-
-namespace {
-
-GOOGLE_PROTOBUF_DECLARE_ONCE(protobuf_AssignDescriptors_once_);
-inline void protobuf_AssignDescriptorsOnce() {
- ::google::protobuf::GoogleOnceInit(&protobuf_AssignDescriptors_once_,
- &protobuf_AssignDesc_pixhawk_2eproto);
-}
-
-void protobuf_RegisterTypes(const ::std::string&) {
- protobuf_AssignDescriptorsOnce();
- ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage(
- HeaderInfo_descriptor_, &HeaderInfo::default_instance());
- ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage(
- GLOverlay_descriptor_, &GLOverlay::default_instance());
- ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage(
- Obstacle_descriptor_, &Obstacle::default_instance());
- ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage(
- ObstacleList_descriptor_, &ObstacleList::default_instance());
- ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage(
- ObstacleMap_descriptor_, &ObstacleMap::default_instance());
- ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage(
- Path_descriptor_, &Path::default_instance());
- ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage(
- PointCloudXYZI_descriptor_, &PointCloudXYZI::default_instance());
- ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage(
- PointCloudXYZI_PointXYZI_descriptor_, &PointCloudXYZI_PointXYZI::default_instance());
- ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage(
- PointCloudXYZRGB_descriptor_, &PointCloudXYZRGB::default_instance());
- ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage(
- PointCloudXYZRGB_PointXYZRGB_descriptor_, &PointCloudXYZRGB_PointXYZRGB::default_instance());
- ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage(
- RGBDImage_descriptor_, &RGBDImage::default_instance());
- ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage(
- Waypoint_descriptor_, &Waypoint::default_instance());
-}
-
-} // namespace
-
-void protobuf_ShutdownFile_pixhawk_2eproto() {
- delete HeaderInfo::default_instance_;
- delete HeaderInfo_reflection_;
- delete GLOverlay::default_instance_;
- delete GLOverlay_reflection_;
- delete Obstacle::default_instance_;
- delete Obstacle_reflection_;
- delete ObstacleList::default_instance_;
- delete ObstacleList_reflection_;
- delete ObstacleMap::default_instance_;
- delete ObstacleMap_reflection_;
- delete Path::default_instance_;
- delete Path_reflection_;
- delete PointCloudXYZI::default_instance_;
- delete PointCloudXYZI_reflection_;
- delete PointCloudXYZI_PointXYZI::default_instance_;
- delete PointCloudXYZI_PointXYZI_reflection_;
- delete PointCloudXYZRGB::default_instance_;
- delete PointCloudXYZRGB_reflection_;
- delete PointCloudXYZRGB_PointXYZRGB::default_instance_;
- delete PointCloudXYZRGB_PointXYZRGB_reflection_;
- delete RGBDImage::default_instance_;
- delete RGBDImage_reflection_;
- delete Waypoint::default_instance_;
- delete Waypoint_reflection_;
-}
-
-void protobuf_AddDesc_pixhawk_2eproto() {
- static bool already_here = false;
- if (already_here) return;
- already_here = true;
- GOOGLE_PROTOBUF_VERIFY_VERSION;
-
- ::google::protobuf::DescriptorPool::InternalAddGeneratedFile(
- "\n\rpixhawk.proto\022\002px\"L\n\nHeaderInfo\022\024\n\014sou"
- "rce_sysid\030\001 \002(\005\022\025\n\rsource_compid\030\002 \002(\005\022\021"
- "\n\ttimestamp\030\003 \002(\001\"\377\004\n\tGLOverlay\022\036\n\006heade"
- "r\030\001 \002(\0132\016.px.HeaderInfo\022\014\n\004name\030\002 \001(\t\022>\n"
- "\023coordinateFrameType\030\003 \001(\0162!.px.GLOverla"
- "y.CoordinateFrameType\022\020\n\010origin_x\030\004 \001(\001\022"
- "\020\n\010origin_y\030\005 \001(\001\022\020\n\010origin_z\030\006 \001(\001\022\014\n\004d"
- "ata\030\007 \001(\014\",\n\023CoordinateFrameType\022\n\n\006GLOB"
- "AL\020\000\022\t\n\005LOCAL\020\001\"\333\001\n\004Mode\022\n\n\006POINTS\020\000\022\t\n\005"
- "LINES\020\001\022\016\n\nLINE_STRIP\020\002\022\r\n\tLINE_LOOP\020\003\022\r"
- "\n\tTRIANGLES\020\004\022\022\n\016TRIANGLE_STRIP\020\005\022\020\n\014TRI"
- "ANGLE_FAN\020\006\022\t\n\005QUADS\020\007\022\016\n\nQUAD_STRIP\020\010\022\013"
- "\n\007POLYGON\020\t\022\020\n\014SOLID_CIRCLE\020\n\022\017\n\013WIRE_CI"
- "RCLE\020\013\022\016\n\nSOLID_CUBE\020\014\022\r\n\tWIRE_CUBE\020\r\"\263\001"
- "\n\nIdentifier\022\007\n\003END\020\016\022\014\n\010VERTEX2F\020\017\022\014\n\010V"
- "ERTEX3F\020\020\022\013\n\007ROTATEF\020\021\022\016\n\nTRANSLATEF\020\022\022\n"
- "\n\006SCALEF\020\023\022\017\n\013PUSH_MATRIX\020\024\022\016\n\nPOP_MATRI"
- "X\020\025\022\013\n\007COLOR3F\020\026\022\013\n\007COLOR4F\020\027\022\r\n\tPOINTSI"
- "ZE\020\030\022\r\n\tLINEWIDTH\020\031\"Z\n\010Obstacle\022\t\n\001x\030\001 \001"
- "(\002\022\t\n\001y\030\002 \001(\002\022\t\n\001z\030\003 \001(\002\022\016\n\006length\030\004 \001(\002"
- "\022\r\n\005width\030\005 \001(\002\022\016\n\006height\030\006 \001(\002\"O\n\014Obsta"
- "cleList\022\036\n\006header\030\001 \002(\0132\016.px.HeaderInfo\022"
- "\037\n\tobstacles\030\002 \003(\0132\014.px.Obstacle\"\271\001\n\013Obs"
- "tacleMap\022\036\n\006header\030\001 \002(\0132\016.px.HeaderInfo"
- "\022\014\n\004type\030\002 \002(\005\022\022\n\nresolution\030\003 \001(\002\022\014\n\004ro"
- "ws\030\004 \001(\005\022\014\n\004cols\030\005 \001(\005\022\r\n\005mapR0\030\006 \001(\005\022\r\n"
- "\005mapC0\030\007 \001(\005\022\017\n\007arrayR0\030\010 \001(\005\022\017\n\007arrayC0"
- "\030\t \001(\005\022\014\n\004data\030\n \001(\014\"G\n\004Path\022\036\n\006header\030\001"
- " \002(\0132\016.px.HeaderInfo\022\037\n\twaypoints\030\002 \003(\0132"
- "\014.px.Waypoint\"\237\001\n\016PointCloudXYZI\022\036\n\006head"
- "er\030\001 \002(\0132\016.px.HeaderInfo\022,\n\006points\030\002 \003(\013"
- "2\034.px.PointCloudXYZI.PointXYZI\032\?\n\tPointX"
- "YZI\022\t\n\001x\030\001 \002(\002\022\t\n\001y\030\002 \002(\002\022\t\n\001z\030\003 \002(\002\022\021\n\t"
- "intensity\030\004 \002(\002\"\241\001\n\020PointCloudXYZRGB\022\036\n\006"
- "header\030\001 \002(\0132\016.px.HeaderInfo\0220\n\006points\030\002"
- " \003(\0132 .px.PointCloudXYZRGB.PointXYZRGB\032;"
- "\n\013PointXYZRGB\022\t\n\001x\030\001 \002(\002\022\t\n\001y\030\002 \002(\002\022\t\n\001z"
- "\030\003 \002(\002\022\013\n\003rgb\030\004 \002(\002\"\365\002\n\tRGBDImage\022\036\n\006hea"
- "der\030\001 \002(\0132\016.px.HeaderInfo\022\014\n\004cols\030\002 \002(\r\022"
- "\014\n\004rows\030\003 \002(\r\022\r\n\005step1\030\004 \002(\r\022\r\n\005type1\030\005 "
- "\002(\r\022\022\n\nimageData1\030\006 \002(\014\022\r\n\005step2\030\007 \002(\r\022\r"
- "\n\005type2\030\010 \002(\r\022\022\n\nimageData2\030\t \002(\014\022\025\n\rcam"
- "era_config\030\n \001(\r\022\023\n\013camera_type\030\013 \001(\r\022\014\n"
- "\004roll\030\014 \001(\002\022\r\n\005pitch\030\r \001(\002\022\013\n\003yaw\030\016 \001(\002\022"
- "\013\n\003lon\030\017 \001(\002\022\013\n\003lat\030\020 \001(\002\022\013\n\003alt\030\021 \001(\002\022\020"
- "\n\010ground_x\030\022 \001(\002\022\020\n\010ground_y\030\023 \001(\002\022\020\n\010gr"
- "ound_z\030\024 \001(\002\022\025\n\rcamera_matrix\030\025 \003(\002\"U\n\010W"
- "aypoint\022\t\n\001x\030\001 \002(\001\022\t\n\001y\030\002 \002(\001\022\t\n\001z\030\003 \001(\001"
- "\022\014\n\004roll\030\004 \001(\001\022\r\n\005pitch\030\005 \001(\001\022\013\n\003yaw\030\006 \001"
- "(\001", 1962);
- ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile(
- "pixhawk.proto", &protobuf_RegisterTypes);
- HeaderInfo::default_instance_ = new HeaderInfo();
- GLOverlay::default_instance_ = new GLOverlay();
- Obstacle::default_instance_ = new Obstacle();
- ObstacleList::default_instance_ = new ObstacleList();
- ObstacleMap::default_instance_ = new ObstacleMap();
- Path::default_instance_ = new Path();
- PointCloudXYZI::default_instance_ = new PointCloudXYZI();
- PointCloudXYZI_PointXYZI::default_instance_ = new PointCloudXYZI_PointXYZI();
- PointCloudXYZRGB::default_instance_ = new PointCloudXYZRGB();
- PointCloudXYZRGB_PointXYZRGB::default_instance_ = new PointCloudXYZRGB_PointXYZRGB();
- RGBDImage::default_instance_ = new RGBDImage();
- Waypoint::default_instance_ = new Waypoint();
- HeaderInfo::default_instance_->InitAsDefaultInstance();
- GLOverlay::default_instance_->InitAsDefaultInstance();
- Obstacle::default_instance_->InitAsDefaultInstance();
- ObstacleList::default_instance_->InitAsDefaultInstance();
- ObstacleMap::default_instance_->InitAsDefaultInstance();
- Path::default_instance_->InitAsDefaultInstance();
- PointCloudXYZI::default_instance_->InitAsDefaultInstance();
- PointCloudXYZI_PointXYZI::default_instance_->InitAsDefaultInstance();
- PointCloudXYZRGB::default_instance_->InitAsDefaultInstance();
- PointCloudXYZRGB_PointXYZRGB::default_instance_->InitAsDefaultInstance();
- RGBDImage::default_instance_->InitAsDefaultInstance();
- Waypoint::default_instance_->InitAsDefaultInstance();
- ::google::protobuf::internal::OnShutdown(&protobuf_ShutdownFile_pixhawk_2eproto);
-}
-
-// Force AddDescriptors() to be called at static initialization time.
-struct StaticDescriptorInitializer_pixhawk_2eproto {
- StaticDescriptorInitializer_pixhawk_2eproto() {
- protobuf_AddDesc_pixhawk_2eproto();
- }
-} static_descriptor_initializer_pixhawk_2eproto_;
-
-
-// ===================================================================
-
-#ifndef _MSC_VER
-const int HeaderInfo::kSourceSysidFieldNumber;
-const int HeaderInfo::kSourceCompidFieldNumber;
-const int HeaderInfo::kTimestampFieldNumber;
-#endif // !_MSC_VER
-
-HeaderInfo::HeaderInfo()
- : ::google::protobuf::Message() {
- SharedCtor();
-}
-
-void HeaderInfo::InitAsDefaultInstance() {
-}
-
-HeaderInfo::HeaderInfo(const HeaderInfo& from)
- : ::google::protobuf::Message() {
- SharedCtor();
- MergeFrom(from);
-}
-
-void HeaderInfo::SharedCtor() {
- _cached_size_ = 0;
- source_sysid_ = 0;
- source_compid_ = 0;
- timestamp_ = 0;
- ::memset(_has_bits_, 0, sizeof(_has_bits_));
-}
-
-HeaderInfo::~HeaderInfo() {
- SharedDtor();
-}
-
-void HeaderInfo::SharedDtor() {
- if (this != default_instance_) {
- }
-}
-
-void HeaderInfo::SetCachedSize(int size) const {
- GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
- _cached_size_ = size;
- GOOGLE_SAFE_CONCURRENT_WRITES_END();
-}
-const ::google::protobuf::Descriptor* HeaderInfo::descriptor() {
- protobuf_AssignDescriptorsOnce();
- return HeaderInfo_descriptor_;
-}
-
-const HeaderInfo& HeaderInfo::default_instance() {
- if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_;
-}
-
-HeaderInfo* HeaderInfo::default_instance_ = NULL;
-
-HeaderInfo* HeaderInfo::New() const {
- return new HeaderInfo;
-}
-
-void HeaderInfo::Clear() {
- if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- source_sysid_ = 0;
- source_compid_ = 0;
- timestamp_ = 0;
- }
- ::memset(_has_bits_, 0, sizeof(_has_bits_));
- mutable_unknown_fields()->Clear();
-}
-
-bool HeaderInfo::MergePartialFromCodedStream(
- ::google::protobuf::io::CodedInputStream* input) {
-#define DO_(EXPRESSION) if (!(EXPRESSION)) return false
- ::google::protobuf::uint32 tag;
- while ((tag = input->ReadTag()) != 0) {
- switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) {
- // required int32 source_sysid = 1;
- case 1: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>(
- input, &source_sysid_)));
- set_has_source_sysid();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(16)) goto parse_source_compid;
- break;
- }
-
- // required int32 source_compid = 2;
- case 2: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
- parse_source_compid:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>(
- input, &source_compid_)));
- set_has_source_compid();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(25)) goto parse_timestamp;
- break;
- }
-
- // required double timestamp = 3;
- case 3: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) {
- parse_timestamp:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>(
- input, &timestamp_)));
- set_has_timestamp();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectAtEnd()) return true;
- break;
- }
-
- default: {
- handle_uninterpreted:
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) {
- return true;
- }
- DO_(::google::protobuf::internal::WireFormat::SkipField(
- input, tag, mutable_unknown_fields()));
- break;
- }
- }
- }
- return true;
-#undef DO_
-}
-
-void HeaderInfo::SerializeWithCachedSizes(
- ::google::protobuf::io::CodedOutputStream* output) const {
- // required int32 source_sysid = 1;
- if (has_source_sysid()) {
- ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->source_sysid(), output);
- }
-
- // required int32 source_compid = 2;
- if (has_source_compid()) {
- ::google::protobuf::internal::WireFormatLite::WriteInt32(2, this->source_compid(), output);
- }
-
- // required double timestamp = 3;
- if (has_timestamp()) {
- ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->timestamp(), output);
- }
-
- if (!unknown_fields().empty()) {
- ::google::protobuf::internal::WireFormat::SerializeUnknownFields(
- unknown_fields(), output);
- }
-}
-
-::google::protobuf::uint8* HeaderInfo::SerializeWithCachedSizesToArray(
- ::google::protobuf::uint8* target) const {
- // required int32 source_sysid = 1;
- if (has_source_sysid()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->source_sysid(), target);
- }
-
- // required int32 source_compid = 2;
- if (has_source_compid()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(2, this->source_compid(), target);
- }
-
- // required double timestamp = 3;
- if (has_timestamp()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->timestamp(), target);
- }
-
- if (!unknown_fields().empty()) {
- target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray(
- unknown_fields(), target);
- }
- return target;
-}
-
-int HeaderInfo::ByteSize() const {
- int total_size = 0;
-
- if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- // required int32 source_sysid = 1;
- if (has_source_sysid()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::Int32Size(
- this->source_sysid());
- }
-
- // required int32 source_compid = 2;
- if (has_source_compid()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::Int32Size(
- this->source_compid());
- }
-
- // required double timestamp = 3;
- if (has_timestamp()) {
- total_size += 1 + 8;
- }
-
- }
- if (!unknown_fields().empty()) {
- total_size +=
- ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize(
- unknown_fields());
- }
- GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
- _cached_size_ = total_size;
- GOOGLE_SAFE_CONCURRENT_WRITES_END();
- return total_size;
-}
-
-void HeaderInfo::MergeFrom(const ::google::protobuf::Message& from) {
- GOOGLE_CHECK_NE(&from, this);
- const HeaderInfo* source =
- ::google::protobuf::internal::dynamic_cast_if_available<const HeaderInfo*>(
- &from);
- if (source == NULL) {
- ::google::protobuf::internal::ReflectionOps::Merge(from, this);
- } else {
- MergeFrom(*source);
- }
-}
-
-void HeaderInfo::MergeFrom(const HeaderInfo& from) {
- GOOGLE_CHECK_NE(&from, this);
- if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- if (from.has_source_sysid()) {
- set_source_sysid(from.source_sysid());
- }
- if (from.has_source_compid()) {
- set_source_compid(from.source_compid());
- }
- if (from.has_timestamp()) {
- set_timestamp(from.timestamp());
- }
- }
- mutable_unknown_fields()->MergeFrom(from.unknown_fields());
-}
-
-void HeaderInfo::CopyFrom(const ::google::protobuf::Message& from) {
- if (&from == this) return;
- Clear();
- MergeFrom(from);
-}
-
-void HeaderInfo::CopyFrom(const HeaderInfo& from) {
- if (&from == this) return;
- Clear();
- MergeFrom(from);
-}
-
-bool HeaderInfo::IsInitialized() const {
- if ((_has_bits_[0] & 0x00000007) != 0x00000007) return false;
-
- return true;
-}
-
-void HeaderInfo::Swap(HeaderInfo* other) {
- if (other != this) {
- std::swap(source_sysid_, other->source_sysid_);
- std::swap(source_compid_, other->source_compid_);
- std::swap(timestamp_, other->timestamp_);
- std::swap(_has_bits_[0], other->_has_bits_[0]);
- _unknown_fields_.Swap(&other->_unknown_fields_);
- std::swap(_cached_size_, other->_cached_size_);
- }
-}
-
-::google::protobuf::Metadata HeaderInfo::GetMetadata() const {
- protobuf_AssignDescriptorsOnce();
- ::google::protobuf::Metadata metadata;
- metadata.descriptor = HeaderInfo_descriptor_;
- metadata.reflection = HeaderInfo_reflection_;
- return metadata;
-}
-
-
-// ===================================================================
-
-const ::google::protobuf::EnumDescriptor* GLOverlay_CoordinateFrameType_descriptor() {
- protobuf_AssignDescriptorsOnce();
- return GLOverlay_CoordinateFrameType_descriptor_;
-}
-bool GLOverlay_CoordinateFrameType_IsValid(int value) {
- switch(value) {
- case 0:
- case 1:
- return true;
- default:
- return false;
- }
-}
-
-#ifndef _MSC_VER
-const GLOverlay_CoordinateFrameType GLOverlay::GLOBAL;
-const GLOverlay_CoordinateFrameType GLOverlay::LOCAL;
-const GLOverlay_CoordinateFrameType GLOverlay::CoordinateFrameType_MIN;
-const GLOverlay_CoordinateFrameType GLOverlay::CoordinateFrameType_MAX;
-const int GLOverlay::CoordinateFrameType_ARRAYSIZE;
-#endif // _MSC_VER
-const ::google::protobuf::EnumDescriptor* GLOverlay_Mode_descriptor() {
- protobuf_AssignDescriptorsOnce();
- return GLOverlay_Mode_descriptor_;
-}
-bool GLOverlay_Mode_IsValid(int value) {
- switch(value) {
- case 0:
- case 1:
- case 2:
- case 3:
- case 4:
- case 5:
- case 6:
- case 7:
- case 8:
- case 9:
- case 10:
- case 11:
- case 12:
- case 13:
- return true;
- default:
- return false;
- }
-}
-
-#ifndef _MSC_VER
-const GLOverlay_Mode GLOverlay::POINTS;
-const GLOverlay_Mode GLOverlay::LINES;
-const GLOverlay_Mode GLOverlay::LINE_STRIP;
-const GLOverlay_Mode GLOverlay::LINE_LOOP;
-const GLOverlay_Mode GLOverlay::TRIANGLES;
-const GLOverlay_Mode GLOverlay::TRIANGLE_STRIP;
-const GLOverlay_Mode GLOverlay::TRIANGLE_FAN;
-const GLOverlay_Mode GLOverlay::QUADS;
-const GLOverlay_Mode GLOverlay::QUAD_STRIP;
-const GLOverlay_Mode GLOverlay::POLYGON;
-const GLOverlay_Mode GLOverlay::SOLID_CIRCLE;
-const GLOverlay_Mode GLOverlay::WIRE_CIRCLE;
-const GLOverlay_Mode GLOverlay::SOLID_CUBE;
-const GLOverlay_Mode GLOverlay::WIRE_CUBE;
-const GLOverlay_Mode GLOverlay::Mode_MIN;
-const GLOverlay_Mode GLOverlay::Mode_MAX;
-const int GLOverlay::Mode_ARRAYSIZE;
-#endif // _MSC_VER
-const ::google::protobuf::EnumDescriptor* GLOverlay_Identifier_descriptor() {
- protobuf_AssignDescriptorsOnce();
- return GLOverlay_Identifier_descriptor_;
-}
-bool GLOverlay_Identifier_IsValid(int value) {
- switch(value) {
- case 14:
- case 15:
- case 16:
- case 17:
- case 18:
- case 19:
- case 20:
- case 21:
- case 22:
- case 23:
- case 24:
- case 25:
- return true;
- default:
- return false;
- }
-}
-
-#ifndef _MSC_VER
-const GLOverlay_Identifier GLOverlay::END;
-const GLOverlay_Identifier GLOverlay::VERTEX2F;
-const GLOverlay_Identifier GLOverlay::VERTEX3F;
-const GLOverlay_Identifier GLOverlay::ROTATEF;
-const GLOverlay_Identifier GLOverlay::TRANSLATEF;
-const GLOverlay_Identifier GLOverlay::SCALEF;
-const GLOverlay_Identifier GLOverlay::PUSH_MATRIX;
-const GLOverlay_Identifier GLOverlay::POP_MATRIX;
-const GLOverlay_Identifier GLOverlay::COLOR3F;
-const GLOverlay_Identifier GLOverlay::COLOR4F;
-const GLOverlay_Identifier GLOverlay::POINTSIZE;
-const GLOverlay_Identifier GLOverlay::LINEWIDTH;
-const GLOverlay_Identifier GLOverlay::Identifier_MIN;
-const GLOverlay_Identifier GLOverlay::Identifier_MAX;
-const int GLOverlay::Identifier_ARRAYSIZE;
-#endif // _MSC_VER
-#ifndef _MSC_VER
-const int GLOverlay::kHeaderFieldNumber;
-const int GLOverlay::kNameFieldNumber;
-const int GLOverlay::kCoordinateFrameTypeFieldNumber;
-const int GLOverlay::kOriginXFieldNumber;
-const int GLOverlay::kOriginYFieldNumber;
-const int GLOverlay::kOriginZFieldNumber;
-const int GLOverlay::kDataFieldNumber;
-#endif // !_MSC_VER
-
-GLOverlay::GLOverlay()
- : ::google::protobuf::Message() {
- SharedCtor();
-}
-
-void GLOverlay::InitAsDefaultInstance() {
- header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance());
-}
-
-GLOverlay::GLOverlay(const GLOverlay& from)
- : ::google::protobuf::Message() {
- SharedCtor();
- MergeFrom(from);
-}
-
-void GLOverlay::SharedCtor() {
- _cached_size_ = 0;
- header_ = NULL;
- name_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString);
- coordinateframetype_ = 0;
- origin_x_ = 0;
- origin_y_ = 0;
- origin_z_ = 0;
- data_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString);
- ::memset(_has_bits_, 0, sizeof(_has_bits_));
-}
-
-GLOverlay::~GLOverlay() {
- SharedDtor();
-}
-
-void GLOverlay::SharedDtor() {
- if (name_ != &::google::protobuf::internal::kEmptyString) {
- delete name_;
- }
- if (data_ != &::google::protobuf::internal::kEmptyString) {
- delete data_;
- }
- if (this != default_instance_) {
- delete header_;
- }
-}
-
-void GLOverlay::SetCachedSize(int size) const {
- GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
- _cached_size_ = size;
- GOOGLE_SAFE_CONCURRENT_WRITES_END();
-}
-const ::google::protobuf::Descriptor* GLOverlay::descriptor() {
- protobuf_AssignDescriptorsOnce();
- return GLOverlay_descriptor_;
-}
-
-const GLOverlay& GLOverlay::default_instance() {
- if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_;
-}
-
-GLOverlay* GLOverlay::default_instance_ = NULL;
-
-GLOverlay* GLOverlay::New() const {
- return new GLOverlay;
-}
-
-void GLOverlay::Clear() {
- if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- if (has_header()) {
- if (header_ != NULL) header_->::px::HeaderInfo::Clear();
- }
- if (has_name()) {
- if (name_ != &::google::protobuf::internal::kEmptyString) {
- name_->clear();
- }
- }
- coordinateframetype_ = 0;
- origin_x_ = 0;
- origin_y_ = 0;
- origin_z_ = 0;
- if (has_data()) {
- if (data_ != &::google::protobuf::internal::kEmptyString) {
- data_->clear();
- }
- }
- }
- ::memset(_has_bits_, 0, sizeof(_has_bits_));
- mutable_unknown_fields()->Clear();
-}
-
-bool GLOverlay::MergePartialFromCodedStream(
- ::google::protobuf::io::CodedInputStream* input) {
-#define DO_(EXPRESSION) if (!(EXPRESSION)) return false
- ::google::protobuf::uint32 tag;
- while ((tag = input->ReadTag()) != 0) {
- switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) {
- // required .px.HeaderInfo header = 1;
- case 1: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
- DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual(
- input, mutable_header()));
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(18)) goto parse_name;
- break;
- }
-
- // optional string name = 2;
- case 2: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
- parse_name:
- DO_(::google::protobuf::internal::WireFormatLite::ReadString(
- input, this->mutable_name()));
- ::google::protobuf::internal::WireFormat::VerifyUTF8String(
- this->name().data(), this->name().length(),
- ::google::protobuf::internal::WireFormat::PARSE);
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(24)) goto parse_coordinateFrameType;
- break;
- }
-
- // optional .px.GLOverlay.CoordinateFrameType coordinateFrameType = 3;
- case 3: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
- parse_coordinateFrameType:
- int value;
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>(
- input, &value)));
- if (::px::GLOverlay_CoordinateFrameType_IsValid(value)) {
- set_coordinateframetype(static_cast< ::px::GLOverlay_CoordinateFrameType >(value));
- } else {
- mutable_unknown_fields()->AddVarint(3, value);
- }
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(33)) goto parse_origin_x;
- break;
- }
-
- // optional double origin_x = 4;
- case 4: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) {
- parse_origin_x:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>(
- input, &origin_x_)));
- set_has_origin_x();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(41)) goto parse_origin_y;
- break;
- }
-
- // optional double origin_y = 5;
- case 5: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) {
- parse_origin_y:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>(
- input, &origin_y_)));
- set_has_origin_y();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(49)) goto parse_origin_z;
- break;
- }
-
- // optional double origin_z = 6;
- case 6: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) {
- parse_origin_z:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>(
- input, &origin_z_)));
- set_has_origin_z();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(58)) goto parse_data;
- break;
- }
-
- // optional bytes data = 7;
- case 7: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
- parse_data:
- DO_(::google::protobuf::internal::WireFormatLite::ReadBytes(
- input, this->mutable_data()));
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectAtEnd()) return true;
- break;
- }
-
- default: {
- handle_uninterpreted:
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) {
- return true;
- }
- DO_(::google::protobuf::internal::WireFormat::SkipField(
- input, tag, mutable_unknown_fields()));
- break;
- }
- }
- }
- return true;
-#undef DO_
-}
-
-void GLOverlay::SerializeWithCachedSizes(
- ::google::protobuf::io::CodedOutputStream* output) const {
- // required .px.HeaderInfo header = 1;
- if (has_header()) {
- ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray(
- 1, this->header(), output);
- }
-
- // optional string name = 2;
- if (has_name()) {
- ::google::protobuf::internal::WireFormat::VerifyUTF8String(
- this->name().data(), this->name().length(),
- ::google::protobuf::internal::WireFormat::SERIALIZE);
- ::google::protobuf::internal::WireFormatLite::WriteString(
- 2, this->name(), output);
- }
-
- // optional .px.GLOverlay.CoordinateFrameType coordinateFrameType = 3;
- if (has_coordinateframetype()) {
- ::google::protobuf::internal::WireFormatLite::WriteEnum(
- 3, this->coordinateframetype(), output);
- }
-
- // optional double origin_x = 4;
- if (has_origin_x()) {
- ::google::protobuf::internal::WireFormatLite::WriteDouble(4, this->origin_x(), output);
- }
-
- // optional double origin_y = 5;
- if (has_origin_y()) {
- ::google::protobuf::internal::WireFormatLite::WriteDouble(5, this->origin_y(), output);
- }
-
- // optional double origin_z = 6;
- if (has_origin_z()) {
- ::google::protobuf::internal::WireFormatLite::WriteDouble(6, this->origin_z(), output);
- }
-
- // optional bytes data = 7;
- if (has_data()) {
- ::google::protobuf::internal::WireFormatLite::WriteBytes(
- 7, this->data(), output);
- }
-
- if (!unknown_fields().empty()) {
- ::google::protobuf::internal::WireFormat::SerializeUnknownFields(
- unknown_fields(), output);
- }
-}
-
-::google::protobuf::uint8* GLOverlay::SerializeWithCachedSizesToArray(
- ::google::protobuf::uint8* target) const {
- // required .px.HeaderInfo header = 1;
- if (has_header()) {
- target = ::google::protobuf::internal::WireFormatLite::
- WriteMessageNoVirtualToArray(
- 1, this->header(), target);
- }
-
- // optional string name = 2;
- if (has_name()) {
- ::google::protobuf::internal::WireFormat::VerifyUTF8String(
- this->name().data(), this->name().length(),
- ::google::protobuf::internal::WireFormat::SERIALIZE);
- target =
- ::google::protobuf::internal::WireFormatLite::WriteStringToArray(
- 2, this->name(), target);
- }
-
- // optional .px.GLOverlay.CoordinateFrameType coordinateFrameType = 3;
- if (has_coordinateframetype()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray(
- 3, this->coordinateframetype(), target);
- }
-
- // optional double origin_x = 4;
- if (has_origin_x()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(4, this->origin_x(), target);
- }
-
- // optional double origin_y = 5;
- if (has_origin_y()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(5, this->origin_y(), target);
- }
-
- // optional double origin_z = 6;
- if (has_origin_z()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(6, this->origin_z(), target);
- }
-
- // optional bytes data = 7;
- if (has_data()) {
- target =
- ::google::protobuf::internal::WireFormatLite::WriteBytesToArray(
- 7, this->data(), target);
- }
-
- if (!unknown_fields().empty()) {
- target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray(
- unknown_fields(), target);
- }
- return target;
-}
-
-int GLOverlay::ByteSize() const {
- int total_size = 0;
-
- if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- // required .px.HeaderInfo header = 1;
- if (has_header()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
- this->header());
- }
-
- // optional string name = 2;
- if (has_name()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::StringSize(
- this->name());
- }
-
- // optional .px.GLOverlay.CoordinateFrameType coordinateFrameType = 3;
- if (has_coordinateframetype()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::EnumSize(this->coordinateframetype());
- }
-
- // optional double origin_x = 4;
- if (has_origin_x()) {
- total_size += 1 + 8;
- }
-
- // optional double origin_y = 5;
- if (has_origin_y()) {
- total_size += 1 + 8;
- }
-
- // optional double origin_z = 6;
- if (has_origin_z()) {
- total_size += 1 + 8;
- }
-
- // optional bytes data = 7;
- if (has_data()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::BytesSize(
- this->data());
- }
-
- }
- if (!unknown_fields().empty()) {
- total_size +=
- ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize(
- unknown_fields());
- }
- GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
- _cached_size_ = total_size;
- GOOGLE_SAFE_CONCURRENT_WRITES_END();
- return total_size;
-}
-
-void GLOverlay::MergeFrom(const ::google::protobuf::Message& from) {
- GOOGLE_CHECK_NE(&from, this);
- const GLOverlay* source =
- ::google::protobuf::internal::dynamic_cast_if_available<const GLOverlay*>(
- &from);
- if (source == NULL) {
- ::google::protobuf::internal::ReflectionOps::Merge(from, this);
- } else {
- MergeFrom(*source);
- }
-}
-
-void GLOverlay::MergeFrom(const GLOverlay& from) {
- GOOGLE_CHECK_NE(&from, this);
- if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- if (from.has_header()) {
- mutable_header()->::px::HeaderInfo::MergeFrom(from.header());
- }
- if (from.has_name()) {
- set_name(from.name());
- }
- if (from.has_coordinateframetype()) {
- set_coordinateframetype(from.coordinateframetype());
- }
- if (from.has_origin_x()) {
- set_origin_x(from.origin_x());
- }
- if (from.has_origin_y()) {
- set_origin_y(from.origin_y());
- }
- if (from.has_origin_z()) {
- set_origin_z(from.origin_z());
- }
- if (from.has_data()) {
- set_data(from.data());
- }
- }
- mutable_unknown_fields()->MergeFrom(from.unknown_fields());
-}
-
-void GLOverlay::CopyFrom(const ::google::protobuf::Message& from) {
- if (&from == this) return;
- Clear();
- MergeFrom(from);
-}
-
-void GLOverlay::CopyFrom(const GLOverlay& from) {
- if (&from == this) return;
- Clear();
- MergeFrom(from);
-}
-
-bool GLOverlay::IsInitialized() const {
- if ((_has_bits_[0] & 0x00000001) != 0x00000001) return false;
-
- if (has_header()) {
- if (!this->header().IsInitialized()) return false;
- }
- return true;
-}
-
-void GLOverlay::Swap(GLOverlay* other) {
- if (other != this) {
- std::swap(header_, other->header_);
- std::swap(name_, other->name_);
- std::swap(coordinateframetype_, other->coordinateframetype_);
- std::swap(origin_x_, other->origin_x_);
- std::swap(origin_y_, other->origin_y_);
- std::swap(origin_z_, other->origin_z_);
- std::swap(data_, other->data_);
- std::swap(_has_bits_[0], other->_has_bits_[0]);
- _unknown_fields_.Swap(&other->_unknown_fields_);
- std::swap(_cached_size_, other->_cached_size_);
- }
-}
-
-::google::protobuf::Metadata GLOverlay::GetMetadata() const {
- protobuf_AssignDescriptorsOnce();
- ::google::protobuf::Metadata metadata;
- metadata.descriptor = GLOverlay_descriptor_;
- metadata.reflection = GLOverlay_reflection_;
- return metadata;
-}
-
-
-// ===================================================================
-
-#ifndef _MSC_VER
-const int Obstacle::kXFieldNumber;
-const int Obstacle::kYFieldNumber;
-const int Obstacle::kZFieldNumber;
-const int Obstacle::kLengthFieldNumber;
-const int Obstacle::kWidthFieldNumber;
-const int Obstacle::kHeightFieldNumber;
-#endif // !_MSC_VER
-
-Obstacle::Obstacle()
- : ::google::protobuf::Message() {
- SharedCtor();
-}
-
-void Obstacle::InitAsDefaultInstance() {
-}
-
-Obstacle::Obstacle(const Obstacle& from)
- : ::google::protobuf::Message() {
- SharedCtor();
- MergeFrom(from);
-}
-
-void Obstacle::SharedCtor() {
- _cached_size_ = 0;
- x_ = 0;
- y_ = 0;
- z_ = 0;
- length_ = 0;
- width_ = 0;
- height_ = 0;
- ::memset(_has_bits_, 0, sizeof(_has_bits_));
-}
-
-Obstacle::~Obstacle() {
- SharedDtor();
-}
-
-void Obstacle::SharedDtor() {
- if (this != default_instance_) {
- }
-}
-
-void Obstacle::SetCachedSize(int size) const {
- GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
- _cached_size_ = size;
- GOOGLE_SAFE_CONCURRENT_WRITES_END();
-}
-const ::google::protobuf::Descriptor* Obstacle::descriptor() {
- protobuf_AssignDescriptorsOnce();
- return Obstacle_descriptor_;
-}
-
-const Obstacle& Obstacle::default_instance() {
- if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_;
-}
-
-Obstacle* Obstacle::default_instance_ = NULL;
-
-Obstacle* Obstacle::New() const {
- return new Obstacle;
-}
-
-void Obstacle::Clear() {
- if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- x_ = 0;
- y_ = 0;
- z_ = 0;
- length_ = 0;
- width_ = 0;
- height_ = 0;
- }
- ::memset(_has_bits_, 0, sizeof(_has_bits_));
- mutable_unknown_fields()->Clear();
-}
-
-bool Obstacle::MergePartialFromCodedStream(
- ::google::protobuf::io::CodedInputStream* input) {
-#define DO_(EXPRESSION) if (!(EXPRESSION)) return false
- ::google::protobuf::uint32 tag;
- while ((tag = input->ReadTag()) != 0) {
- switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) {
- // optional float x = 1;
- case 1: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
- input, &x_)));
- set_has_x();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(21)) goto parse_y;
- break;
- }
-
- // optional float y = 2;
- case 2: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- parse_y:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
- input, &y_)));
- set_has_y();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(29)) goto parse_z;
- break;
- }
-
- // optional float z = 3;
- case 3: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- parse_z:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
- input, &z_)));
- set_has_z();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(37)) goto parse_length;
- break;
- }
-
- // optional float length = 4;
- case 4: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- parse_length:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
- input, &length_)));
- set_has_length();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(45)) goto parse_width;
- break;
- }
-
- // optional float width = 5;
- case 5: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- parse_width:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
- input, &width_)));
- set_has_width();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(53)) goto parse_height;
- break;
- }
-
- // optional float height = 6;
- case 6: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- parse_height:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
- input, &height_)));
- set_has_height();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectAtEnd()) return true;
- break;
- }
-
- default: {
- handle_uninterpreted:
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) {
- return true;
- }
- DO_(::google::protobuf::internal::WireFormat::SkipField(
- input, tag, mutable_unknown_fields()));
- break;
- }
- }
- }
- return true;
-#undef DO_
-}
-
-void Obstacle::SerializeWithCachedSizes(
- ::google::protobuf::io::CodedOutputStream* output) const {
- // optional float x = 1;
- if (has_x()) {
- ::google::protobuf::internal::WireFormatLite::WriteFloat(1, this->x(), output);
- }
-
- // optional float y = 2;
- if (has_y()) {
- ::google::protobuf::internal::WireFormatLite::WriteFloat(2, this->y(), output);
- }
-
- // optional float z = 3;
- if (has_z()) {
- ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->z(), output);
- }
-
- // optional float length = 4;
- if (has_length()) {
- ::google::protobuf::internal::WireFormatLite::WriteFloat(4, this->length(), output);
- }
-
- // optional float width = 5;
- if (has_width()) {
- ::google::protobuf::internal::WireFormatLite::WriteFloat(5, this->width(), output);
- }
-
- // optional float height = 6;
- if (has_height()) {
- ::google::protobuf::internal::WireFormatLite::WriteFloat(6, this->height(), output);
- }
-
- if (!unknown_fields().empty()) {
- ::google::protobuf::internal::WireFormat::SerializeUnknownFields(
- unknown_fields(), output);
- }
-}
-
-::google::protobuf::uint8* Obstacle::SerializeWithCachedSizesToArray(
- ::google::protobuf::uint8* target) const {
- // optional float x = 1;
- if (has_x()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(1, this->x(), target);
- }
-
- // optional float y = 2;
- if (has_y()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(2, this->y(), target);
- }
-
- // optional float z = 3;
- if (has_z()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->z(), target);
- }
-
- // optional float length = 4;
- if (has_length()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(4, this->length(), target);
- }
-
- // optional float width = 5;
- if (has_width()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(5, this->width(), target);
- }
-
- // optional float height = 6;
- if (has_height()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(6, this->height(), target);
- }
-
- if (!unknown_fields().empty()) {
- target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray(
- unknown_fields(), target);
- }
- return target;
-}
-
-int Obstacle::ByteSize() const {
- int total_size = 0;
-
- if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- // optional float x = 1;
- if (has_x()) {
- total_size += 1 + 4;
- }
-
- // optional float y = 2;
- if (has_y()) {
- total_size += 1 + 4;
- }
-
- // optional float z = 3;
- if (has_z()) {
- total_size += 1 + 4;
- }
-
- // optional float length = 4;
- if (has_length()) {
- total_size += 1 + 4;
- }
-
- // optional float width = 5;
- if (has_width()) {
- total_size += 1 + 4;
- }
-
- // optional float height = 6;
- if (has_height()) {
- total_size += 1 + 4;
- }
-
- }
- if (!unknown_fields().empty()) {
- total_size +=
- ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize(
- unknown_fields());
- }
- GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
- _cached_size_ = total_size;
- GOOGLE_SAFE_CONCURRENT_WRITES_END();
- return total_size;
-}
-
-void Obstacle::MergeFrom(const ::google::protobuf::Message& from) {
- GOOGLE_CHECK_NE(&from, this);
- const Obstacle* source =
- ::google::protobuf::internal::dynamic_cast_if_available<const Obstacle*>(
- &from);
- if (source == NULL) {
- ::google::protobuf::internal::ReflectionOps::Merge(from, this);
- } else {
- MergeFrom(*source);
- }
-}
-
-void Obstacle::MergeFrom(const Obstacle& from) {
- GOOGLE_CHECK_NE(&from, this);
- if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- if (from.has_x()) {
- set_x(from.x());
- }
- if (from.has_y()) {
- set_y(from.y());
- }
- if (from.has_z()) {
- set_z(from.z());
- }
- if (from.has_length()) {
- set_length(from.length());
- }
- if (from.has_width()) {
- set_width(from.width());
- }
- if (from.has_height()) {
- set_height(from.height());
- }
- }
- mutable_unknown_fields()->MergeFrom(from.unknown_fields());
-}
-
-void Obstacle::CopyFrom(const ::google::protobuf::Message& from) {
- if (&from == this) return;
- Clear();
- MergeFrom(from);
-}
-
-void Obstacle::CopyFrom(const Obstacle& from) {
- if (&from == this) return;
- Clear();
- MergeFrom(from);
-}
-
-bool Obstacle::IsInitialized() const {
-
- return true;
-}
-
-void Obstacle::Swap(Obstacle* other) {
- if (other != this) {
- std::swap(x_, other->x_);
- std::swap(y_, other->y_);
- std::swap(z_, other->z_);
- std::swap(length_, other->length_);
- std::swap(width_, other->width_);
- std::swap(height_, other->height_);
- std::swap(_has_bits_[0], other->_has_bits_[0]);
- _unknown_fields_.Swap(&other->_unknown_fields_);
- std::swap(_cached_size_, other->_cached_size_);
- }
-}
-
-::google::protobuf::Metadata Obstacle::GetMetadata() const {
- protobuf_AssignDescriptorsOnce();
- ::google::protobuf::Metadata metadata;
- metadata.descriptor = Obstacle_descriptor_;
- metadata.reflection = Obstacle_reflection_;
- return metadata;
-}
-
-
-// ===================================================================
-
-#ifndef _MSC_VER
-const int ObstacleList::kHeaderFieldNumber;
-const int ObstacleList::kObstaclesFieldNumber;
-#endif // !_MSC_VER
-
-ObstacleList::ObstacleList()
- : ::google::protobuf::Message() {
- SharedCtor();
-}
-
-void ObstacleList::InitAsDefaultInstance() {
- header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance());
-}
-
-ObstacleList::ObstacleList(const ObstacleList& from)
- : ::google::protobuf::Message() {
- SharedCtor();
- MergeFrom(from);
-}
-
-void ObstacleList::SharedCtor() {
- _cached_size_ = 0;
- header_ = NULL;
- ::memset(_has_bits_, 0, sizeof(_has_bits_));
-}
-
-ObstacleList::~ObstacleList() {
- SharedDtor();
-}
-
-void ObstacleList::SharedDtor() {
- if (this != default_instance_) {
- delete header_;
- }
-}
-
-void ObstacleList::SetCachedSize(int size) const {
- GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
- _cached_size_ = size;
- GOOGLE_SAFE_CONCURRENT_WRITES_END();
-}
-const ::google::protobuf::Descriptor* ObstacleList::descriptor() {
- protobuf_AssignDescriptorsOnce();
- return ObstacleList_descriptor_;
-}
-
-const ObstacleList& ObstacleList::default_instance() {
- if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_;
-}
-
-ObstacleList* ObstacleList::default_instance_ = NULL;
-
-ObstacleList* ObstacleList::New() const {
- return new ObstacleList;
-}
-
-void ObstacleList::Clear() {
- if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- if (has_header()) {
- if (header_ != NULL) header_->::px::HeaderInfo::Clear();
- }
- }
- obstacles_.Clear();
- ::memset(_has_bits_, 0, sizeof(_has_bits_));
- mutable_unknown_fields()->Clear();
-}
-
-bool ObstacleList::MergePartialFromCodedStream(
- ::google::protobuf::io::CodedInputStream* input) {
-#define DO_(EXPRESSION) if (!(EXPRESSION)) return false
- ::google::protobuf::uint32 tag;
- while ((tag = input->ReadTag()) != 0) {
- switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) {
- // required .px.HeaderInfo header = 1;
- case 1: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
- DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual(
- input, mutable_header()));
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(18)) goto parse_obstacles;
- break;
- }
-
- // repeated .px.Obstacle obstacles = 2;
- case 2: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
- parse_obstacles:
- DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual(
- input, add_obstacles()));
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(18)) goto parse_obstacles;
- if (input->ExpectAtEnd()) return true;
- break;
- }
-
- default: {
- handle_uninterpreted:
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) {
- return true;
- }
- DO_(::google::protobuf::internal::WireFormat::SkipField(
- input, tag, mutable_unknown_fields()));
- break;
- }
- }
- }
- return true;
-#undef DO_
-}
-
-void ObstacleList::SerializeWithCachedSizes(
- ::google::protobuf::io::CodedOutputStream* output) const {
- // required .px.HeaderInfo header = 1;
- if (has_header()) {
- ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray(
- 1, this->header(), output);
- }
-
- // repeated .px.Obstacle obstacles = 2;
- for (int i = 0; i < this->obstacles_size(); i++) {
- ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray(
- 2, this->obstacles(i), output);
- }
-
- if (!unknown_fields().empty()) {
- ::google::protobuf::internal::WireFormat::SerializeUnknownFields(
- unknown_fields(), output);
- }
-}
-
-::google::protobuf::uint8* ObstacleList::SerializeWithCachedSizesToArray(
- ::google::protobuf::uint8* target) const {
- // required .px.HeaderInfo header = 1;
- if (has_header()) {
- target = ::google::protobuf::internal::WireFormatLite::
- WriteMessageNoVirtualToArray(
- 1, this->header(), target);
- }
-
- // repeated .px.Obstacle obstacles = 2;
- for (int i = 0; i < this->obstacles_size(); i++) {
- target = ::google::protobuf::internal::WireFormatLite::
- WriteMessageNoVirtualToArray(
- 2, this->obstacles(i), target);
- }
-
- if (!unknown_fields().empty()) {
- target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray(
- unknown_fields(), target);
- }
- return target;
-}
-
-int ObstacleList::ByteSize() const {
- int total_size = 0;
-
- if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- // required .px.HeaderInfo header = 1;
- if (has_header()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
- this->header());
- }
-
- }
- // repeated .px.Obstacle obstacles = 2;
- total_size += 1 * this->obstacles_size();
- for (int i = 0; i < this->obstacles_size(); i++) {
- total_size +=
- ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
- this->obstacles(i));
- }
-
- if (!unknown_fields().empty()) {
- total_size +=
- ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize(
- unknown_fields());
- }
- GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
- _cached_size_ = total_size;
- GOOGLE_SAFE_CONCURRENT_WRITES_END();
- return total_size;
-}
-
-void ObstacleList::MergeFrom(const ::google::protobuf::Message& from) {
- GOOGLE_CHECK_NE(&from, this);
- const ObstacleList* source =
- ::google::protobuf::internal::dynamic_cast_if_available<const ObstacleList*>(
- &from);
- if (source == NULL) {
- ::google::protobuf::internal::ReflectionOps::Merge(from, this);
- } else {
- MergeFrom(*source);
- }
-}
-
-void ObstacleList::MergeFrom(const ObstacleList& from) {
- GOOGLE_CHECK_NE(&from, this);
- obstacles_.MergeFrom(from.obstacles_);
- if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- if (from.has_header()) {
- mutable_header()->::px::HeaderInfo::MergeFrom(from.header());
- }
- }
- mutable_unknown_fields()->MergeFrom(from.unknown_fields());
-}
-
-void ObstacleList::CopyFrom(const ::google::protobuf::Message& from) {
- if (&from == this) return;
- Clear();
- MergeFrom(from);
-}
-
-void ObstacleList::CopyFrom(const ObstacleList& from) {
- if (&from == this) return;
- Clear();
- MergeFrom(from);
-}
-
-bool ObstacleList::IsInitialized() const {
- if ((_has_bits_[0] & 0x00000001) != 0x00000001) return false;
-
- if (has_header()) {
- if (!this->header().IsInitialized()) return false;
- }
- return true;
-}
-
-void ObstacleList::Swap(ObstacleList* other) {
- if (other != this) {
- std::swap(header_, other->header_);
- obstacles_.Swap(&other->obstacles_);
- std::swap(_has_bits_[0], other->_has_bits_[0]);
- _unknown_fields_.Swap(&other->_unknown_fields_);
- std::swap(_cached_size_, other->_cached_size_);
- }
-}
-
-::google::protobuf::Metadata ObstacleList::GetMetadata() const {
- protobuf_AssignDescriptorsOnce();
- ::google::protobuf::Metadata metadata;
- metadata.descriptor = ObstacleList_descriptor_;
- metadata.reflection = ObstacleList_reflection_;
- return metadata;
-}
-
-
-// ===================================================================
-
-#ifndef _MSC_VER
-const int ObstacleMap::kHeaderFieldNumber;
-const int ObstacleMap::kTypeFieldNumber;
-const int ObstacleMap::kResolutionFieldNumber;
-const int ObstacleMap::kRowsFieldNumber;
-const int ObstacleMap::kColsFieldNumber;
-const int ObstacleMap::kMapR0FieldNumber;
-const int ObstacleMap::kMapC0FieldNumber;
-const int ObstacleMap::kArrayR0FieldNumber;
-const int ObstacleMap::kArrayC0FieldNumber;
-const int ObstacleMap::kDataFieldNumber;
-#endif // !_MSC_VER
-
-ObstacleMap::ObstacleMap()
- : ::google::protobuf::Message() {
- SharedCtor();
-}
-
-void ObstacleMap::InitAsDefaultInstance() {
- header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance());
-}
-
-ObstacleMap::ObstacleMap(const ObstacleMap& from)
- : ::google::protobuf::Message() {
- SharedCtor();
- MergeFrom(from);
-}
-
-void ObstacleMap::SharedCtor() {
- _cached_size_ = 0;
- header_ = NULL;
- type_ = 0;
- resolution_ = 0;
- rows_ = 0;
- cols_ = 0;
- mapr0_ = 0;
- mapc0_ = 0;
- arrayr0_ = 0;
- arrayc0_ = 0;
- data_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString);
- ::memset(_has_bits_, 0, sizeof(_has_bits_));
-}
-
-ObstacleMap::~ObstacleMap() {
- SharedDtor();
-}
-
-void ObstacleMap::SharedDtor() {
- if (data_ != &::google::protobuf::internal::kEmptyString) {
- delete data_;
- }
- if (this != default_instance_) {
- delete header_;
- }
-}
-
-void ObstacleMap::SetCachedSize(int size) const {
- GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
- _cached_size_ = size;
- GOOGLE_SAFE_CONCURRENT_WRITES_END();
-}
-const ::google::protobuf::Descriptor* ObstacleMap::descriptor() {
- protobuf_AssignDescriptorsOnce();
- return ObstacleMap_descriptor_;
-}
-
-const ObstacleMap& ObstacleMap::default_instance() {
- if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_;
-}
-
-ObstacleMap* ObstacleMap::default_instance_ = NULL;
-
-ObstacleMap* ObstacleMap::New() const {
- return new ObstacleMap;
-}
-
-void ObstacleMap::Clear() {
- if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- if (has_header()) {
- if (header_ != NULL) header_->::px::HeaderInfo::Clear();
- }
- type_ = 0;
- resolution_ = 0;
- rows_ = 0;
- cols_ = 0;
- mapr0_ = 0;
- mapc0_ = 0;
- arrayr0_ = 0;
- }
- if (_has_bits_[8 / 32] & (0xffu << (8 % 32))) {
- arrayc0_ = 0;
- if (has_data()) {
- if (data_ != &::google::protobuf::internal::kEmptyString) {
- data_->clear();
- }
- }
- }
- ::memset(_has_bits_, 0, sizeof(_has_bits_));
- mutable_unknown_fields()->Clear();
-}
-
-bool ObstacleMap::MergePartialFromCodedStream(
- ::google::protobuf::io::CodedInputStream* input) {
-#define DO_(EXPRESSION) if (!(EXPRESSION)) return false
- ::google::protobuf::uint32 tag;
- while ((tag = input->ReadTag()) != 0) {
- switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) {
- // required .px.HeaderInfo header = 1;
- case 1: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
- DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual(
- input, mutable_header()));
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(16)) goto parse_type;
- break;
- }
-
- // required int32 type = 2;
- case 2: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
- parse_type:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>(
- input, &type_)));
- set_has_type();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(29)) goto parse_resolution;
- break;
- }
-
- // optional float resolution = 3;
- case 3: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- parse_resolution:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
- input, &resolution_)));
- set_has_resolution();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(32)) goto parse_rows;
- break;
- }
-
- // optional int32 rows = 4;
- case 4: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
- parse_rows:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>(
- input, &rows_)));
- set_has_rows();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(40)) goto parse_cols;
- break;
- }
-
- // optional int32 cols = 5;
- case 5: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
- parse_cols:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>(
- input, &cols_)));
- set_has_cols();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(48)) goto parse_mapR0;
- break;
- }
-
- // optional int32 mapR0 = 6;
- case 6: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
- parse_mapR0:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>(
- input, &mapr0_)));
- set_has_mapr0();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(56)) goto parse_mapC0;
- break;
- }
-
- // optional int32 mapC0 = 7;
- case 7: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
- parse_mapC0:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>(
- input, &mapc0_)));
- set_has_mapc0();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(64)) goto parse_arrayR0;
- break;
- }
-
- // optional int32 arrayR0 = 8;
- case 8: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
- parse_arrayR0:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>(
- input, &arrayr0_)));
- set_has_arrayr0();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(72)) goto parse_arrayC0;
- break;
- }
-
- // optional int32 arrayC0 = 9;
- case 9: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
- parse_arrayC0:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>(
- input, &arrayc0_)));
- set_has_arrayc0();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(82)) goto parse_data;
- break;
- }
-
- // optional bytes data = 10;
- case 10: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
- parse_data:
- DO_(::google::protobuf::internal::WireFormatLite::ReadBytes(
- input, this->mutable_data()));
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectAtEnd()) return true;
- break;
- }
-
- default: {
- handle_uninterpreted:
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) {
- return true;
- }
- DO_(::google::protobuf::internal::WireFormat::SkipField(
- input, tag, mutable_unknown_fields()));
- break;
- }
- }
- }
- return true;
-#undef DO_
-}
-
-void ObstacleMap::SerializeWithCachedSizes(
- ::google::protobuf::io::CodedOutputStream* output) const {
- // required .px.HeaderInfo header = 1;
- if (has_header()) {
- ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray(
- 1, this->header(), output);
- }
-
- // required int32 type = 2;
- if (has_type()) {
- ::google::protobuf::internal::WireFormatLite::WriteInt32(2, this->type(), output);
- }
-
- // optional float resolution = 3;
- if (has_resolution()) {
- ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->resolution(), output);
- }
-
- // optional int32 rows = 4;
- if (has_rows()) {
- ::google::protobuf::internal::WireFormatLite::WriteInt32(4, this->rows(), output);
- }
-
- // optional int32 cols = 5;
- if (has_cols()) {
- ::google::protobuf::internal::WireFormatLite::WriteInt32(5, this->cols(), output);
- }
-
- // optional int32 mapR0 = 6;
- if (has_mapr0()) {
- ::google::protobuf::internal::WireFormatLite::WriteInt32(6, this->mapr0(), output);
- }
-
- // optional int32 mapC0 = 7;
- if (has_mapc0()) {
- ::google::protobuf::internal::WireFormatLite::WriteInt32(7, this->mapc0(), output);
- }
-
- // optional int32 arrayR0 = 8;
- if (has_arrayr0()) {
- ::google::protobuf::internal::WireFormatLite::WriteInt32(8, this->arrayr0(), output);
- }
-
- // optional int32 arrayC0 = 9;
- if (has_arrayc0()) {
- ::google::protobuf::internal::WireFormatLite::WriteInt32(9, this->arrayc0(), output);
- }
-
- // optional bytes data = 10;
- if (has_data()) {
- ::google::protobuf::internal::WireFormatLite::WriteBytes(
- 10, this->data(), output);
- }
-
- if (!unknown_fields().empty()) {
- ::google::protobuf::internal::WireFormat::SerializeUnknownFields(
- unknown_fields(), output);
- }
-}
-
-::google::protobuf::uint8* ObstacleMap::SerializeWithCachedSizesToArray(
- ::google::protobuf::uint8* target) const {
- // required .px.HeaderInfo header = 1;
- if (has_header()) {
- target = ::google::protobuf::internal::WireFormatLite::
- WriteMessageNoVirtualToArray(
- 1, this->header(), target);
- }
-
- // required int32 type = 2;
- if (has_type()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(2, this->type(), target);
- }
-
- // optional float resolution = 3;
- if (has_resolution()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->resolution(), target);
- }
-
- // optional int32 rows = 4;
- if (has_rows()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(4, this->rows(), target);
- }
-
- // optional int32 cols = 5;
- if (has_cols()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(5, this->cols(), target);
- }
-
- // optional int32 mapR0 = 6;
- if (has_mapr0()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(6, this->mapr0(), target);
- }
-
- // optional int32 mapC0 = 7;
- if (has_mapc0()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(7, this->mapc0(), target);
- }
-
- // optional int32 arrayR0 = 8;
- if (has_arrayr0()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(8, this->arrayr0(), target);
- }
-
- // optional int32 arrayC0 = 9;
- if (has_arrayc0()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(9, this->arrayc0(), target);
- }
-
- // optional bytes data = 10;
- if (has_data()) {
- target =
- ::google::protobuf::internal::WireFormatLite::WriteBytesToArray(
- 10, this->data(), target);
- }
-
- if (!unknown_fields().empty()) {
- target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray(
- unknown_fields(), target);
- }
- return target;
-}
-
-int ObstacleMap::ByteSize() const {
- int total_size = 0;
-
- if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- // required .px.HeaderInfo header = 1;
- if (has_header()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
- this->header());
- }
-
- // required int32 type = 2;
- if (has_type()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::Int32Size(
- this->type());
- }
-
- // optional float resolution = 3;
- if (has_resolution()) {
- total_size += 1 + 4;
- }
-
- // optional int32 rows = 4;
- if (has_rows()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::Int32Size(
- this->rows());
- }
-
- // optional int32 cols = 5;
- if (has_cols()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::Int32Size(
- this->cols());
- }
-
- // optional int32 mapR0 = 6;
- if (has_mapr0()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::Int32Size(
- this->mapr0());
- }
-
- // optional int32 mapC0 = 7;
- if (has_mapc0()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::Int32Size(
- this->mapc0());
- }
-
- // optional int32 arrayR0 = 8;
- if (has_arrayr0()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::Int32Size(
- this->arrayr0());
- }
-
- }
- if (_has_bits_[8 / 32] & (0xffu << (8 % 32))) {
- // optional int32 arrayC0 = 9;
- if (has_arrayc0()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::Int32Size(
- this->arrayc0());
- }
-
- // optional bytes data = 10;
- if (has_data()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::BytesSize(
- this->data());
- }
-
- }
- if (!unknown_fields().empty()) {
- total_size +=
- ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize(
- unknown_fields());
- }
- GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
- _cached_size_ = total_size;
- GOOGLE_SAFE_CONCURRENT_WRITES_END();
- return total_size;
-}
-
-void ObstacleMap::MergeFrom(const ::google::protobuf::Message& from) {
- GOOGLE_CHECK_NE(&from, this);
- const ObstacleMap* source =
- ::google::protobuf::internal::dynamic_cast_if_available<const ObstacleMap*>(
- &from);
- if (source == NULL) {
- ::google::protobuf::internal::ReflectionOps::Merge(from, this);
- } else {
- MergeFrom(*source);
- }
-}
-
-void ObstacleMap::MergeFrom(const ObstacleMap& from) {
- GOOGLE_CHECK_NE(&from, this);
- if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- if (from.has_header()) {
- mutable_header()->::px::HeaderInfo::MergeFrom(from.header());
- }
- if (from.has_type()) {
- set_type(from.type());
- }
- if (from.has_resolution()) {
- set_resolution(from.resolution());
- }
- if (from.has_rows()) {
- set_rows(from.rows());
- }
- if (from.has_cols()) {
- set_cols(from.cols());
- }
- if (from.has_mapr0()) {
- set_mapr0(from.mapr0());
- }
- if (from.has_mapc0()) {
- set_mapc0(from.mapc0());
- }
- if (from.has_arrayr0()) {
- set_arrayr0(from.arrayr0());
- }
- }
- if (from._has_bits_[8 / 32] & (0xffu << (8 % 32))) {
- if (from.has_arrayc0()) {
- set_arrayc0(from.arrayc0());
- }
- if (from.has_data()) {
- set_data(from.data());
- }
- }
- mutable_unknown_fields()->MergeFrom(from.unknown_fields());
-}
-
-void ObstacleMap::CopyFrom(const ::google::protobuf::Message& from) {
- if (&from == this) return;
- Clear();
- MergeFrom(from);
-}
-
-void ObstacleMap::CopyFrom(const ObstacleMap& from) {
- if (&from == this) return;
- Clear();
- MergeFrom(from);
-}
-
-bool ObstacleMap::IsInitialized() const {
- if ((_has_bits_[0] & 0x00000003) != 0x00000003) return false;
-
- if (has_header()) {
- if (!this->header().IsInitialized()) return false;
- }
- return true;
-}
-
-void ObstacleMap::Swap(ObstacleMap* other) {
- if (other != this) {
- std::swap(header_, other->header_);
- std::swap(type_, other->type_);
- std::swap(resolution_, other->resolution_);
- std::swap(rows_, other->rows_);
- std::swap(cols_, other->cols_);
- std::swap(mapr0_, other->mapr0_);
- std::swap(mapc0_, other->mapc0_);
- std::swap(arrayr0_, other->arrayr0_);
- std::swap(arrayc0_, other->arrayc0_);
- std::swap(data_, other->data_);
- std::swap(_has_bits_[0], other->_has_bits_[0]);
- _unknown_fields_.Swap(&other->_unknown_fields_);
- std::swap(_cached_size_, other->_cached_size_);
- }
-}
-
-::google::protobuf::Metadata ObstacleMap::GetMetadata() const {
- protobuf_AssignDescriptorsOnce();
- ::google::protobuf::Metadata metadata;
- metadata.descriptor = ObstacleMap_descriptor_;
- metadata.reflection = ObstacleMap_reflection_;
- return metadata;
-}
-
-
-// ===================================================================
-
-#ifndef _MSC_VER
-const int Path::kHeaderFieldNumber;
-const int Path::kWaypointsFieldNumber;
-#endif // !_MSC_VER
-
-Path::Path()
- : ::google::protobuf::Message() {
- SharedCtor();
-}
-
-void Path::InitAsDefaultInstance() {
- header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance());
-}
-
-Path::Path(const Path& from)
- : ::google::protobuf::Message() {
- SharedCtor();
- MergeFrom(from);
-}
-
-void Path::SharedCtor() {
- _cached_size_ = 0;
- header_ = NULL;
- ::memset(_has_bits_, 0, sizeof(_has_bits_));
-}
-
-Path::~Path() {
- SharedDtor();
-}
-
-void Path::SharedDtor() {
- if (this != default_instance_) {
- delete header_;
- }
-}
-
-void Path::SetCachedSize(int size) const {
- GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
- _cached_size_ = size;
- GOOGLE_SAFE_CONCURRENT_WRITES_END();
-}
-const ::google::protobuf::Descriptor* Path::descriptor() {
- protobuf_AssignDescriptorsOnce();
- return Path_descriptor_;
-}
-
-const Path& Path::default_instance() {
- if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_;
-}
-
-Path* Path::default_instance_ = NULL;
-
-Path* Path::New() const {
- return new Path;
-}
-
-void Path::Clear() {
- if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- if (has_header()) {
- if (header_ != NULL) header_->::px::HeaderInfo::Clear();
- }
- }
- waypoints_.Clear();
- ::memset(_has_bits_, 0, sizeof(_has_bits_));
- mutable_unknown_fields()->Clear();
-}
-
-bool Path::MergePartialFromCodedStream(
- ::google::protobuf::io::CodedInputStream* input) {
-#define DO_(EXPRESSION) if (!(EXPRESSION)) return false
- ::google::protobuf::uint32 tag;
- while ((tag = input->ReadTag()) != 0) {
- switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) {
- // required .px.HeaderInfo header = 1;
- case 1: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
- DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual(
- input, mutable_header()));
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(18)) goto parse_waypoints;
- break;
- }
-
- // repeated .px.Waypoint waypoints = 2;
- case 2: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
- parse_waypoints:
- DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual(
- input, add_waypoints()));
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(18)) goto parse_waypoints;
- if (input->ExpectAtEnd()) return true;
- break;
- }
-
- default: {
- handle_uninterpreted:
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) {
- return true;
- }
- DO_(::google::protobuf::internal::WireFormat::SkipField(
- input, tag, mutable_unknown_fields()));
- break;
- }
- }
- }
- return true;
-#undef DO_
-}
-
-void Path::SerializeWithCachedSizes(
- ::google::protobuf::io::CodedOutputStream* output) const {
- // required .px.HeaderInfo header = 1;
- if (has_header()) {
- ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray(
- 1, this->header(), output);
- }
-
- // repeated .px.Waypoint waypoints = 2;
- for (int i = 0; i < this->waypoints_size(); i++) {
- ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray(
- 2, this->waypoints(i), output);
- }
-
- if (!unknown_fields().empty()) {
- ::google::protobuf::internal::WireFormat::SerializeUnknownFields(
- unknown_fields(), output);
- }
-}
-
-::google::protobuf::uint8* Path::SerializeWithCachedSizesToArray(
- ::google::protobuf::uint8* target) const {
- // required .px.HeaderInfo header = 1;
- if (has_header()) {
- target = ::google::protobuf::internal::WireFormatLite::
- WriteMessageNoVirtualToArray(
- 1, this->header(), target);
- }
-
- // repeated .px.Waypoint waypoints = 2;
- for (int i = 0; i < this->waypoints_size(); i++) {
- target = ::google::protobuf::internal::WireFormatLite::
- WriteMessageNoVirtualToArray(
- 2, this->waypoints(i), target);
- }
-
- if (!unknown_fields().empty()) {
- target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray(
- unknown_fields(), target);
- }
- return target;
-}
-
-int Path::ByteSize() const {
- int total_size = 0;
-
- if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- // required .px.HeaderInfo header = 1;
- if (has_header()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
- this->header());
- }
-
- }
- // repeated .px.Waypoint waypoints = 2;
- total_size += 1 * this->waypoints_size();
- for (int i = 0; i < this->waypoints_size(); i++) {
- total_size +=
- ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
- this->waypoints(i));
- }
-
- if (!unknown_fields().empty()) {
- total_size +=
- ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize(
- unknown_fields());
- }
- GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
- _cached_size_ = total_size;
- GOOGLE_SAFE_CONCURRENT_WRITES_END();
- return total_size;
-}
-
-void Path::MergeFrom(const ::google::protobuf::Message& from) {
- GOOGLE_CHECK_NE(&from, this);
- const Path* source =
- ::google::protobuf::internal::dynamic_cast_if_available<const Path*>(
- &from);
- if (source == NULL) {
- ::google::protobuf::internal::ReflectionOps::Merge(from, this);
- } else {
- MergeFrom(*source);
- }
-}
-
-void Path::MergeFrom(const Path& from) {
- GOOGLE_CHECK_NE(&from, this);
- waypoints_.MergeFrom(from.waypoints_);
- if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- if (from.has_header()) {
- mutable_header()->::px::HeaderInfo::MergeFrom(from.header());
- }
- }
- mutable_unknown_fields()->MergeFrom(from.unknown_fields());
-}
-
-void Path::CopyFrom(const ::google::protobuf::Message& from) {
- if (&from == this) return;
- Clear();
- MergeFrom(from);
-}
-
-void Path::CopyFrom(const Path& from) {
- if (&from == this) return;
- Clear();
- MergeFrom(from);
-}
-
-bool Path::IsInitialized() const {
- if ((_has_bits_[0] & 0x00000001) != 0x00000001) return false;
-
- if (has_header()) {
- if (!this->header().IsInitialized()) return false;
- }
- for (int i = 0; i < waypoints_size(); i++) {
- if (!this->waypoints(i).IsInitialized()) return false;
- }
- return true;
-}
-
-void Path::Swap(Path* other) {
- if (other != this) {
- std::swap(header_, other->header_);
- waypoints_.Swap(&other->waypoints_);
- std::swap(_has_bits_[0], other->_has_bits_[0]);
- _unknown_fields_.Swap(&other->_unknown_fields_);
- std::swap(_cached_size_, other->_cached_size_);
- }
-}
-
-::google::protobuf::Metadata Path::GetMetadata() const {
- protobuf_AssignDescriptorsOnce();
- ::google::protobuf::Metadata metadata;
- metadata.descriptor = Path_descriptor_;
- metadata.reflection = Path_reflection_;
- return metadata;
-}
-
-
-// ===================================================================
-
-#ifndef _MSC_VER
-const int PointCloudXYZI_PointXYZI::kXFieldNumber;
-const int PointCloudXYZI_PointXYZI::kYFieldNumber;
-const int PointCloudXYZI_PointXYZI::kZFieldNumber;
-const int PointCloudXYZI_PointXYZI::kIntensityFieldNumber;
-#endif // !_MSC_VER
-
-PointCloudXYZI_PointXYZI::PointCloudXYZI_PointXYZI()
- : ::google::protobuf::Message() {
- SharedCtor();
-}
-
-void PointCloudXYZI_PointXYZI::InitAsDefaultInstance() {
-}
-
-PointCloudXYZI_PointXYZI::PointCloudXYZI_PointXYZI(const PointCloudXYZI_PointXYZI& from)
- : ::google::protobuf::Message() {
- SharedCtor();
- MergeFrom(from);
-}
-
-void PointCloudXYZI_PointXYZI::SharedCtor() {
- _cached_size_ = 0;
- x_ = 0;
- y_ = 0;
- z_ = 0;
- intensity_ = 0;
- ::memset(_has_bits_, 0, sizeof(_has_bits_));
-}
-
-PointCloudXYZI_PointXYZI::~PointCloudXYZI_PointXYZI() {
- SharedDtor();
-}
-
-void PointCloudXYZI_PointXYZI::SharedDtor() {
- if (this != default_instance_) {
- }
-}
-
-void PointCloudXYZI_PointXYZI::SetCachedSize(int size) const {
- GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
- _cached_size_ = size;
- GOOGLE_SAFE_CONCURRENT_WRITES_END();
-}
-const ::google::protobuf::Descriptor* PointCloudXYZI_PointXYZI::descriptor() {
- protobuf_AssignDescriptorsOnce();
- return PointCloudXYZI_PointXYZI_descriptor_;
-}
-
-const PointCloudXYZI_PointXYZI& PointCloudXYZI_PointXYZI::default_instance() {
- if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_;
-}
-
-PointCloudXYZI_PointXYZI* PointCloudXYZI_PointXYZI::default_instance_ = NULL;
-
-PointCloudXYZI_PointXYZI* PointCloudXYZI_PointXYZI::New() const {
- return new PointCloudXYZI_PointXYZI;
-}
-
-void PointCloudXYZI_PointXYZI::Clear() {
- if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- x_ = 0;
- y_ = 0;
- z_ = 0;
- intensity_ = 0;
- }
- ::memset(_has_bits_, 0, sizeof(_has_bits_));
- mutable_unknown_fields()->Clear();
-}
-
-bool PointCloudXYZI_PointXYZI::MergePartialFromCodedStream(
- ::google::protobuf::io::CodedInputStream* input) {
-#define DO_(EXPRESSION) if (!(EXPRESSION)) return false
- ::google::protobuf::uint32 tag;
- while ((tag = input->ReadTag()) != 0) {
- switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) {
- // required float x = 1;
- case 1: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
- input, &x_)));
- set_has_x();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(21)) goto parse_y;
- break;
- }
-
- // required float y = 2;
- case 2: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- parse_y:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
- input, &y_)));
- set_has_y();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(29)) goto parse_z;
- break;
- }
-
- // required float z = 3;
- case 3: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- parse_z:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
- input, &z_)));
- set_has_z();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(37)) goto parse_intensity;
- break;
- }
-
- // required float intensity = 4;
- case 4: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- parse_intensity:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
- input, &intensity_)));
- set_has_intensity();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectAtEnd()) return true;
- break;
- }
-
- default: {
- handle_uninterpreted:
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) {
- return true;
- }
- DO_(::google::protobuf::internal::WireFormat::SkipField(
- input, tag, mutable_unknown_fields()));
- break;
- }
- }
- }
- return true;
-#undef DO_
-}
-
-void PointCloudXYZI_PointXYZI::SerializeWithCachedSizes(
- ::google::protobuf::io::CodedOutputStream* output) const {
- // required float x = 1;
- if (has_x()) {
- ::google::protobuf::internal::WireFormatLite::WriteFloat(1, this->x(), output);
- }
-
- // required float y = 2;
- if (has_y()) {
- ::google::protobuf::internal::WireFormatLite::WriteFloat(2, this->y(), output);
- }
-
- // required float z = 3;
- if (has_z()) {
- ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->z(), output);
- }
-
- // required float intensity = 4;
- if (has_intensity()) {
- ::google::protobuf::internal::WireFormatLite::WriteFloat(4, this->intensity(), output);
- }
-
- if (!unknown_fields().empty()) {
- ::google::protobuf::internal::WireFormat::SerializeUnknownFields(
- unknown_fields(), output);
- }
-}
-
-::google::protobuf::uint8* PointCloudXYZI_PointXYZI::SerializeWithCachedSizesToArray(
- ::google::protobuf::uint8* target) const {
- // required float x = 1;
- if (has_x()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(1, this->x(), target);
- }
-
- // required float y = 2;
- if (has_y()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(2, this->y(), target);
- }
-
- // required float z = 3;
- if (has_z()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->z(), target);
- }
-
- // required float intensity = 4;
- if (has_intensity()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(4, this->intensity(), target);
- }
-
- if (!unknown_fields().empty()) {
- target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray(
- unknown_fields(), target);
- }
- return target;
-}
-
-int PointCloudXYZI_PointXYZI::ByteSize() const {
- int total_size = 0;
-
- if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- // required float x = 1;
- if (has_x()) {
- total_size += 1 + 4;
- }
-
- // required float y = 2;
- if (has_y()) {
- total_size += 1 + 4;
- }
-
- // required float z = 3;
- if (has_z()) {
- total_size += 1 + 4;
- }
-
- // required float intensity = 4;
- if (has_intensity()) {
- total_size += 1 + 4;
- }
-
- }
- if (!unknown_fields().empty()) {
- total_size +=
- ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize(
- unknown_fields());
- }
- GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
- _cached_size_ = total_size;
- GOOGLE_SAFE_CONCURRENT_WRITES_END();
- return total_size;
-}
-
-void PointCloudXYZI_PointXYZI::MergeFrom(const ::google::protobuf::Message& from) {
- GOOGLE_CHECK_NE(&from, this);
- const PointCloudXYZI_PointXYZI* source =
- ::google::protobuf::internal::dynamic_cast_if_available<const PointCloudXYZI_PointXYZI*>(
- &from);
- if (source == NULL) {
- ::google::protobuf::internal::ReflectionOps::Merge(from, this);
- } else {
- MergeFrom(*source);
- }
-}
-
-void PointCloudXYZI_PointXYZI::MergeFrom(const PointCloudXYZI_PointXYZI& from) {
- GOOGLE_CHECK_NE(&from, this);
- if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- if (from.has_x()) {
- set_x(from.x());
- }
- if (from.has_y()) {
- set_y(from.y());
- }
- if (from.has_z()) {
- set_z(from.z());
- }
- if (from.has_intensity()) {
- set_intensity(from.intensity());
- }
- }
- mutable_unknown_fields()->MergeFrom(from.unknown_fields());
-}
-
-void PointCloudXYZI_PointXYZI::CopyFrom(const ::google::protobuf::Message& from) {
- if (&from == this) return;
- Clear();
- MergeFrom(from);
-}
-
-void PointCloudXYZI_PointXYZI::CopyFrom(const PointCloudXYZI_PointXYZI& from) {
- if (&from == this) return;
- Clear();
- MergeFrom(from);
-}
-
-bool PointCloudXYZI_PointXYZI::IsInitialized() const {
- if ((_has_bits_[0] & 0x0000000f) != 0x0000000f) return false;
-
- return true;
-}
-
-void PointCloudXYZI_PointXYZI::Swap(PointCloudXYZI_PointXYZI* other) {
- if (other != this) {
- std::swap(x_, other->x_);
- std::swap(y_, other->y_);
- std::swap(z_, other->z_);
- std::swap(intensity_, other->intensity_);
- std::swap(_has_bits_[0], other->_has_bits_[0]);
- _unknown_fields_.Swap(&other->_unknown_fields_);
- std::swap(_cached_size_, other->_cached_size_);
- }
-}
-
-::google::protobuf::Metadata PointCloudXYZI_PointXYZI::GetMetadata() const {
- protobuf_AssignDescriptorsOnce();
- ::google::protobuf::Metadata metadata;
- metadata.descriptor = PointCloudXYZI_PointXYZI_descriptor_;
- metadata.reflection = PointCloudXYZI_PointXYZI_reflection_;
- return metadata;
-}
-
-
-// -------------------------------------------------------------------
-
-#ifndef _MSC_VER
-const int PointCloudXYZI::kHeaderFieldNumber;
-const int PointCloudXYZI::kPointsFieldNumber;
-#endif // !_MSC_VER
-
-PointCloudXYZI::PointCloudXYZI()
- : ::google::protobuf::Message() {
- SharedCtor();
-}
-
-void PointCloudXYZI::InitAsDefaultInstance() {
- header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance());
-}
-
-PointCloudXYZI::PointCloudXYZI(const PointCloudXYZI& from)
- : ::google::protobuf::Message() {
- SharedCtor();
- MergeFrom(from);
-}
-
-void PointCloudXYZI::SharedCtor() {
- _cached_size_ = 0;
- header_ = NULL;
- ::memset(_has_bits_, 0, sizeof(_has_bits_));
-}
-
-PointCloudXYZI::~PointCloudXYZI() {
- SharedDtor();
-}
-
-void PointCloudXYZI::SharedDtor() {
- if (this != default_instance_) {
- delete header_;
- }
-}
-
-void PointCloudXYZI::SetCachedSize(int size) const {
- GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
- _cached_size_ = size;
- GOOGLE_SAFE_CONCURRENT_WRITES_END();
-}
-const ::google::protobuf::Descriptor* PointCloudXYZI::descriptor() {
- protobuf_AssignDescriptorsOnce();
- return PointCloudXYZI_descriptor_;
-}
-
-const PointCloudXYZI& PointCloudXYZI::default_instance() {
- if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_;
-}
-
-PointCloudXYZI* PointCloudXYZI::default_instance_ = NULL;
-
-PointCloudXYZI* PointCloudXYZI::New() const {
- return new PointCloudXYZI;
-}
-
-void PointCloudXYZI::Clear() {
- if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- if (has_header()) {
- if (header_ != NULL) header_->::px::HeaderInfo::Clear();
- }
- }
- points_.Clear();
- ::memset(_has_bits_, 0, sizeof(_has_bits_));
- mutable_unknown_fields()->Clear();
-}
-
-bool PointCloudXYZI::MergePartialFromCodedStream(
- ::google::protobuf::io::CodedInputStream* input) {
-#define DO_(EXPRESSION) if (!(EXPRESSION)) return false
- ::google::protobuf::uint32 tag;
- while ((tag = input->ReadTag()) != 0) {
- switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) {
- // required .px.HeaderInfo header = 1;
- case 1: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
- DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual(
- input, mutable_header()));
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(18)) goto parse_points;
- break;
- }
-
- // repeated .px.PointCloudXYZI.PointXYZI points = 2;
- case 2: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
- parse_points:
- DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual(
- input, add_points()));
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(18)) goto parse_points;
- if (input->ExpectAtEnd()) return true;
- break;
- }
-
- default: {
- handle_uninterpreted:
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) {
- return true;
- }
- DO_(::google::protobuf::internal::WireFormat::SkipField(
- input, tag, mutable_unknown_fields()));
- break;
- }
- }
- }
- return true;
-#undef DO_
-}
-
-void PointCloudXYZI::SerializeWithCachedSizes(
- ::google::protobuf::io::CodedOutputStream* output) const {
- // required .px.HeaderInfo header = 1;
- if (has_header()) {
- ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray(
- 1, this->header(), output);
- }
-
- // repeated .px.PointCloudXYZI.PointXYZI points = 2;
- for (int i = 0; i < this->points_size(); i++) {
- ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray(
- 2, this->points(i), output);
- }
-
- if (!unknown_fields().empty()) {
- ::google::protobuf::internal::WireFormat::SerializeUnknownFields(
- unknown_fields(), output);
- }
-}
-
-::google::protobuf::uint8* PointCloudXYZI::SerializeWithCachedSizesToArray(
- ::google::protobuf::uint8* target) const {
- // required .px.HeaderInfo header = 1;
- if (has_header()) {
- target = ::google::protobuf::internal::WireFormatLite::
- WriteMessageNoVirtualToArray(
- 1, this->header(), target);
- }
-
- // repeated .px.PointCloudXYZI.PointXYZI points = 2;
- for (int i = 0; i < this->points_size(); i++) {
- target = ::google::protobuf::internal::WireFormatLite::
- WriteMessageNoVirtualToArray(
- 2, this->points(i), target);
- }
-
- if (!unknown_fields().empty()) {
- target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray(
- unknown_fields(), target);
- }
- return target;
-}
-
-int PointCloudXYZI::ByteSize() const {
- int total_size = 0;
-
- if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- // required .px.HeaderInfo header = 1;
- if (has_header()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
- this->header());
- }
-
- }
- // repeated .px.PointCloudXYZI.PointXYZI points = 2;
- total_size += 1 * this->points_size();
- for (int i = 0; i < this->points_size(); i++) {
- total_size +=
- ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
- this->points(i));
- }
-
- if (!unknown_fields().empty()) {
- total_size +=
- ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize(
- unknown_fields());
- }
- GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
- _cached_size_ = total_size;
- GOOGLE_SAFE_CONCURRENT_WRITES_END();
- return total_size;
-}
-
-void PointCloudXYZI::MergeFrom(const ::google::protobuf::Message& from) {
- GOOGLE_CHECK_NE(&from, this);
- const PointCloudXYZI* source =
- ::google::protobuf::internal::dynamic_cast_if_available<const PointCloudXYZI*>(
- &from);
- if (source == NULL) {
- ::google::protobuf::internal::ReflectionOps::Merge(from, this);
- } else {
- MergeFrom(*source);
- }
-}
-
-void PointCloudXYZI::MergeFrom(const PointCloudXYZI& from) {
- GOOGLE_CHECK_NE(&from, this);
- points_.MergeFrom(from.points_);
- if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- if (from.has_header()) {
- mutable_header()->::px::HeaderInfo::MergeFrom(from.header());
- }
- }
- mutable_unknown_fields()->MergeFrom(from.unknown_fields());
-}
-
-void PointCloudXYZI::CopyFrom(const ::google::protobuf::Message& from) {
- if (&from == this) return;
- Clear();
- MergeFrom(from);
-}
-
-void PointCloudXYZI::CopyFrom(const PointCloudXYZI& from) {
- if (&from == this) return;
- Clear();
- MergeFrom(from);
-}
-
-bool PointCloudXYZI::IsInitialized() const {
- if ((_has_bits_[0] & 0x00000001) != 0x00000001) return false;
-
- if (has_header()) {
- if (!this->header().IsInitialized()) return false;
- }
- for (int i = 0; i < points_size(); i++) {
- if (!this->points(i).IsInitialized()) return false;
- }
- return true;
-}
-
-void PointCloudXYZI::Swap(PointCloudXYZI* other) {
- if (other != this) {
- std::swap(header_, other->header_);
- points_.Swap(&other->points_);
- std::swap(_has_bits_[0], other->_has_bits_[0]);
- _unknown_fields_.Swap(&other->_unknown_fields_);
- std::swap(_cached_size_, other->_cached_size_);
- }
-}
-
-::google::protobuf::Metadata PointCloudXYZI::GetMetadata() const {
- protobuf_AssignDescriptorsOnce();
- ::google::protobuf::Metadata metadata;
- metadata.descriptor = PointCloudXYZI_descriptor_;
- metadata.reflection = PointCloudXYZI_reflection_;
- return metadata;
-}
-
-
-// ===================================================================
-
-#ifndef _MSC_VER
-const int PointCloudXYZRGB_PointXYZRGB::kXFieldNumber;
-const int PointCloudXYZRGB_PointXYZRGB::kYFieldNumber;
-const int PointCloudXYZRGB_PointXYZRGB::kZFieldNumber;
-const int PointCloudXYZRGB_PointXYZRGB::kRgbFieldNumber;
-#endif // !_MSC_VER
-
-PointCloudXYZRGB_PointXYZRGB::PointCloudXYZRGB_PointXYZRGB()
- : ::google::protobuf::Message() {
- SharedCtor();
-}
-
-void PointCloudXYZRGB_PointXYZRGB::InitAsDefaultInstance() {
-}
-
-PointCloudXYZRGB_PointXYZRGB::PointCloudXYZRGB_PointXYZRGB(const PointCloudXYZRGB_PointXYZRGB& from)
- : ::google::protobuf::Message() {
- SharedCtor();
- MergeFrom(from);
-}
-
-void PointCloudXYZRGB_PointXYZRGB::SharedCtor() {
- _cached_size_ = 0;
- x_ = 0;
- y_ = 0;
- z_ = 0;
- rgb_ = 0;
- ::memset(_has_bits_, 0, sizeof(_has_bits_));
-}
-
-PointCloudXYZRGB_PointXYZRGB::~PointCloudXYZRGB_PointXYZRGB() {
- SharedDtor();
-}
-
-void PointCloudXYZRGB_PointXYZRGB::SharedDtor() {
- if (this != default_instance_) {
- }
-}
-
-void PointCloudXYZRGB_PointXYZRGB::SetCachedSize(int size) const {
- GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
- _cached_size_ = size;
- GOOGLE_SAFE_CONCURRENT_WRITES_END();
-}
-const ::google::protobuf::Descriptor* PointCloudXYZRGB_PointXYZRGB::descriptor() {
- protobuf_AssignDescriptorsOnce();
- return PointCloudXYZRGB_PointXYZRGB_descriptor_;
-}
-
-const PointCloudXYZRGB_PointXYZRGB& PointCloudXYZRGB_PointXYZRGB::default_instance() {
- if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_;
-}
-
-PointCloudXYZRGB_PointXYZRGB* PointCloudXYZRGB_PointXYZRGB::default_instance_ = NULL;
-
-PointCloudXYZRGB_PointXYZRGB* PointCloudXYZRGB_PointXYZRGB::New() const {
- return new PointCloudXYZRGB_PointXYZRGB;
-}
-
-void PointCloudXYZRGB_PointXYZRGB::Clear() {
- if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- x_ = 0;
- y_ = 0;
- z_ = 0;
- rgb_ = 0;
- }
- ::memset(_has_bits_, 0, sizeof(_has_bits_));
- mutable_unknown_fields()->Clear();
-}
-
-bool PointCloudXYZRGB_PointXYZRGB::MergePartialFromCodedStream(
- ::google::protobuf::io::CodedInputStream* input) {
-#define DO_(EXPRESSION) if (!(EXPRESSION)) return false
- ::google::protobuf::uint32 tag;
- while ((tag = input->ReadTag()) != 0) {
- switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) {
- // required float x = 1;
- case 1: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
- input, &x_)));
- set_has_x();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(21)) goto parse_y;
- break;
- }
-
- // required float y = 2;
- case 2: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- parse_y:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
- input, &y_)));
- set_has_y();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(29)) goto parse_z;
- break;
- }
-
- // required float z = 3;
- case 3: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- parse_z:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
- input, &z_)));
- set_has_z();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(37)) goto parse_rgb;
- break;
- }
-
- // required float rgb = 4;
- case 4: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- parse_rgb:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
- input, &rgb_)));
- set_has_rgb();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectAtEnd()) return true;
- break;
- }
-
- default: {
- handle_uninterpreted:
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) {
- return true;
- }
- DO_(::google::protobuf::internal::WireFormat::SkipField(
- input, tag, mutable_unknown_fields()));
- break;
- }
- }
- }
- return true;
-#undef DO_
-}
-
-void PointCloudXYZRGB_PointXYZRGB::SerializeWithCachedSizes(
- ::google::protobuf::io::CodedOutputStream* output) const {
- // required float x = 1;
- if (has_x()) {
- ::google::protobuf::internal::WireFormatLite::WriteFloat(1, this->x(), output);
- }
-
- // required float y = 2;
- if (has_y()) {
- ::google::protobuf::internal::WireFormatLite::WriteFloat(2, this->y(), output);
- }
-
- // required float z = 3;
- if (has_z()) {
- ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->z(), output);
- }
-
- // required float rgb = 4;
- if (has_rgb()) {
- ::google::protobuf::internal::WireFormatLite::WriteFloat(4, this->rgb(), output);
- }
-
- if (!unknown_fields().empty()) {
- ::google::protobuf::internal::WireFormat::SerializeUnknownFields(
- unknown_fields(), output);
- }
-}
-
-::google::protobuf::uint8* PointCloudXYZRGB_PointXYZRGB::SerializeWithCachedSizesToArray(
- ::google::protobuf::uint8* target) const {
- // required float x = 1;
- if (has_x()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(1, this->x(), target);
- }
-
- // required float y = 2;
- if (has_y()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(2, this->y(), target);
- }
-
- // required float z = 3;
- if (has_z()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->z(), target);
- }
-
- // required float rgb = 4;
- if (has_rgb()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(4, this->rgb(), target);
- }
-
- if (!unknown_fields().empty()) {
- target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray(
- unknown_fields(), target);
- }
- return target;
-}
-
-int PointCloudXYZRGB_PointXYZRGB::ByteSize() const {
- int total_size = 0;
-
- if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- // required float x = 1;
- if (has_x()) {
- total_size += 1 + 4;
- }
-
- // required float y = 2;
- if (has_y()) {
- total_size += 1 + 4;
- }
-
- // required float z = 3;
- if (has_z()) {
- total_size += 1 + 4;
- }
-
- // required float rgb = 4;
- if (has_rgb()) {
- total_size += 1 + 4;
- }
-
- }
- if (!unknown_fields().empty()) {
- total_size +=
- ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize(
- unknown_fields());
- }
- GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
- _cached_size_ = total_size;
- GOOGLE_SAFE_CONCURRENT_WRITES_END();
- return total_size;
-}
-
-void PointCloudXYZRGB_PointXYZRGB::MergeFrom(const ::google::protobuf::Message& from) {
- GOOGLE_CHECK_NE(&from, this);
- const PointCloudXYZRGB_PointXYZRGB* source =
- ::google::protobuf::internal::dynamic_cast_if_available<const PointCloudXYZRGB_PointXYZRGB*>(
- &from);
- if (source == NULL) {
- ::google::protobuf::internal::ReflectionOps::Merge(from, this);
- } else {
- MergeFrom(*source);
- }
-}
-
-void PointCloudXYZRGB_PointXYZRGB::MergeFrom(const PointCloudXYZRGB_PointXYZRGB& from) {
- GOOGLE_CHECK_NE(&from, this);
- if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- if (from.has_x()) {
- set_x(from.x());
- }
- if (from.has_y()) {
- set_y(from.y());
- }
- if (from.has_z()) {
- set_z(from.z());
- }
- if (from.has_rgb()) {
- set_rgb(from.rgb());
- }
- }
- mutable_unknown_fields()->MergeFrom(from.unknown_fields());
-}
-
-void PointCloudXYZRGB_PointXYZRGB::CopyFrom(const ::google::protobuf::Message& from) {
- if (&from == this) return;
- Clear();
- MergeFrom(from);
-}
-
-void PointCloudXYZRGB_PointXYZRGB::CopyFrom(const PointCloudXYZRGB_PointXYZRGB& from) {
- if (&from == this) return;
- Clear();
- MergeFrom(from);
-}
-
-bool PointCloudXYZRGB_PointXYZRGB::IsInitialized() const {
- if ((_has_bits_[0] & 0x0000000f) != 0x0000000f) return false;
-
- return true;
-}
-
-void PointCloudXYZRGB_PointXYZRGB::Swap(PointCloudXYZRGB_PointXYZRGB* other) {
- if (other != this) {
- std::swap(x_, other->x_);
- std::swap(y_, other->y_);
- std::swap(z_, other->z_);
- std::swap(rgb_, other->rgb_);
- std::swap(_has_bits_[0], other->_has_bits_[0]);
- _unknown_fields_.Swap(&other->_unknown_fields_);
- std::swap(_cached_size_, other->_cached_size_);
- }
-}
-
-::google::protobuf::Metadata PointCloudXYZRGB_PointXYZRGB::GetMetadata() const {
- protobuf_AssignDescriptorsOnce();
- ::google::protobuf::Metadata metadata;
- metadata.descriptor = PointCloudXYZRGB_PointXYZRGB_descriptor_;
- metadata.reflection = PointCloudXYZRGB_PointXYZRGB_reflection_;
- return metadata;
-}
-
-
-// -------------------------------------------------------------------
-
-#ifndef _MSC_VER
-const int PointCloudXYZRGB::kHeaderFieldNumber;
-const int PointCloudXYZRGB::kPointsFieldNumber;
-#endif // !_MSC_VER
-
-PointCloudXYZRGB::PointCloudXYZRGB()
- : ::google::protobuf::Message() {
- SharedCtor();
-}
-
-void PointCloudXYZRGB::InitAsDefaultInstance() {
- header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance());
-}
-
-PointCloudXYZRGB::PointCloudXYZRGB(const PointCloudXYZRGB& from)
- : ::google::protobuf::Message() {
- SharedCtor();
- MergeFrom(from);
-}
-
-void PointCloudXYZRGB::SharedCtor() {
- _cached_size_ = 0;
- header_ = NULL;
- ::memset(_has_bits_, 0, sizeof(_has_bits_));
-}
-
-PointCloudXYZRGB::~PointCloudXYZRGB() {
- SharedDtor();
-}
-
-void PointCloudXYZRGB::SharedDtor() {
- if (this != default_instance_) {
- delete header_;
- }
-}
-
-void PointCloudXYZRGB::SetCachedSize(int size) const {
- GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
- _cached_size_ = size;
- GOOGLE_SAFE_CONCURRENT_WRITES_END();
-}
-const ::google::protobuf::Descriptor* PointCloudXYZRGB::descriptor() {
- protobuf_AssignDescriptorsOnce();
- return PointCloudXYZRGB_descriptor_;
-}
-
-const PointCloudXYZRGB& PointCloudXYZRGB::default_instance() {
- if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_;
-}
-
-PointCloudXYZRGB* PointCloudXYZRGB::default_instance_ = NULL;
-
-PointCloudXYZRGB* PointCloudXYZRGB::New() const {
- return new PointCloudXYZRGB;
-}
-
-void PointCloudXYZRGB::Clear() {
- if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- if (has_header()) {
- if (header_ != NULL) header_->::px::HeaderInfo::Clear();
- }
- }
- points_.Clear();
- ::memset(_has_bits_, 0, sizeof(_has_bits_));
- mutable_unknown_fields()->Clear();
-}
-
-bool PointCloudXYZRGB::MergePartialFromCodedStream(
- ::google::protobuf::io::CodedInputStream* input) {
-#define DO_(EXPRESSION) if (!(EXPRESSION)) return false
- ::google::protobuf::uint32 tag;
- while ((tag = input->ReadTag()) != 0) {
- switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) {
- // required .px.HeaderInfo header = 1;
- case 1: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
- DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual(
- input, mutable_header()));
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(18)) goto parse_points;
- break;
- }
-
- // repeated .px.PointCloudXYZRGB.PointXYZRGB points = 2;
- case 2: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
- parse_points:
- DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual(
- input, add_points()));
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(18)) goto parse_points;
- if (input->ExpectAtEnd()) return true;
- break;
- }
-
- default: {
- handle_uninterpreted:
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) {
- return true;
- }
- DO_(::google::protobuf::internal::WireFormat::SkipField(
- input, tag, mutable_unknown_fields()));
- break;
- }
- }
- }
- return true;
-#undef DO_
-}
-
-void PointCloudXYZRGB::SerializeWithCachedSizes(
- ::google::protobuf::io::CodedOutputStream* output) const {
- // required .px.HeaderInfo header = 1;
- if (has_header()) {
- ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray(
- 1, this->header(), output);
- }
-
- // repeated .px.PointCloudXYZRGB.PointXYZRGB points = 2;
- for (int i = 0; i < this->points_size(); i++) {
- ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray(
- 2, this->points(i), output);
- }
-
- if (!unknown_fields().empty()) {
- ::google::protobuf::internal::WireFormat::SerializeUnknownFields(
- unknown_fields(), output);
- }
-}
-
-::google::protobuf::uint8* PointCloudXYZRGB::SerializeWithCachedSizesToArray(
- ::google::protobuf::uint8* target) const {
- // required .px.HeaderInfo header = 1;
- if (has_header()) {
- target = ::google::protobuf::internal::WireFormatLite::
- WriteMessageNoVirtualToArray(
- 1, this->header(), target);
- }
-
- // repeated .px.PointCloudXYZRGB.PointXYZRGB points = 2;
- for (int i = 0; i < this->points_size(); i++) {
- target = ::google::protobuf::internal::WireFormatLite::
- WriteMessageNoVirtualToArray(
- 2, this->points(i), target);
- }
-
- if (!unknown_fields().empty()) {
- target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray(
- unknown_fields(), target);
- }
- return target;
-}
-
-int PointCloudXYZRGB::ByteSize() const {
- int total_size = 0;
-
- if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- // required .px.HeaderInfo header = 1;
- if (has_header()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
- this->header());
- }
-
- }
- // repeated .px.PointCloudXYZRGB.PointXYZRGB points = 2;
- total_size += 1 * this->points_size();
- for (int i = 0; i < this->points_size(); i++) {
- total_size +=
- ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
- this->points(i));
- }
-
- if (!unknown_fields().empty()) {
- total_size +=
- ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize(
- unknown_fields());
- }
- GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
- _cached_size_ = total_size;
- GOOGLE_SAFE_CONCURRENT_WRITES_END();
- return total_size;
-}
-
-void PointCloudXYZRGB::MergeFrom(const ::google::protobuf::Message& from) {
- GOOGLE_CHECK_NE(&from, this);
- const PointCloudXYZRGB* source =
- ::google::protobuf::internal::dynamic_cast_if_available<const PointCloudXYZRGB*>(
- &from);
- if (source == NULL) {
- ::google::protobuf::internal::ReflectionOps::Merge(from, this);
- } else {
- MergeFrom(*source);
- }
-}
-
-void PointCloudXYZRGB::MergeFrom(const PointCloudXYZRGB& from) {
- GOOGLE_CHECK_NE(&from, this);
- points_.MergeFrom(from.points_);
- if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- if (from.has_header()) {
- mutable_header()->::px::HeaderInfo::MergeFrom(from.header());
- }
- }
- mutable_unknown_fields()->MergeFrom(from.unknown_fields());
-}
-
-void PointCloudXYZRGB::CopyFrom(const ::google::protobuf::Message& from) {
- if (&from == this) return;
- Clear();
- MergeFrom(from);
-}
-
-void PointCloudXYZRGB::CopyFrom(const PointCloudXYZRGB& from) {
- if (&from == this) return;
- Clear();
- MergeFrom(from);
-}
-
-bool PointCloudXYZRGB::IsInitialized() const {
- if ((_has_bits_[0] & 0x00000001) != 0x00000001) return false;
-
- if (has_header()) {
- if (!this->header().IsInitialized()) return false;
- }
- for (int i = 0; i < points_size(); i++) {
- if (!this->points(i).IsInitialized()) return false;
- }
- return true;
-}
-
-void PointCloudXYZRGB::Swap(PointCloudXYZRGB* other) {
- if (other != this) {
- std::swap(header_, other->header_);
- points_.Swap(&other->points_);
- std::swap(_has_bits_[0], other->_has_bits_[0]);
- _unknown_fields_.Swap(&other->_unknown_fields_);
- std::swap(_cached_size_, other->_cached_size_);
- }
-}
-
-::google::protobuf::Metadata PointCloudXYZRGB::GetMetadata() const {
- protobuf_AssignDescriptorsOnce();
- ::google::protobuf::Metadata metadata;
- metadata.descriptor = PointCloudXYZRGB_descriptor_;
- metadata.reflection = PointCloudXYZRGB_reflection_;
- return metadata;
-}
-
-
-// ===================================================================
-
-#ifndef _MSC_VER
-const int RGBDImage::kHeaderFieldNumber;
-const int RGBDImage::kColsFieldNumber;
-const int RGBDImage::kRowsFieldNumber;
-const int RGBDImage::kStep1FieldNumber;
-const int RGBDImage::kType1FieldNumber;
-const int RGBDImage::kImageData1FieldNumber;
-const int RGBDImage::kStep2FieldNumber;
-const int RGBDImage::kType2FieldNumber;
-const int RGBDImage::kImageData2FieldNumber;
-const int RGBDImage::kCameraConfigFieldNumber;
-const int RGBDImage::kCameraTypeFieldNumber;
-const int RGBDImage::kRollFieldNumber;
-const int RGBDImage::kPitchFieldNumber;
-const int RGBDImage::kYawFieldNumber;
-const int RGBDImage::kLonFieldNumber;
-const int RGBDImage::kLatFieldNumber;
-const int RGBDImage::kAltFieldNumber;
-const int RGBDImage::kGroundXFieldNumber;
-const int RGBDImage::kGroundYFieldNumber;
-const int RGBDImage::kGroundZFieldNumber;
-const int RGBDImage::kCameraMatrixFieldNumber;
-#endif // !_MSC_VER
-
-RGBDImage::RGBDImage()
- : ::google::protobuf::Message() {
- SharedCtor();
-}
-
-void RGBDImage::InitAsDefaultInstance() {
- header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance());
-}
-
-RGBDImage::RGBDImage(const RGBDImage& from)
- : ::google::protobuf::Message() {
- SharedCtor();
- MergeFrom(from);
-}
-
-void RGBDImage::SharedCtor() {
- _cached_size_ = 0;
- header_ = NULL;
- cols_ = 0u;
- rows_ = 0u;
- step1_ = 0u;
- type1_ = 0u;
- imagedata1_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString);
- step2_ = 0u;
- type2_ = 0u;
- imagedata2_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString);
- camera_config_ = 0u;
- camera_type_ = 0u;
- roll_ = 0;
- pitch_ = 0;
- yaw_ = 0;
- lon_ = 0;
- lat_ = 0;
- alt_ = 0;
- ground_x_ = 0;
- ground_y_ = 0;
- ground_z_ = 0;
- ::memset(_has_bits_, 0, sizeof(_has_bits_));
-}
-
-RGBDImage::~RGBDImage() {
- SharedDtor();
-}
-
-void RGBDImage::SharedDtor() {
- if (imagedata1_ != &::google::protobuf::internal::kEmptyString) {
- delete imagedata1_;
- }
- if (imagedata2_ != &::google::protobuf::internal::kEmptyString) {
- delete imagedata2_;
- }
- if (this != default_instance_) {
- delete header_;
- }
-}
-
-void RGBDImage::SetCachedSize(int size) const {
- GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
- _cached_size_ = size;
- GOOGLE_SAFE_CONCURRENT_WRITES_END();
-}
-const ::google::protobuf::Descriptor* RGBDImage::descriptor() {
- protobuf_AssignDescriptorsOnce();
- return RGBDImage_descriptor_;
-}
-
-const RGBDImage& RGBDImage::default_instance() {
- if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_;
-}
-
-RGBDImage* RGBDImage::default_instance_ = NULL;
-
-RGBDImage* RGBDImage::New() const {
- return new RGBDImage;
-}
-
-void RGBDImage::Clear() {
- if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- if (has_header()) {
- if (header_ != NULL) header_->::px::HeaderInfo::Clear();
- }
- cols_ = 0u;
- rows_ = 0u;
- step1_ = 0u;
- type1_ = 0u;
- if (has_imagedata1()) {
- if (imagedata1_ != &::google::protobuf::internal::kEmptyString) {
- imagedata1_->clear();
- }
- }
- step2_ = 0u;
- type2_ = 0u;
- }
- if (_has_bits_[8 / 32] & (0xffu << (8 % 32))) {
- if (has_imagedata2()) {
- if (imagedata2_ != &::google::protobuf::internal::kEmptyString) {
- imagedata2_->clear();
- }
- }
- camera_config_ = 0u;
- camera_type_ = 0u;
- roll_ = 0;
- pitch_ = 0;
- yaw_ = 0;
- lon_ = 0;
- lat_ = 0;
- }
- if (_has_bits_[16 / 32] & (0xffu << (16 % 32))) {
- alt_ = 0;
- ground_x_ = 0;
- ground_y_ = 0;
- ground_z_ = 0;
- }
- camera_matrix_.Clear();
- ::memset(_has_bits_, 0, sizeof(_has_bits_));
- mutable_unknown_fields()->Clear();
-}
-
-bool RGBDImage::MergePartialFromCodedStream(
- ::google::protobuf::io::CodedInputStream* input) {
-#define DO_(EXPRESSION) if (!(EXPRESSION)) return false
- ::google::protobuf::uint32 tag;
- while ((tag = input->ReadTag()) != 0) {
- switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) {
- // required .px.HeaderInfo header = 1;
- case 1: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
- DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual(
- input, mutable_header()));
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(16)) goto parse_cols;
- break;
- }
-
- // required uint32 cols = 2;
- case 2: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
- parse_cols:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>(
- input, &cols_)));
- set_has_cols();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(24)) goto parse_rows;
- break;
- }
-
- // required uint32 rows = 3;
- case 3: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
- parse_rows:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>(
- input, &rows_)));
- set_has_rows();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(32)) goto parse_step1;
- break;
- }
-
- // required uint32 step1 = 4;
- case 4: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
- parse_step1:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>(
- input, &step1_)));
- set_has_step1();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(40)) goto parse_type1;
- break;
- }
-
- // required uint32 type1 = 5;
- case 5: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
- parse_type1:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>(
- input, &type1_)));
- set_has_type1();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(50)) goto parse_imageData1;
- break;
- }
-
- // required bytes imageData1 = 6;
- case 6: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
- parse_imageData1:
- DO_(::google::protobuf::internal::WireFormatLite::ReadBytes(
- input, this->mutable_imagedata1()));
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(56)) goto parse_step2;
- break;
- }
-
- // required uint32 step2 = 7;
- case 7: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
- parse_step2:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>(
- input, &step2_)));
- set_has_step2();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(64)) goto parse_type2;
- break;
- }
-
- // required uint32 type2 = 8;
- case 8: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
- parse_type2:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>(
- input, &type2_)));
- set_has_type2();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(74)) goto parse_imageData2;
- break;
- }
-
- // required bytes imageData2 = 9;
- case 9: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
- parse_imageData2:
- DO_(::google::protobuf::internal::WireFormatLite::ReadBytes(
- input, this->mutable_imagedata2()));
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(80)) goto parse_camera_config;
- break;
- }
-
- // optional uint32 camera_config = 10;
- case 10: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
- parse_camera_config:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>(
- input, &camera_config_)));
- set_has_camera_config();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(88)) goto parse_camera_type;
- break;
- }
-
- // optional uint32 camera_type = 11;
- case 11: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
- parse_camera_type:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>(
- input, &camera_type_)));
- set_has_camera_type();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(101)) goto parse_roll;
- break;
- }
-
- // optional float roll = 12;
- case 12: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- parse_roll:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
- input, &roll_)));
- set_has_roll();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(109)) goto parse_pitch;
- break;
- }
-
- // optional float pitch = 13;
- case 13: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- parse_pitch:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
- input, &pitch_)));
- set_has_pitch();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(117)) goto parse_yaw;
- break;
- }
-
- // optional float yaw = 14;
- case 14: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- parse_yaw:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
- input, &yaw_)));
- set_has_yaw();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(125)) goto parse_lon;
- break;
- }
-
- // optional float lon = 15;
- case 15: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- parse_lon:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
- input, &lon_)));
- set_has_lon();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(133)) goto parse_lat;
- break;
- }
-
- // optional float lat = 16;
- case 16: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- parse_lat:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
- input, &lat_)));
- set_has_lat();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(141)) goto parse_alt;
- break;
- }
-
- // optional float alt = 17;
- case 17: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- parse_alt:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
- input, &alt_)));
- set_has_alt();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(149)) goto parse_ground_x;
- break;
- }
-
- // optional float ground_x = 18;
- case 18: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- parse_ground_x:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
- input, &ground_x_)));
- set_has_ground_x();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(157)) goto parse_ground_y;
- break;
- }
-
- // optional float ground_y = 19;
- case 19: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- parse_ground_y:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
- input, &ground_y_)));
- set_has_ground_y();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(165)) goto parse_ground_z;
- break;
- }
-
- // optional float ground_z = 20;
- case 20: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- parse_ground_z:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
- input, &ground_z_)));
- set_has_ground_z();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(173)) goto parse_camera_matrix;
- break;
- }
-
- // repeated float camera_matrix = 21;
- case 21: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- parse_camera_matrix:
- DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitive<
- float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
- 2, 173, input, this->mutable_camera_matrix())));
- } else if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag)
- == ::google::protobuf::internal::WireFormatLite::
- WIRETYPE_LENGTH_DELIMITED) {
- DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitiveNoInline<
- float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
- input, this->mutable_camera_matrix())));
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(173)) goto parse_camera_matrix;
- if (input->ExpectAtEnd()) return true;
- break;
- }
-
- default: {
- handle_uninterpreted:
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) {
- return true;
- }
- DO_(::google::protobuf::internal::WireFormat::SkipField(
- input, tag, mutable_unknown_fields()));
- break;
- }
- }
- }
- return true;
-#undef DO_
-}
-
-void RGBDImage::SerializeWithCachedSizes(
- ::google::protobuf::io::CodedOutputStream* output) const {
- // required .px.HeaderInfo header = 1;
- if (has_header()) {
- ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray(
- 1, this->header(), output);
- }
-
- // required uint32 cols = 2;
- if (has_cols()) {
- ::google::protobuf::internal::WireFormatLite::WriteUInt32(2, this->cols(), output);
- }
-
- // required uint32 rows = 3;
- if (has_rows()) {
- ::google::protobuf::internal::WireFormatLite::WriteUInt32(3, this->rows(), output);
- }
-
- // required uint32 step1 = 4;
- if (has_step1()) {
- ::google::protobuf::internal::WireFormatLite::WriteUInt32(4, this->step1(), output);
- }
-
- // required uint32 type1 = 5;
- if (has_type1()) {
- ::google::protobuf::internal::WireFormatLite::WriteUInt32(5, this->type1(), output);
- }
-
- // required bytes imageData1 = 6;
- if (has_imagedata1()) {
- ::google::protobuf::internal::WireFormatLite::WriteBytes(
- 6, this->imagedata1(), output);
- }
-
- // required uint32 step2 = 7;
- if (has_step2()) {
- ::google::protobuf::internal::WireFormatLite::WriteUInt32(7, this->step2(), output);
- }
-
- // required uint32 type2 = 8;
- if (has_type2()) {
- ::google::protobuf::internal::WireFormatLite::WriteUInt32(8, this->type2(), output);
- }
-
- // required bytes imageData2 = 9;
- if (has_imagedata2()) {
- ::google::protobuf::internal::WireFormatLite::WriteBytes(
- 9, this->imagedata2(), output);
- }
-
- // optional uint32 camera_config = 10;
- if (has_camera_config()) {
- ::google::protobuf::internal::WireFormatLite::WriteUInt32(10, this->camera_config(), output);
- }
-
- // optional uint32 camera_type = 11;
- if (has_camera_type()) {
- ::google::protobuf::internal::WireFormatLite::WriteUInt32(11, this->camera_type(), output);
- }
-
- // optional float roll = 12;
- if (has_roll()) {
- ::google::protobuf::internal::WireFormatLite::WriteFloat(12, this->roll(), output);
- }
-
- // optional float pitch = 13;
- if (has_pitch()) {
- ::google::protobuf::internal::WireFormatLite::WriteFloat(13, this->pitch(), output);
- }
-
- // optional float yaw = 14;
- if (has_yaw()) {
- ::google::protobuf::internal::WireFormatLite::WriteFloat(14, this->yaw(), output);
- }
-
- // optional float lon = 15;
- if (has_lon()) {
- ::google::protobuf::internal::WireFormatLite::WriteFloat(15, this->lon(), output);
- }
-
- // optional float lat = 16;
- if (has_lat()) {
- ::google::protobuf::internal::WireFormatLite::WriteFloat(16, this->lat(), output);
- }
-
- // optional float alt = 17;
- if (has_alt()) {
- ::google::protobuf::internal::WireFormatLite::WriteFloat(17, this->alt(), output);
- }
-
- // optional float ground_x = 18;
- if (has_ground_x()) {
- ::google::protobuf::internal::WireFormatLite::WriteFloat(18, this->ground_x(), output);
- }
-
- // optional float ground_y = 19;
- if (has_ground_y()) {
- ::google::protobuf::internal::WireFormatLite::WriteFloat(19, this->ground_y(), output);
- }
-
- // optional float ground_z = 20;
- if (has_ground_z()) {
- ::google::protobuf::internal::WireFormatLite::WriteFloat(20, this->ground_z(), output);
- }
-
- // repeated float camera_matrix = 21;
- for (int i = 0; i < this->camera_matrix_size(); i++) {
- ::google::protobuf::internal::WireFormatLite::WriteFloat(
- 21, this->camera_matrix(i), output);
- }
-
- if (!unknown_fields().empty()) {
- ::google::protobuf::internal::WireFormat::SerializeUnknownFields(
- unknown_fields(), output);
- }
-}
-
-::google::protobuf::uint8* RGBDImage::SerializeWithCachedSizesToArray(
- ::google::protobuf::uint8* target) const {
- // required .px.HeaderInfo header = 1;
- if (has_header()) {
- target = ::google::protobuf::internal::WireFormatLite::
- WriteMessageNoVirtualToArray(
- 1, this->header(), target);
- }
-
- // required uint32 cols = 2;
- if (has_cols()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(2, this->cols(), target);
- }
-
- // required uint32 rows = 3;
- if (has_rows()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(3, this->rows(), target);
- }
-
- // required uint32 step1 = 4;
- if (has_step1()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(4, this->step1(), target);
- }
-
- // required uint32 type1 = 5;
- if (has_type1()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(5, this->type1(), target);
- }
-
- // required bytes imageData1 = 6;
- if (has_imagedata1()) {
- target =
- ::google::protobuf::internal::WireFormatLite::WriteBytesToArray(
- 6, this->imagedata1(), target);
- }
-
- // required uint32 step2 = 7;
- if (has_step2()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(7, this->step2(), target);
- }
-
- // required uint32 type2 = 8;
- if (has_type2()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(8, this->type2(), target);
- }
-
- // required bytes imageData2 = 9;
- if (has_imagedata2()) {
- target =
- ::google::protobuf::internal::WireFormatLite::WriteBytesToArray(
- 9, this->imagedata2(), target);
- }
-
- // optional uint32 camera_config = 10;
- if (has_camera_config()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(10, this->camera_config(), target);
- }
-
- // optional uint32 camera_type = 11;
- if (has_camera_type()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(11, this->camera_type(), target);
- }
-
- // optional float roll = 12;
- if (has_roll()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(12, this->roll(), target);
- }
-
- // optional float pitch = 13;
- if (has_pitch()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(13, this->pitch(), target);
- }
-
- // optional float yaw = 14;
- if (has_yaw()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(14, this->yaw(), target);
- }
-
- // optional float lon = 15;
- if (has_lon()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(15, this->lon(), target);
- }
-
- // optional float lat = 16;
- if (has_lat()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(16, this->lat(), target);
- }
-
- // optional float alt = 17;
- if (has_alt()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(17, this->alt(), target);
- }
-
- // optional float ground_x = 18;
- if (has_ground_x()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(18, this->ground_x(), target);
- }
-
- // optional float ground_y = 19;
- if (has_ground_y()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(19, this->ground_y(), target);
- }
-
- // optional float ground_z = 20;
- if (has_ground_z()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(20, this->ground_z(), target);
- }
-
- // repeated float camera_matrix = 21;
- for (int i = 0; i < this->camera_matrix_size(); i++) {
- target = ::google::protobuf::internal::WireFormatLite::
- WriteFloatToArray(21, this->camera_matrix(i), target);
- }
-
- if (!unknown_fields().empty()) {
- target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray(
- unknown_fields(), target);
- }
- return target;
-}
-
-int RGBDImage::ByteSize() const {
- int total_size = 0;
-
- if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- // required .px.HeaderInfo header = 1;
- if (has_header()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
- this->header());
- }
-
- // required uint32 cols = 2;
- if (has_cols()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::UInt32Size(
- this->cols());
- }
-
- // required uint32 rows = 3;
- if (has_rows()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::UInt32Size(
- this->rows());
- }
-
- // required uint32 step1 = 4;
- if (has_step1()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::UInt32Size(
- this->step1());
- }
-
- // required uint32 type1 = 5;
- if (has_type1()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::UInt32Size(
- this->type1());
- }
-
- // required bytes imageData1 = 6;
- if (has_imagedata1()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::BytesSize(
- this->imagedata1());
- }
-
- // required uint32 step2 = 7;
- if (has_step2()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::UInt32Size(
- this->step2());
- }
-
- // required uint32 type2 = 8;
- if (has_type2()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::UInt32Size(
- this->type2());
- }
-
- }
- if (_has_bits_[8 / 32] & (0xffu << (8 % 32))) {
- // required bytes imageData2 = 9;
- if (has_imagedata2()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::BytesSize(
- this->imagedata2());
- }
-
- // optional uint32 camera_config = 10;
- if (has_camera_config()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::UInt32Size(
- this->camera_config());
- }
-
- // optional uint32 camera_type = 11;
- if (has_camera_type()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::UInt32Size(
- this->camera_type());
- }
-
- // optional float roll = 12;
- if (has_roll()) {
- total_size += 1 + 4;
- }
-
- // optional float pitch = 13;
- if (has_pitch()) {
- total_size += 1 + 4;
- }
-
- // optional float yaw = 14;
- if (has_yaw()) {
- total_size += 1 + 4;
- }
-
- // optional float lon = 15;
- if (has_lon()) {
- total_size += 1 + 4;
- }
-
- // optional float lat = 16;
- if (has_lat()) {
- total_size += 2 + 4;
- }
-
- }
- if (_has_bits_[16 / 32] & (0xffu << (16 % 32))) {
- // optional float alt = 17;
- if (has_alt()) {
- total_size += 2 + 4;
- }
-
- // optional float ground_x = 18;
- if (has_ground_x()) {
- total_size += 2 + 4;
- }
-
- // optional float ground_y = 19;
- if (has_ground_y()) {
- total_size += 2 + 4;
- }
-
- // optional float ground_z = 20;
- if (has_ground_z()) {
- total_size += 2 + 4;
- }
-
- }
- // repeated float camera_matrix = 21;
- {
- int data_size = 0;
- data_size = 4 * this->camera_matrix_size();
- total_size += 2 * this->camera_matrix_size() + data_size;
- }
-
- if (!unknown_fields().empty()) {
- total_size +=
- ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize(
- unknown_fields());
- }
- GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
- _cached_size_ = total_size;
- GOOGLE_SAFE_CONCURRENT_WRITES_END();
- return total_size;
-}
-
-void RGBDImage::MergeFrom(const ::google::protobuf::Message& from) {
- GOOGLE_CHECK_NE(&from, this);
- const RGBDImage* source =
- ::google::protobuf::internal::dynamic_cast_if_available<const RGBDImage*>(
- &from);
- if (source == NULL) {
- ::google::protobuf::internal::ReflectionOps::Merge(from, this);
- } else {
- MergeFrom(*source);
- }
-}
-
-void RGBDImage::MergeFrom(const RGBDImage& from) {
- GOOGLE_CHECK_NE(&from, this);
- camera_matrix_.MergeFrom(from.camera_matrix_);
- if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- if (from.has_header()) {
- mutable_header()->::px::HeaderInfo::MergeFrom(from.header());
- }
- if (from.has_cols()) {
- set_cols(from.cols());
- }
- if (from.has_rows()) {
- set_rows(from.rows());
- }
- if (from.has_step1()) {
- set_step1(from.step1());
- }
- if (from.has_type1()) {
- set_type1(from.type1());
- }
- if (from.has_imagedata1()) {
- set_imagedata1(from.imagedata1());
- }
- if (from.has_step2()) {
- set_step2(from.step2());
- }
- if (from.has_type2()) {
- set_type2(from.type2());
- }
- }
- if (from._has_bits_[8 / 32] & (0xffu << (8 % 32))) {
- if (from.has_imagedata2()) {
- set_imagedata2(from.imagedata2());
- }
- if (from.has_camera_config()) {
- set_camera_config(from.camera_config());
- }
- if (from.has_camera_type()) {
- set_camera_type(from.camera_type());
- }
- if (from.has_roll()) {
- set_roll(from.roll());
- }
- if (from.has_pitch()) {
- set_pitch(from.pitch());
- }
- if (from.has_yaw()) {
- set_yaw(from.yaw());
- }
- if (from.has_lon()) {
- set_lon(from.lon());
- }
- if (from.has_lat()) {
- set_lat(from.lat());
- }
- }
- if (from._has_bits_[16 / 32] & (0xffu << (16 % 32))) {
- if (from.has_alt()) {
- set_alt(from.alt());
- }
- if (from.has_ground_x()) {
- set_ground_x(from.ground_x());
- }
- if (from.has_ground_y()) {
- set_ground_y(from.ground_y());
- }
- if (from.has_ground_z()) {
- set_ground_z(from.ground_z());
- }
- }
- mutable_unknown_fields()->MergeFrom(from.unknown_fields());
-}
-
-void RGBDImage::CopyFrom(const ::google::protobuf::Message& from) {
- if (&from == this) return;
- Clear();
- MergeFrom(from);
-}
-
-void RGBDImage::CopyFrom(const RGBDImage& from) {
- if (&from == this) return;
- Clear();
- MergeFrom(from);
-}
-
-bool RGBDImage::IsInitialized() const {
- if ((_has_bits_[0] & 0x000001ff) != 0x000001ff) return false;
-
- if (has_header()) {
- if (!this->header().IsInitialized()) return false;
- }
- return true;
-}
-
-void RGBDImage::Swap(RGBDImage* other) {
- if (other != this) {
- std::swap(header_, other->header_);
- std::swap(cols_, other->cols_);
- std::swap(rows_, other->rows_);
- std::swap(step1_, other->step1_);
- std::swap(type1_, other->type1_);
- std::swap(imagedata1_, other->imagedata1_);
- std::swap(step2_, other->step2_);
- std::swap(type2_, other->type2_);
- std::swap(imagedata2_, other->imagedata2_);
- std::swap(camera_config_, other->camera_config_);
- std::swap(camera_type_, other->camera_type_);
- std::swap(roll_, other->roll_);
- std::swap(pitch_, other->pitch_);
- std::swap(yaw_, other->yaw_);
- std::swap(lon_, other->lon_);
- std::swap(lat_, other->lat_);
- std::swap(alt_, other->alt_);
- std::swap(ground_x_, other->ground_x_);
- std::swap(ground_y_, other->ground_y_);
- std::swap(ground_z_, other->ground_z_);
- camera_matrix_.Swap(&other->camera_matrix_);
- std::swap(_has_bits_[0], other->_has_bits_[0]);
- _unknown_fields_.Swap(&other->_unknown_fields_);
- std::swap(_cached_size_, other->_cached_size_);
- }
-}
-
-::google::protobuf::Metadata RGBDImage::GetMetadata() const {
- protobuf_AssignDescriptorsOnce();
- ::google::protobuf::Metadata metadata;
- metadata.descriptor = RGBDImage_descriptor_;
- metadata.reflection = RGBDImage_reflection_;
- return metadata;
-}
-
-
-// ===================================================================
-
-#ifndef _MSC_VER
-const int Waypoint::kXFieldNumber;
-const int Waypoint::kYFieldNumber;
-const int Waypoint::kZFieldNumber;
-const int Waypoint::kRollFieldNumber;
-const int Waypoint::kPitchFieldNumber;
-const int Waypoint::kYawFieldNumber;
-#endif // !_MSC_VER
-
-Waypoint::Waypoint()
- : ::google::protobuf::Message() {
- SharedCtor();
-}
-
-void Waypoint::InitAsDefaultInstance() {
-}
-
-Waypoint::Waypoint(const Waypoint& from)
- : ::google::protobuf::Message() {
- SharedCtor();
- MergeFrom(from);
-}
-
-void Waypoint::SharedCtor() {
- _cached_size_ = 0;
- x_ = 0;
- y_ = 0;
- z_ = 0;
- roll_ = 0;
- pitch_ = 0;
- yaw_ = 0;
- ::memset(_has_bits_, 0, sizeof(_has_bits_));
-}
-
-Waypoint::~Waypoint() {
- SharedDtor();
-}
-
-void Waypoint::SharedDtor() {
- if (this != default_instance_) {
- }
-}
-
-void Waypoint::SetCachedSize(int size) const {
- GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
- _cached_size_ = size;
- GOOGLE_SAFE_CONCURRENT_WRITES_END();
-}
-const ::google::protobuf::Descriptor* Waypoint::descriptor() {
- protobuf_AssignDescriptorsOnce();
- return Waypoint_descriptor_;
-}
-
-const Waypoint& Waypoint::default_instance() {
- if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_;
-}
-
-Waypoint* Waypoint::default_instance_ = NULL;
-
-Waypoint* Waypoint::New() const {
- return new Waypoint;
-}
-
-void Waypoint::Clear() {
- if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- x_ = 0;
- y_ = 0;
- z_ = 0;
- roll_ = 0;
- pitch_ = 0;
- yaw_ = 0;
- }
- ::memset(_has_bits_, 0, sizeof(_has_bits_));
- mutable_unknown_fields()->Clear();
-}
-
-bool Waypoint::MergePartialFromCodedStream(
- ::google::protobuf::io::CodedInputStream* input) {
-#define DO_(EXPRESSION) if (!(EXPRESSION)) return false
- ::google::protobuf::uint32 tag;
- while ((tag = input->ReadTag()) != 0) {
- switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) {
- // required double x = 1;
- case 1: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) {
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>(
- input, &x_)));
- set_has_x();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(17)) goto parse_y;
- break;
- }
-
- // required double y = 2;
- case 2: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) {
- parse_y:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>(
- input, &y_)));
- set_has_y();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(25)) goto parse_z;
- break;
- }
-
- // optional double z = 3;
- case 3: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) {
- parse_z:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>(
- input, &z_)));
- set_has_z();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(33)) goto parse_roll;
- break;
- }
-
- // optional double roll = 4;
- case 4: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) {
- parse_roll:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>(
- input, &roll_)));
- set_has_roll();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(41)) goto parse_pitch;
- break;
- }
-
- // optional double pitch = 5;
- case 5: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) {
- parse_pitch:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>(
- input, &pitch_)));
- set_has_pitch();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectTag(49)) goto parse_yaw;
- break;
- }
-
- // optional double yaw = 6;
- case 6: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) {
- parse_yaw:
- DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
- double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>(
- input, &yaw_)));
- set_has_yaw();
- } else {
- goto handle_uninterpreted;
- }
- if (input->ExpectAtEnd()) return true;
- break;
- }
-
- default: {
- handle_uninterpreted:
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) {
- return true;
- }
- DO_(::google::protobuf::internal::WireFormat::SkipField(
- input, tag, mutable_unknown_fields()));
- break;
- }
- }
- }
- return true;
-#undef DO_
-}
-
-void Waypoint::SerializeWithCachedSizes(
- ::google::protobuf::io::CodedOutputStream* output) const {
- // required double x = 1;
- if (has_x()) {
- ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->x(), output);
- }
-
- // required double y = 2;
- if (has_y()) {
- ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->y(), output);
- }
-
- // optional double z = 3;
- if (has_z()) {
- ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->z(), output);
- }
-
- // optional double roll = 4;
- if (has_roll()) {
- ::google::protobuf::internal::WireFormatLite::WriteDouble(4, this->roll(), output);
- }
-
- // optional double pitch = 5;
- if (has_pitch()) {
- ::google::protobuf::internal::WireFormatLite::WriteDouble(5, this->pitch(), output);
- }
-
- // optional double yaw = 6;
- if (has_yaw()) {
- ::google::protobuf::internal::WireFormatLite::WriteDouble(6, this->yaw(), output);
- }
-
- if (!unknown_fields().empty()) {
- ::google::protobuf::internal::WireFormat::SerializeUnknownFields(
- unknown_fields(), output);
- }
-}
-
-::google::protobuf::uint8* Waypoint::SerializeWithCachedSizesToArray(
- ::google::protobuf::uint8* target) const {
- // required double x = 1;
- if (has_x()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->x(), target);
- }
-
- // required double y = 2;
- if (has_y()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->y(), target);
- }
-
- // optional double z = 3;
- if (has_z()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->z(), target);
- }
-
- // optional double roll = 4;
- if (has_roll()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(4, this->roll(), target);
- }
-
- // optional double pitch = 5;
- if (has_pitch()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(5, this->pitch(), target);
- }
-
- // optional double yaw = 6;
- if (has_yaw()) {
- target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(6, this->yaw(), target);
- }
-
- if (!unknown_fields().empty()) {
- target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray(
- unknown_fields(), target);
- }
- return target;
-}
-
-int Waypoint::ByteSize() const {
- int total_size = 0;
-
- if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- // required double x = 1;
- if (has_x()) {
- total_size += 1 + 8;
- }
-
- // required double y = 2;
- if (has_y()) {
- total_size += 1 + 8;
- }
-
- // optional double z = 3;
- if (has_z()) {
- total_size += 1 + 8;
- }
-
- // optional double roll = 4;
- if (has_roll()) {
- total_size += 1 + 8;
- }
-
- // optional double pitch = 5;
- if (has_pitch()) {
- total_size += 1 + 8;
- }
-
- // optional double yaw = 6;
- if (has_yaw()) {
- total_size += 1 + 8;
- }
-
- }
- if (!unknown_fields().empty()) {
- total_size +=
- ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize(
- unknown_fields());
- }
- GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
- _cached_size_ = total_size;
- GOOGLE_SAFE_CONCURRENT_WRITES_END();
- return total_size;
-}
-
-void Waypoint::MergeFrom(const ::google::protobuf::Message& from) {
- GOOGLE_CHECK_NE(&from, this);
- const Waypoint* source =
- ::google::protobuf::internal::dynamic_cast_if_available<const Waypoint*>(
- &from);
- if (source == NULL) {
- ::google::protobuf::internal::ReflectionOps::Merge(from, this);
- } else {
- MergeFrom(*source);
- }
-}
-
-void Waypoint::MergeFrom(const Waypoint& from) {
- GOOGLE_CHECK_NE(&from, this);
- if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- if (from.has_x()) {
- set_x(from.x());
- }
- if (from.has_y()) {
- set_y(from.y());
- }
- if (from.has_z()) {
- set_z(from.z());
- }
- if (from.has_roll()) {
- set_roll(from.roll());
- }
- if (from.has_pitch()) {
- set_pitch(from.pitch());
- }
- if (from.has_yaw()) {
- set_yaw(from.yaw());
- }
- }
- mutable_unknown_fields()->MergeFrom(from.unknown_fields());
-}
-
-void Waypoint::CopyFrom(const ::google::protobuf::Message& from) {
- if (&from == this) return;
- Clear();
- MergeFrom(from);
-}
-
-void Waypoint::CopyFrom(const Waypoint& from) {
- if (&from == this) return;
- Clear();
- MergeFrom(from);
-}
-
-bool Waypoint::IsInitialized() const {
- if ((_has_bits_[0] & 0x00000003) != 0x00000003) return false;
-
- return true;
-}
-
-void Waypoint::Swap(Waypoint* other) {
- if (other != this) {
- std::swap(x_, other->x_);
- std::swap(y_, other->y_);
- std::swap(z_, other->z_);
- std::swap(roll_, other->roll_);
- std::swap(pitch_, other->pitch_);
- std::swap(yaw_, other->yaw_);
- std::swap(_has_bits_[0], other->_has_bits_[0]);
- _unknown_fields_.Swap(&other->_unknown_fields_);
- std::swap(_cached_size_, other->_cached_size_);
- }
-}
-
-::google::protobuf::Metadata Waypoint::GetMetadata() const {
- protobuf_AssignDescriptorsOnce();
- ::google::protobuf::Metadata metadata;
- metadata.descriptor = Waypoint_descriptor_;
- metadata.reflection = Waypoint_reflection_;
- return metadata;
-}
-
-
-// @@protoc_insertion_point(namespace_scope)
-
-} // namespace px
-
-// @@protoc_insertion_point(global_scope)
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/test/posix/.gitignore b/mavlink/share/pyshared/pymavlink/generator/C/test/posix/.gitignore
deleted file mode 100644
index 7c98650cc..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/test/posix/.gitignore
+++ /dev/null
@@ -1,3 +0,0 @@
-/testmav0.9
-/testmav1.0
-/testmav1.0_nonstrict
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/test/posix/testmav.c b/mavlink/share/pyshared/pymavlink/generator/C/test/posix/testmav.c
deleted file mode 100644
index 2fd7fa378..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/test/posix/testmav.c
+++ /dev/null
@@ -1,159 +0,0 @@
-/*
- simple MAVLink testsuite for C
- */
-#include <stdio.h>
-#include <stdlib.h>
-#include <stdint.h>
-#include <assert.h>
-#include <stddef.h>
-
-#define MAVLINK_USE_CONVENIENCE_FUNCTIONS
-#define MAVLINK_COMM_NUM_BUFFERS 2
-
-// this trick allows us to make mavlink_message_t as small as possible
-// for this dialect, which saves some memory
-#include <version.h>
-#define MAVLINK_MAX_PAYLOAD_LEN MAVLINK_MAX_DIALECT_PAYLOAD_SIZE
-
-#include <mavlink_types.h>
-static mavlink_system_t mavlink_system = {42,11,};
-
-#define MAVLINK_ASSERT(x) assert(x)
-static void comm_send_ch(mavlink_channel_t chan, uint8_t c);
-
-static mavlink_message_t last_msg;
-
-#include <mavlink.h>
-#include <testsuite.h>
-
-static unsigned chan_counts[MAVLINK_COMM_NUM_BUFFERS];
-
-static const unsigned message_lengths[] = MAVLINK_MESSAGE_LENGTHS;
-static unsigned error_count;
-
-static const mavlink_message_info_t message_info[256] = MAVLINK_MESSAGE_INFO;
-
-static void print_one_field(mavlink_message_t *msg, const mavlink_field_info_t *f, int idx)
-{
-#define PRINT_FORMAT(f, def) (f->print_format?f->print_format:def)
- switch (f->type) {
- case MAVLINK_TYPE_CHAR:
- printf(PRINT_FORMAT(f, "%c"), _MAV_RETURN_char(msg, f->wire_offset+idx*1));
- break;
- case MAVLINK_TYPE_UINT8_T:
- printf(PRINT_FORMAT(f, "%u"), _MAV_RETURN_uint8_t(msg, f->wire_offset+idx*1));
- break;
- case MAVLINK_TYPE_INT8_T:
- printf(PRINT_FORMAT(f, "%d"), _MAV_RETURN_int8_t(msg, f->wire_offset+idx*1));
- break;
- case MAVLINK_TYPE_UINT16_T:
- printf(PRINT_FORMAT(f, "%u"), _MAV_RETURN_uint16_t(msg, f->wire_offset+idx*2));
- break;
- case MAVLINK_TYPE_INT16_T:
- printf(PRINT_FORMAT(f, "%d"), _MAV_RETURN_int16_t(msg, f->wire_offset+idx*2));
- break;
- case MAVLINK_TYPE_UINT32_T:
- printf(PRINT_FORMAT(f, "%lu"), (unsigned long)_MAV_RETURN_uint32_t(msg, f->wire_offset+idx*4));
- break;
- case MAVLINK_TYPE_INT32_T:
- printf(PRINT_FORMAT(f, "%ld"), (long)_MAV_RETURN_int32_t(msg, f->wire_offset+idx*4));
- break;
- case MAVLINK_TYPE_UINT64_T:
- printf(PRINT_FORMAT(f, "%llu"), (unsigned long long)_MAV_RETURN_uint64_t(msg, f->wire_offset+idx*8));
- break;
- case MAVLINK_TYPE_INT64_T:
- printf(PRINT_FORMAT(f, "%lld"), (long long)_MAV_RETURN_int64_t(msg, f->wire_offset+idx*8));
- break;
- case MAVLINK_TYPE_FLOAT:
- printf(PRINT_FORMAT(f, "%f"), (double)_MAV_RETURN_float(msg, f->wire_offset+idx*4));
- break;
- case MAVLINK_TYPE_DOUBLE:
- printf(PRINT_FORMAT(f, "%f"), _MAV_RETURN_double(msg, f->wire_offset+idx*8));
- break;
- }
-}
-
-static void print_field(mavlink_message_t *msg, const mavlink_field_info_t *f)
-{
- printf("%s: ", f->name);
- if (f->array_length == 0) {
- print_one_field(msg, f, 0);
- printf(" ");
- } else {
- unsigned i;
- /* print an array */
- if (f->type == MAVLINK_TYPE_CHAR) {
- printf("'%.*s'", f->array_length,
- f->wire_offset+(const char *)_MAV_PAYLOAD(msg));
-
- } else {
- printf("[ ");
- for (i=0; i<f->array_length; i++) {
- print_one_field(msg, f, i);
- if (i < f->array_length) {
- printf(", ");
- }
- }
- printf("]");
- }
- }
- printf(" ");
-}
-
-static void print_message(mavlink_message_t *msg)
-{
- const mavlink_message_info_t *m = &message_info[msg->msgid];
- const mavlink_field_info_t *f = m->fields;
- unsigned i;
- printf("%s { ", m->name);
- for (i=0; i<m->num_fields; i++) {
- print_field(msg, &f[i]);
- }
- printf("}\n");
-}
-
-static void comm_send_ch(mavlink_channel_t chan, uint8_t c)
-{
- mavlink_status_t status;
- if (mavlink_parse_char(chan, c, &last_msg, &status)) {
- print_message(&last_msg);
- chan_counts[chan]++;
- /* channel 0 gets 3 messages per message, because of
- the channel defaults for _pack() and _encode() */
- if (chan == MAVLINK_COMM_0 && status.current_rx_seq != (uint8_t)(chan_counts[chan]*3)) {
- printf("Channel 0 sequence mismatch error at packet %u (rx_seq=%u)\n",
- chan_counts[chan], status.current_rx_seq);
- error_count++;
- } else if (chan > MAVLINK_COMM_0 && status.current_rx_seq != (uint8_t)chan_counts[chan]) {
- printf("Channel %u sequence mismatch error at packet %u (rx_seq=%u)\n",
- (unsigned)chan, chan_counts[chan], status.current_rx_seq);
- error_count++;
- }
- if (message_lengths[last_msg.msgid] != last_msg.len) {
- printf("Incorrect message length %u for message %u - expected %u\n",
- (unsigned)last_msg.len, (unsigned)last_msg.msgid, message_lengths[last_msg.msgid]);
- error_count++;
- }
- }
- if (status.packet_rx_drop_count != 0) {
- printf("Parse error at packet %u\n", chan_counts[chan]);
- error_count++;
- }
-}
-
-int main(void)
-{
- mavlink_channel_t chan;
- mavlink_test_all(11, 10, &last_msg);
- for (chan=MAVLINK_COMM_0; chan<=MAVLINK_COMM_1; chan++) {
- printf("Received %u messages on channel %u OK\n",
- chan_counts[chan], (unsigned)chan);
- }
- if (error_count != 0) {
- printf("Error count %u\n", error_count);
- exit(1);
- }
- printf("No errors detected\n");
- return 0;
-}
-
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/test/windows/stdafx.cpp b/mavlink/share/pyshared/pymavlink/generator/C/test/windows/stdafx.cpp
deleted file mode 100644
index 98b4abf05..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/test/windows/stdafx.cpp
+++ /dev/null
@@ -1,8 +0,0 @@
-// stdafx.cpp : source file that includes just the standard includes
-// testmav.pch will be the pre-compiled header
-// stdafx.obj will contain the pre-compiled type information
-
-#include "stdafx.h"
-
-// TODO: reference any additional headers you need in STDAFX.H
-// and not in this file
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/test/windows/stdafx.h b/mavlink/share/pyshared/pymavlink/generator/C/test/windows/stdafx.h
deleted file mode 100644
index 47a0d0252..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/test/windows/stdafx.h
+++ /dev/null
@@ -1,15 +0,0 @@
-// stdafx.h : include file for standard system include files,
-// or project specific include files that are used frequently, but
-// are changed infrequently
-//
-
-#pragma once
-
-#include "targetver.h"
-
-#include <stdio.h>
-#include <tchar.h>
-
-
-
-// TODO: reference additional headers your program requires here
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/test/windows/targetver.h b/mavlink/share/pyshared/pymavlink/generator/C/test/windows/targetver.h
deleted file mode 100644
index 90e767bfc..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/test/windows/targetver.h
+++ /dev/null
@@ -1,8 +0,0 @@
-#pragma once
-
-// Including SDKDDKVer.h defines the highest available Windows platform.
-
-// If you wish to build your application for a previous Windows platform, include WinSDKVer.h and
-// set the _WIN32_WINNT macro to the platform you wish to support before including SDKDDKVer.h.
-
-#include <SDKDDKVer.h>
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/test/windows/testmav.cpp b/mavlink/share/pyshared/pymavlink/generator/C/test/windows/testmav.cpp
deleted file mode 100644
index aa83caced..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/test/windows/testmav.cpp
+++ /dev/null
@@ -1,154 +0,0 @@
-// testmav.cpp : Defines the entry point for the console application.
-//
-
-#include "stdafx.h"
-#include "stdio.h"
-#include "stdint.h"
-#include "stddef.h"
-#include "assert.h"
-
-
-#define MAVLINK_USE_CONVENIENCE_FUNCTIONS
-#define MAVLINK_COMM_NUM_BUFFERS 2
-
-#include <mavlink_types.h>
-static mavlink_system_t mavlink_system = {42,11,};
-
-#define MAVLINK_ASSERT(x) assert(x)
-static void comm_send_ch(mavlink_channel_t chan, uint8_t c);
-
-static mavlink_message_t last_msg;
-
-#include <common/mavlink.h>
-#include <common/testsuite.h>
-
-static unsigned chan_counts[MAVLINK_COMM_NUM_BUFFERS];
-
-static const unsigned message_lengths[] = MAVLINK_MESSAGE_LENGTHS;
-static unsigned error_count;
-
-static const mavlink_message_info_t message_info[256] = MAVLINK_MESSAGE_INFO;
-
-static void print_one_field(mavlink_message_t *msg, const mavlink_field_info_t *f, int idx)
-{
-#define PRINT_FORMAT(f, def) (f->print_format?f->print_format:def)
- switch (f->type) {
- case MAVLINK_TYPE_CHAR:
- printf(PRINT_FORMAT(f, "%c"), _MAV_RETURN_char(msg, f->wire_offset+idx*1));
- break;
- case MAVLINK_TYPE_UINT8_T:
- printf(PRINT_FORMAT(f, "%u"), _MAV_RETURN_uint8_t(msg, f->wire_offset+idx*1));
- break;
- case MAVLINK_TYPE_INT8_T:
- printf(PRINT_FORMAT(f, "%d"), _MAV_RETURN_int8_t(msg, f->wire_offset+idx*1));
- break;
- case MAVLINK_TYPE_UINT16_T:
- printf(PRINT_FORMAT(f, "%u"), _MAV_RETURN_uint16_t(msg, f->wire_offset+idx*2));
- break;
- case MAVLINK_TYPE_INT16_T:
- printf(PRINT_FORMAT(f, "%d"), _MAV_RETURN_int16_t(msg, f->wire_offset+idx*2));
- break;
- case MAVLINK_TYPE_UINT32_T:
- printf(PRINT_FORMAT(f, "%lu"), (unsigned long)_MAV_RETURN_uint32_t(msg, f->wire_offset+idx*4));
- break;
- case MAVLINK_TYPE_INT32_T:
- printf(PRINT_FORMAT(f, "%ld"), (long)_MAV_RETURN_int32_t(msg, f->wire_offset+idx*4));
- break;
- case MAVLINK_TYPE_UINT64_T:
- printf(PRINT_FORMAT(f, "%llu"), (unsigned long long)_MAV_RETURN_uint64_t(msg, f->wire_offset+idx*8));
- break;
- case MAVLINK_TYPE_INT64_T:
- printf(PRINT_FORMAT(f, "%lld"), (long long)_MAV_RETURN_int64_t(msg, f->wire_offset+idx*8));
- break;
- case MAVLINK_TYPE_FLOAT:
- printf(PRINT_FORMAT(f, "%f"), (double)_MAV_RETURN_float(msg, f->wire_offset+idx*4));
- break;
- case MAVLINK_TYPE_DOUBLE:
- printf(PRINT_FORMAT(f, "%f"), _MAV_RETURN_double(msg, f->wire_offset+idx*8));
- break;
- }
-}
-
-static void print_field(mavlink_message_t *msg, const mavlink_field_info_t *f)
-{
- printf("%s: ", f->name);
- if (f->array_length == 0) {
- print_one_field(msg, f, 0);
- printf(" ");
- } else {
- unsigned i;
- /* print an array */
- if (f->type == MAVLINK_TYPE_CHAR) {
- printf("'%.*s'", f->array_length,
- f->wire_offset+(const char *)_MAV_PAYLOAD(msg));
-
- } else {
- printf("[ ");
- for (i=0; i<f->array_length; i++) {
- print_one_field(msg, f, i);
- if (i < f->array_length) {
- printf(", ");
- }
- }
- printf("]");
- }
- }
- printf(" ");
-}
-
-static void print_message(mavlink_message_t *msg)
-{
- const mavlink_message_info_t *m = &message_info[msg->msgid];
- const mavlink_field_info_t *f = m->fields;
- unsigned i;
- printf("%s { ", m->name);
- for (i=0; i<m->num_fields; i++) {
- print_field(msg, &f[i]);
- }
- printf("}\n");
-}
-
-static void comm_send_ch(mavlink_channel_t chan, uint8_t c)
-{
- mavlink_status_t status;
- if (mavlink_parse_char(chan, c, &last_msg, &status)) {
- print_message(&last_msg);
- chan_counts[chan]++;
- /* channel 0 gets 3 messages per message, because of
- the channel defaults for _pack() and _encode() */
- if (chan == MAVLINK_COMM_0 && status.current_rx_seq != (uint8_t)(chan_counts[chan]*3)) {
- printf("Channel 0 sequence mismatch error at packet %u (rx_seq=%u)\n",
- chan_counts[chan], status.current_rx_seq);
- error_count++;
- } else if (chan > MAVLINK_COMM_0 && status.current_rx_seq != (uint8_t)chan_counts[chan]) {
- printf("Channel %u sequence mismatch error at packet %u (rx_seq=%u)\n",
- (unsigned)chan, chan_counts[chan], status.current_rx_seq);
- error_count++;
- }
- if (message_lengths[last_msg.msgid] != last_msg.len) {
- printf("Incorrect message length %u for message %u - expected %u\n",
- (unsigned)last_msg.len, (unsigned)last_msg.msgid, message_lengths[last_msg.msgid]);
- error_count++;
- }
- }
- if (status.packet_rx_drop_count != 0) {
- printf("Parse error at packet %u\n", chan_counts[chan]);
- error_count++;
- }
-}
-
-int _tmain(int argc, _TCHAR* argv[])
-{
- int chan;
- mavlink_test_all(11, 10, &last_msg);
- for (chan=MAVLINK_COMM_0; chan<=MAVLINK_COMM_1; chan++) {
- printf("Received %u messages on channel %u OK\n",
- chan_counts[chan], (unsigned)chan);
- }
- if (error_count != 0) {
- printf("Error count %u\n", error_count);
- return(1);
- }
- printf("No errors detected\n");
- return 0;
-}
diff --git a/mavlink/share/pyshared/pymavlink/generator/gen_MatrixPilot.py b/mavlink/share/pyshared/pymavlink/generator/gen_MatrixPilot.py
deleted file mode 100644
index 165c1b343..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/gen_MatrixPilot.py
+++ /dev/null
@@ -1,93 +0,0 @@
-#!/usr/bin/env python
-'''
-Use mavgen.py matrixpilot.xml definitions to generate
-C and Python MAVLink routines for sending and parsing the protocol
-This python script is soley for MatrixPilot MAVLink impoementation
-
-Copyright Pete Hollands 2011
-Released under GNU GPL version 3 or later
-'''
-
-import os, sys, glob, re
-from shutil import copy
-from mavgen import mavgen
-
-# allow import from the parent directory, where mavutil.py is
-# Under Windows, this script must be run from a DOS command window
-sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..'))
-
-class options:
- """ a class to simulate the options of mavgen OptionsParser"""
- def __init__(self, lang, output, wire_protocol):
- self.language = lang
- self.wire_protocol = wire_protocol
- self.output = output
-
-def remove_include_files(target_directory):
- search_pattern = target_directory+'/*.h'
- print "search pattern is", search_pattern
- files_to_remove = glob.glob(search_pattern)
- for afile in files_to_remove :
- try:
- print "removing", afile
- os.remove(afile)
- except:
- print "error while trying to remove", afile
-
-def copy_include_files(source_directory,target_directory):
- search_pattern = source_directory+'/*.h'
- files_to_copy = glob.glob(search_pattern)
- for afile in files_to_copy:
- basename = os.path.basename(afile)
- print "Copying ...", basename
- copy(afile, target_directory)
-
-protocol = "1.0"
-
-xml_directory = './message_definitions/v'+protocol
-print "xml_directory is", xml_directory
-xml_file_names = []
-xml_file_names.append(xml_directory+"/"+"matrixpilot.xml")
-
-for xml_file in xml_file_names:
- print "xml file is ", xml_file
- opts = options(lang = "C", output = "C/include_v"+protocol, \
- wire_protocol=protocol)
- args = []
- args.append(xml_file)
- mavgen(opts, args)
- xml_file_base = os.path.basename(xml_file)
- xml_file_base = re.sub("\.xml","", xml_file_base)
- print "xml_file_base is", xml_file_base
- opts = options(lang = "python", \
- output="python/mavlink_"+xml_file_base+"_v"+protocol+".py", \
- wire_protocol=protocol)
- mavgen(opts,args)
-
-mavlink_directory_list = ["common","matrixpilot"]
-for mavlink_directory in mavlink_directory_list :
- # Look specifically for MatrixPilot directory structure
- target_directory = "../../../../MAVLink/include/"+mavlink_directory
- source_directory = "C/include_v"+protocol+"/"+mavlink_directory
- if os.access(source_directory, os.R_OK):
- if os.access(target_directory, os.W_OK):
- print "Preparing to copy over files..."
- print "About to remove all files in",target_directory
- print "OK to continue ?[Yes / No]: ",
- line = sys.stdin.readline()
- if line == "Yes\n" or line == "yes\n" \
- or line == "Y\n" or line == "y\n":
- print "passed"
- remove_include_files(target_directory)
- copy_include_files(source_directory,target_directory)
- print "Finished copying over include files"
- else :
- print "Your answer is No. Exiting Program"
- sys.exit()
- else :
- print "Cannot find " + target_directory + "in MatrixPilot"
- sys.exit()
- else:
- print "Could not find files to copy at", source_directory
- print "Exiting Program."
- sys.exit()
diff --git a/mavlink/share/pyshared/pymavlink/generator/gen_all.py b/mavlink/share/pyshared/pymavlink/generator/gen_all.py
deleted file mode 100644
index 5b24f85cb..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/gen_all.py
+++ /dev/null
@@ -1,44 +0,0 @@
-#!/usr/bin/env python
-
-'''
-Use mavgen.py on all available MAVLink XML definitions to generate
-C and Python MAVLink routines for sending and parsing the protocol
-
-Copyright Pete Hollands 2011
-Released under GNU GPL version 3 or later
-'''
-
-import os, sys, glob, re
-from mavgen import mavgen
-
-# allow import from the parent directory, where mavutil.py is
-sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..'))
-
-class options:
- """ a class to simulate the options of mavgen OptionsParser"""
- def __init__(self, lang, output, wire_protocol):
- self.language = lang
- self.wire_protocol = wire_protocol
- self.output = output
-
-protocols = [ '0.9', '1.0' ]
-
-for protocol in protocols :
- xml_directory = './message_definitions/v'+protocol
- print "xml_directory is", xml_directory
- xml_file_names = glob.glob(xml_directory+'/*.xml')
-
- for xml_file in xml_file_names:
- print "xml file is ", xml_file
- opts = options(lang = "C", output = "C/include_v"+protocol, \
- wire_protocol=protocol)
- args = []
- args.append(xml_file)
- mavgen(opts, args)
- xml_file_base = os.path.basename(xml_file)
- xml_file_base = re.sub("\.xml","", xml_file_base)
- print "xml_file_base is", xml_file_base
- opts = options(lang = "python", \
- output="python/mavlink_"+xml_file_base+"_v"+protocol+".py", \
- wire_protocol=protocol)
- mavgen(opts,args)
diff --git a/mavlink/share/pyshared/pymavlink/generator/gen_all.sh b/mavlink/share/pyshared/pymavlink/generator/gen_all.sh
deleted file mode 100644
index e8dafedc5..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/gen_all.sh
+++ /dev/null
@@ -1,12 +0,0 @@
-#!/bin/sh
-
-for protocol in 0.9 1.0; do
- for xml in message_definitions/v$protocol/*.xml; do
- base=$(basename $xml .xml)
- ./mavgen.py --lang=C --wire-protocol=$protocol --output=C/include_v$protocol $xml || exit 1
- ./mavgen.py --lang=python --wire-protocol=$protocol --output=python/mavlink_${base}_v$protocol.py $xml || exit 1
- done
-done
-
-cp -f python/mavlink_ardupilotmega_v0.9.py ../mavlink.py
-cp -f python/mavlink_ardupilotmega_v1.0.py ../mavlinkv10.py
diff --git a/mavlink/share/pyshared/pymavlink/generator/mavgen.py b/mavlink/share/pyshared/pymavlink/generator/mavgen.py
deleted file mode 100644
index 05f71f778..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/mavgen.py
+++ /dev/null
@@ -1,82 +0,0 @@
-#!/usr/bin/env python
-'''
-parse a MAVLink protocol XML file and generate a python implementation
-
-Copyright Andrew Tridgell 2011
-Released under GNU GPL version 3 or later
-'''
-
-def mavgen(opts, args) :
- """Generate mavlink message formatters and parsers (C and Python ) using options
- and args where args are a list of xml files. This function allows python
- scripts under Windows to control mavgen using the same interface as
- shell scripts under Unix"""
- import sys, textwrap, os
-
- import mavparse
- import mavgen_python
- import mavgen_c
-
- xml = []
-
- for fname in args:
- print("Parsing %s" % fname)
- xml.append(mavparse.MAVXML(fname, opts.wire_protocol))
-
- # expand includes
- for x in xml[:]:
- for i in x.include:
- fname = os.path.join(os.path.dirname(x.filename), i)
- print("Parsing %s" % fname)
- xml.append(mavparse.MAVXML(fname, opts.wire_protocol))
-
- # include message lengths and CRCs too
- for idx in range(0, 256):
- if x.message_lengths[idx] == 0:
- x.message_lengths[idx] = xml[-1].message_lengths[idx]
- x.message_crcs[idx] = xml[-1].message_crcs[idx]
- x.message_names[idx] = xml[-1].message_names[idx]
-
- # work out max payload size across all includes
- largest_payload = 0
- for x in xml:
- if x.largest_payload > largest_payload:
- largest_payload = x.largest_payload
- for x in xml:
- x.largest_payload = largest_payload
-
- if mavparse.check_duplicates(xml):
- sys.exit(1)
-
- print("Found %u MAVLink message types in %u XML files" % (
- mavparse.total_msgs(xml), len(xml)))
-
- if opts.language == 'python':
- mavgen_python.generate(opts.output, xml)
- elif opts.language == 'C':
- mavgen_c.generate(opts.output, xml)
- else:
- print("Unsupported language %s" % opts.language)
-
-
-if __name__=="__main__":
- import sys, textwrap, os
-
- from optparse import OptionParser
-
- # allow import from the parent directory, where mavutil.py is
- sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..'))
-
- import mavparse
- import mavgen_python
- import mavgen_c
-
- parser = OptionParser("%prog [options] <XML files>")
- parser.add_option("-o", "--output", dest="output", default="mavlink", help="output directory.")
- parser.add_option("--lang", dest="language", default="python", help="language of generated code: 'Python' or 'C' [default: %default]")
- parser.add_option("--wire-protocol", dest="wire_protocol", default=mavparse.PROTOCOL_0_9, help="MAVLink protocol version: '0.9' or '1.0'. [default: %default]")
- (opts, args) = parser.parse_args()
-
- if len(args) < 1:
- parser.error("You must supply at least one MAVLink XML protocol definition")
- mavgen(opts, args)
diff --git a/mavlink/share/pyshared/pymavlink/generator/mavgen_c.py b/mavlink/share/pyshared/pymavlink/generator/mavgen_c.py
deleted file mode 100644
index 255919f0d..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/mavgen_c.py
+++ /dev/null
@@ -1,581 +0,0 @@
-#!/usr/bin/env python
-'''
-parse a MAVLink protocol XML file and generate a C implementation
-
-Copyright Andrew Tridgell 2011
-Released under GNU GPL version 3 or later
-'''
-
-import sys, textwrap, os, time
-import mavparse, mavtemplate
-
-t = mavtemplate.MAVTemplate()
-
-def generate_version_h(directory, xml):
- '''generate version.h'''
- f = open(os.path.join(directory, "version.h"), mode='w')
- t.write(f,'''
-/** @file
- * @brief MAVLink comm protocol built from ${basename}.xml
- * @see http://pixhawk.ethz.ch/software/mavlink
- */
-#ifndef MAVLINK_VERSION_H
-#define MAVLINK_VERSION_H
-
-#define MAVLINK_BUILD_DATE "${parse_time}"
-#define MAVLINK_WIRE_PROTOCOL_VERSION "${wire_protocol_version}"
-#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE ${largest_payload}
-
-#endif // MAVLINK_VERSION_H
-''', xml)
- f.close()
-
-def generate_mavlink_h(directory, xml):
- '''generate mavlink.h'''
- f = open(os.path.join(directory, "mavlink.h"), mode='w')
- t.write(f,'''
-/** @file
- * @brief MAVLink comm protocol built from ${basename}.xml
- * @see http://pixhawk.ethz.ch/software/mavlink
- */
-#ifndef MAVLINK_H
-#define MAVLINK_H
-
-#ifndef MAVLINK_STX
-#define MAVLINK_STX ${protocol_marker}
-#endif
-
-#ifndef MAVLINK_ENDIAN
-#define MAVLINK_ENDIAN ${mavlink_endian}
-#endif
-
-#ifndef MAVLINK_ALIGNED_FIELDS
-#define MAVLINK_ALIGNED_FIELDS ${aligned_fields_define}
-#endif
-
-#ifndef MAVLINK_CRC_EXTRA
-#define MAVLINK_CRC_EXTRA ${crc_extra_define}
-#endif
-
-#include "version.h"
-#include "${basename}.h"
-
-#endif // MAVLINK_H
-''', xml)
- f.close()
-
-def generate_main_h(directory, xml):
- '''generate main header per XML file'''
- f = open(os.path.join(directory, xml.basename + ".h"), mode='w')
- t.write(f, '''
-/** @file
- * @brief MAVLink comm protocol generated from ${basename}.xml
- * @see http://qgroundcontrol.org/mavlink/
- */
-#ifndef ${basename_upper}_H
-#define ${basename_upper}_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-// MESSAGE LENGTHS AND CRCS
-
-#ifndef MAVLINK_MESSAGE_LENGTHS
-#define MAVLINK_MESSAGE_LENGTHS {${message_lengths_array}}
-#endif
-
-#ifndef MAVLINK_MESSAGE_CRCS
-#define MAVLINK_MESSAGE_CRCS {${message_crcs_array}}
-#endif
-
-#ifndef MAVLINK_MESSAGE_INFO
-#define MAVLINK_MESSAGE_INFO {${message_info_array}}
-#endif
-
-#include "../protocol.h"
-
-#define MAVLINK_ENABLED_${basename_upper}
-
-${{include_list:#include "../${base}/${base}.h"
-}}
-
-// MAVLINK VERSION
-
-#ifndef MAVLINK_VERSION
-#define MAVLINK_VERSION ${version}
-#endif
-
-#if (MAVLINK_VERSION == 0)
-#undef MAVLINK_VERSION
-#define MAVLINK_VERSION ${version}
-#endif
-
-// ENUM DEFINITIONS
-
-${{enum:
-/** @brief ${description} */
-#ifndef HAVE_ENUM_${name}
-#define HAVE_ENUM_${name}
-enum ${name}
-{
-${{entry: ${name}=${value}, /* ${description} |${{param:${description}| }} */
-}}
-};
-#endif
-}}
-
-// MESSAGE DEFINITIONS
-${{message:#include "./mavlink_msg_${name_lower}.h"
-}}
-
-#ifdef __cplusplus
-}
-#endif // __cplusplus
-#endif // ${basename_upper}_H
-''', xml)
-
- f.close()
-
-
-def generate_message_h(directory, m):
- '''generate per-message header for a XML file'''
- f = open(os.path.join(directory, 'mavlink_msg_%s.h' % m.name_lower), mode='w')
- t.write(f, '''
-// MESSAGE ${name} PACKING
-
-#define MAVLINK_MSG_ID_${name} ${id}
-
-typedef struct __mavlink_${name_lower}_t
-{
-${{ordered_fields: ${type} ${name}${array_suffix}; ///< ${description}
-}}
-} mavlink_${name_lower}_t;
-
-#define MAVLINK_MSG_ID_${name}_LEN ${wire_length}
-#define MAVLINK_MSG_ID_${id}_LEN ${wire_length}
-
-${{array_fields:#define MAVLINK_MSG_${msg_name}_FIELD_${name_upper}_LEN ${array_length}
-}}
-
-#define MAVLINK_MESSAGE_INFO_${name} { \\
- "${name}", \\
- ${num_fields}, \\
- { ${{ordered_fields: { "${name}", ${c_print_format}, MAVLINK_TYPE_${type_upper}, ${array_length}, ${wire_offset}, offsetof(mavlink_${name_lower}_t, ${name}) }, \\
- }} } \\
-}
-
-
-/**
- * @brief Pack a ${name_lower} message
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param msg The MAVLink message to compress the data into
- *
-${{arg_fields: * @param ${name} ${description}
-}}
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_${name_lower}_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- ${{arg_fields: ${array_const}${type} ${array_prefix}${name},}})
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[${wire_length}];
-${{scalar_fields: _mav_put_${type}(buf, ${wire_offset}, ${putname});
-}}
-${{array_fields: _mav_put_${type}_array(buf, ${wire_offset}, ${name}, ${array_length});
-}}
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, ${wire_length});
-#else
- mavlink_${name_lower}_t packet;
-${{scalar_fields: packet.${name} = ${putname};
-}}
-${{array_fields: mav_array_memcpy(packet.${name}, ${name}, sizeof(${type})*${array_length});
-}}
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, ${wire_length});
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_${name};
- return mavlink_finalize_message(msg, system_id, component_id, ${wire_length}${crc_extra_arg});
-}
-
-/**
- * @brief Pack a ${name_lower} message on a channel
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
- * @param msg The MAVLink message to compress the data into
-${{arg_fields: * @param ${name} ${description}
-}}
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_${name_lower}_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- ${{arg_fields:${array_const}${type} ${array_prefix}${name},}})
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[${wire_length}];
-${{scalar_fields: _mav_put_${type}(buf, ${wire_offset}, ${putname});
-}}
-${{array_fields: _mav_put_${type}_array(buf, ${wire_offset}, ${name}, ${array_length});
-}}
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, ${wire_length});
-#else
- mavlink_${name_lower}_t packet;
-${{scalar_fields: packet.${name} = ${putname};
-}}
-${{array_fields: mav_array_memcpy(packet.${name}, ${name}, sizeof(${type})*${array_length});
-}}
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, ${wire_length});
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_${name};
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, ${wire_length}${crc_extra_arg});
-}
-
-/**
- * @brief Encode a ${name_lower} struct into a message
- *
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param msg The MAVLink message to compress the data into
- * @param ${name_lower} C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_${name_lower}_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_${name_lower}_t* ${name_lower})
-{
- return mavlink_msg_${name_lower}_pack(system_id, component_id, msg,${{arg_fields: ${name_lower}->${name},}});
-}
-
-/**
- * @brief Send a ${name_lower} message
- * @param chan MAVLink channel to send the message
- *
-${{arg_fields: * @param ${name} ${description}
-}}
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_${name_lower}_send(mavlink_channel_t chan,${{arg_fields: ${array_const}${type} ${array_prefix}${name},}})
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[${wire_length}];
-${{scalar_fields: _mav_put_${type}(buf, ${wire_offset}, ${putname});
-}}
-${{array_fields: _mav_put_${type}_array(buf, ${wire_offset}, ${name}, ${array_length});
-}}
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_${name}, buf, ${wire_length}${crc_extra_arg});
-#else
- mavlink_${name_lower}_t packet;
-${{scalar_fields: packet.${name} = ${putname};
-}}
-${{array_fields: mav_array_memcpy(packet.${name}, ${name}, sizeof(${type})*${array_length});
-}}
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_${name}, (const char *)&packet, ${wire_length}${crc_extra_arg});
-#endif
-}
-
-#endif
-
-// MESSAGE ${name} UNPACKING
-
-${{fields:
-/**
- * @brief Get field ${name} from ${name_lower} message
- *
- * @return ${description}
- */
-static inline ${return_type} mavlink_msg_${name_lower}_get_${name}(const mavlink_message_t* msg${get_arg})
-{
- return _MAV_RETURN_${type}${array_tag}(msg, ${array_return_arg} ${wire_offset});
-}
-}}
-
-/**
- * @brief Decode a ${name_lower} message into a struct
- *
- * @param msg The message to decode
- * @param ${name_lower} C-struct to decode the message contents into
- */
-static inline void mavlink_msg_${name_lower}_decode(const mavlink_message_t* msg, mavlink_${name_lower}_t* ${name_lower})
-{
-#if MAVLINK_NEED_BYTE_SWAP
-${{ordered_fields: ${decode_left}mavlink_msg_${name_lower}_get_${name}(msg${decode_right});
-}}
-#else
- memcpy(${name_lower}, _MAV_PAYLOAD(msg), ${wire_length});
-#endif
-}
-''', m)
- f.close()
-
-
-def generate_testsuite_h(directory, xml):
- '''generate testsuite.h per XML file'''
- f = open(os.path.join(directory, "testsuite.h"), mode='w')
- t.write(f, '''
-/** @file
- * @brief MAVLink comm protocol testsuite generated from ${basename}.xml
- * @see http://qgroundcontrol.org/mavlink/
- */
-#ifndef ${basename_upper}_TESTSUITE_H
-#define ${basename_upper}_TESTSUITE_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-#ifndef MAVLINK_TEST_ALL
-#define MAVLINK_TEST_ALL
-${{include_list:static void mavlink_test_${base}(uint8_t, uint8_t, mavlink_message_t *last_msg);
-}}
-static void mavlink_test_${basename}(uint8_t, uint8_t, mavlink_message_t *last_msg);
-
-static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
-{
-${{include_list: mavlink_test_${base}(system_id, component_id, last_msg);
-}}
- mavlink_test_${basename}(system_id, component_id, last_msg);
-}
-#endif
-
-${{include_list:#include "../${base}/testsuite.h"
-}}
-
-${{message:
-static void mavlink_test_${name_lower}(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
-{
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_${name_lower}_t packet_in = {
- ${{ordered_fields:${c_test_value},
- }}};
- mavlink_${name_lower}_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- ${{scalar_fields: packet1.${name} = packet_in.${name};
- }}
- ${{array_fields: mav_array_memcpy(packet1.${name}, packet_in.${name}, sizeof(${type})*${array_length});
- }}
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_${name_lower}_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_${name_lower}_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_${name_lower}_pack(system_id, component_id, &msg ${{arg_fields:, packet1.${name} }});
- mavlink_msg_${name_lower}_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_${name_lower}_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg ${{arg_fields:, packet1.${name} }});
- mavlink_msg_${name_lower}_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_to_send_buffer(buffer, &msg);
- for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_${name_lower}_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_${name_lower}_send(MAVLINK_COMM_1 ${{arg_fields:, packet1.${name} }});
- mavlink_msg_${name_lower}_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-}}
-
-static void mavlink_test_${basename}(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
-{
-${{message: mavlink_test_${name_lower}(system_id, component_id, last_msg);
-}}
-}
-
-#ifdef __cplusplus
-}
-#endif // __cplusplus
-#endif // ${basename_upper}_TESTSUITE_H
-''', xml)
-
- f.close()
-
-def copy_fixed_headers(directory, xml):
- '''copy the fixed protocol headers to the target directory'''
- import shutil
- hlist = [ 'protocol.h', 'mavlink_helpers.h', 'mavlink_types.h', 'checksum.h', 'mavlink_protobuf_manager.hpp' ]
- basepath = os.path.dirname(os.path.realpath(__file__))
- srcpath = os.path.join(basepath, 'C/include_v%s' % xml.wire_protocol_version)
- print("Copying fixed headers")
- for h in hlist:
- if (not (h == 'mavlink_protobuf_manager.hpp' and xml.wire_protocol_version == '0.9')):
- src = os.path.realpath(os.path.join(srcpath, h))
- dest = os.path.realpath(os.path.join(directory, h))
- if src == dest:
- continue
- shutil.copy(src, dest)
- # XXX This is a hack - to be removed
- if (xml.basename == 'pixhawk' and xml.wire_protocol_version == '1.0'):
- h = 'pixhawk/pixhawk.pb.h'
- src = os.path.realpath(os.path.join(srcpath, h))
- dest = os.path.realpath(os.path.join(directory, h))
- shutil.copy(src, dest)
-
-def copy_fixed_sources(directory, xml):
- # XXX This is a hack - to be removed
- import shutil
- basepath = os.path.dirname(os.path.realpath(__file__))
- srcpath = os.path.join(basepath, 'C/src_v%s' % xml.wire_protocol_version)
- if (xml.basename == 'pixhawk' and xml.wire_protocol_version == '1.0'):
- print("Copying fixed sources")
- src = os.path.realpath(os.path.join(srcpath, 'pixhawk/pixhawk.pb.cc'))
- dest = os.path.realpath(os.path.join(directory, '../../../share/mavlink/src/v%s/pixhawk/pixhawk.pb.cc' % xml.wire_protocol_version))
- destdir = os.path.realpath(os.path.join(directory, '../../../share/mavlink/src/v%s/pixhawk' % xml.wire_protocol_version))
- try:
- os.makedirs(destdir)
- except:
- print("Not re-creating directory")
- shutil.copy(src, dest)
- print("Copied to"),
- print(dest)
-
-class mav_include(object):
- def __init__(self, base):
- self.base = base
-
-def generate_one(basename, xml):
- '''generate headers for one XML file'''
-
- directory = os.path.join(basename, xml.basename)
-
- print("Generating C implementation in directory %s" % directory)
- mavparse.mkdir_p(directory)
-
- if xml.little_endian:
- xml.mavlink_endian = "MAVLINK_LITTLE_ENDIAN"
- else:
- xml.mavlink_endian = "MAVLINK_BIG_ENDIAN"
-
- if xml.crc_extra:
- xml.crc_extra_define = "1"
- else:
- xml.crc_extra_define = "0"
-
- if xml.sort_fields:
- xml.aligned_fields_define = "1"
- else:
- xml.aligned_fields_define = "0"
-
- # work out the included headers
- xml.include_list = []
- for i in xml.include:
- base = i[:-4]
- xml.include_list.append(mav_include(base))
-
- # form message lengths array
- xml.message_lengths_array = ''
- for mlen in xml.message_lengths:
- xml.message_lengths_array += '%u, ' % mlen
- xml.message_lengths_array = xml.message_lengths_array[:-2]
-
- # and message CRCs array
- xml.message_crcs_array = ''
- for crc in xml.message_crcs:
- xml.message_crcs_array += '%u, ' % crc
- xml.message_crcs_array = xml.message_crcs_array[:-2]
-
- # form message info array
- xml.message_info_array = ''
- for name in xml.message_names:
- if name is not None:
- xml.message_info_array += 'MAVLINK_MESSAGE_INFO_%s, ' % name
- else:
- # Several C compilers don't accept {NULL} for
- # multi-dimensional arrays and structs
- # feed the compiler a "filled" empty message
- xml.message_info_array += '{"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, '
- xml.message_info_array = xml.message_info_array[:-2]
-
- # add some extra field attributes for convenience with arrays
- for m in xml.message:
- m.msg_name = m.name
- if xml.crc_extra:
- m.crc_extra_arg = ", %s" % m.crc_extra
- else:
- m.crc_extra_arg = ""
- for f in m.fields:
- if f.print_format is None:
- f.c_print_format = 'NULL'
- else:
- f.c_print_format = '"%s"' % f.print_format
- if f.array_length != 0:
- f.array_suffix = '[%u]' % f.array_length
- f.array_prefix = '*'
- f.array_tag = '_array'
- f.array_arg = ', %u' % f.array_length
- f.array_return_arg = '%s, %u, ' % (f.name, f.array_length)
- f.array_const = 'const '
- f.decode_left = ''
- f.decode_right = ', %s->%s' % (m.name_lower, f.name)
- f.return_type = 'uint16_t'
- f.get_arg = ', %s *%s' % (f.type, f.name)
- if f.type == 'char':
- f.c_test_value = '"%s"' % f.test_value
- else:
- test_strings = []
- for v in f.test_value:
- test_strings.append(str(v))
- f.c_test_value = '{ %s }' % ', '.join(test_strings)
- else:
- f.array_suffix = ''
- f.array_prefix = ''
- f.array_tag = ''
- f.array_arg = ''
- f.array_return_arg = ''
- f.array_const = ''
- f.decode_left = "%s->%s = " % (m.name_lower, f.name)
- f.decode_right = ''
- f.get_arg = ''
- f.return_type = f.type
- if f.type == 'char':
- f.c_test_value = "'%s'" % f.test_value
- elif f.type == 'uint64_t':
- f.c_test_value = "%sULL" % f.test_value
- elif f.type == 'int64_t':
- f.c_test_value = "%sLL" % f.test_value
- else:
- f.c_test_value = f.test_value
-
- # cope with uint8_t_mavlink_version
- for m in xml.message:
- m.arg_fields = []
- m.array_fields = []
- m.scalar_fields = []
- for f in m.ordered_fields:
- if f.array_length != 0:
- m.array_fields.append(f)
- else:
- m.scalar_fields.append(f)
- for f in m.fields:
- if not f.omit_arg:
- m.arg_fields.append(f)
- f.putname = f.name
- else:
- f.putname = f.const_value
-
- generate_mavlink_h(directory, xml)
- generate_version_h(directory, xml)
- generate_main_h(directory, xml)
- for m in xml.message:
- generate_message_h(directory, m)
- generate_testsuite_h(directory, xml)
-
-
-def generate(basename, xml_list):
- '''generate complete MAVLink C implemenation'''
-
- for xml in xml_list:
- generate_one(basename, xml)
- copy_fixed_headers(basename, xml_list[0])
- copy_fixed_sources(basename, xml_list[0])
diff --git a/mavlink/share/pyshared/pymavlink/generator/mavgen_python.py b/mavlink/share/pyshared/pymavlink/generator/mavgen_python.py
deleted file mode 100644
index fad366a68..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/mavgen_python.py
+++ /dev/null
@@ -1,455 +0,0 @@
-#!/usr/bin/env python
-'''
-parse a MAVLink protocol XML file and generate a python implementation
-
-Copyright Andrew Tridgell 2011
-Released under GNU GPL version 3 or later
-'''
-
-import sys, textwrap, os
-import mavparse, mavtemplate
-
-t = mavtemplate.MAVTemplate()
-
-def generate_preamble(outf, msgs, args, xml):
- print("Generating preamble")
- t.write(outf, """
-'''
-MAVLink protocol implementation (auto-generated by mavgen.py)
-
-Generated from: ${FILELIST}
-
-Note: this file has been auto-generated. DO NOT EDIT
-'''
-
-import struct, array, mavutil, time
-
-WIRE_PROTOCOL_VERSION = "${WIRE_PROTOCOL_VERSION}"
-
-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', ${PROTOCOL_MARKER}, 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 ${crc_extra}: # using CRC extra
- crc.accumulate(chr(crc_extra))
- self._crc = crc.crc
- self._msgbuf += struct.pack('<H', self._crc)
- return self._msgbuf
-
-""", {'FILELIST' : ",".join(args),
- 'PROTOCOL_MARKER' : xml.protocol_marker,
- 'crc_extra' : xml.crc_extra,
- 'WIRE_PROTOCOL_VERSION' : xml.wire_protocol_version })
-
-
-def generate_enums(outf, enums):
- print("Generating enums")
- outf.write("\n# enums\n")
- wrapper = textwrap.TextWrapper(initial_indent="", subsequent_indent=" # ")
- for e in enums:
- outf.write("\n# %s\n" % e.name)
- for entry in e.entry:
- outf.write("%s = %u # %s\n" % (entry.name, entry.value, wrapper.fill(entry.description)))
-
-def generate_message_ids(outf, msgs):
- print("Generating message IDs")
- outf.write("\n# message IDs\n")
- outf.write("MAVLINK_MSG_ID_BAD_DATA = -1\n")
- for m in msgs:
- outf.write("MAVLINK_MSG_ID_%s = %u\n" % (m.name.upper(), m.id))
-
-def generate_classes(outf, msgs):
- print("Generating class definitions")
- wrapper = textwrap.TextWrapper(initial_indent=" ", subsequent_indent=" ")
- for m in msgs:
- outf.write("""
-class MAVLink_%s_message(MAVLink_message):
- '''
-%s
- '''
- def __init__(self""" % (m.name.lower(), wrapper.fill(m.description.strip())))
- if len(m.fields) != 0:
- outf.write(", " + ", ".join(m.fieldnames))
- outf.write("):\n")
- outf.write(" MAVLink_message.__init__(self, MAVLINK_MSG_ID_%s, '%s')\n" % (m.name.upper(), m.name.upper()))
- if len(m.fieldnames) != 0:
- outf.write(" self._fieldnames = ['%s']\n" % "', '".join(m.fieldnames))
- for f in m.fields:
- outf.write(" self.%s = %s\n" % (f.name, f.name))
- outf.write("""
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, %u, struct.pack('%s'""" % (m.crc_extra, m.fmtstr))
- if len(m.fields) != 0:
- outf.write(", self." + ", self.".join(m.ordered_fieldnames))
- outf.write("))\n")
-
-
-def mavfmt(field):
- '''work out the struct format for a type'''
- map = {
- 'float' : 'f',
- 'double' : 'd',
- 'char' : 'c',
- 'int8_t' : 'b',
- 'uint8_t' : 'B',
- 'uint8_t_mavlink_version' : 'B',
- 'int16_t' : 'h',
- 'uint16_t' : 'H',
- 'int32_t' : 'i',
- 'uint32_t' : 'I',
- 'int64_t' : 'q',
- 'uint64_t' : 'Q',
- }
-
- if field.array_length:
- if field.type in ['char', 'int8_t', 'uint8_t']:
- return str(field.array_length)+'s'
- return str(field.array_length)+map[field.type]
- return map[field.type]
-
-def generate_mavlink_class(outf, msgs, xml):
- print("Generating MAVLink class")
-
- outf.write("\n\nmavlink_map = {\n");
- for m in msgs:
- outf.write(" MAVLINK_MSG_ID_%s : ( '%s', MAVLink_%s_message, %s, %u ),\n" % (
- m.name.upper(), m.fmtstr, m.name.lower(), m.order_map, m.crc_extra))
- outf.write("}\n\n")
-
- t.write(outf, """
-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 = ${protocol_marker}
- self.little_endian = ${little_endian}
- self.crc_extra = ${crc_extra}
- self.sort_fields = ${sort_fields}
- 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] != ${protocol_marker}:
- 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) != ${protocol_marker}:
- 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 ${crc_extra}: # 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 ${sort_fields}:
- 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
-""", xml)
-
-def generate_methods(outf, msgs):
- print("Generating methods")
-
- def field_descriptions(fields):
- ret = ""
- for f in fields:
- ret += " %-18s : %s (%s)\n" % (f.name, f.description.strip(), f.type)
- return ret
-
- wrapper = textwrap.TextWrapper(initial_indent="", subsequent_indent=" ")
-
- for m in msgs:
- comment = "%s\n\n%s" % (wrapper.fill(m.description.strip()), field_descriptions(m.fields))
-
- selffieldnames = 'self, '
- for f in m.fields:
- if f.omit_arg:
- selffieldnames += '%s=%s, ' % (f.name, f.const_value)
- else:
- selffieldnames += '%s, ' % f.name
- selffieldnames = selffieldnames[:-2]
-
- sub = {'NAMELOWER' : m.name.lower(),
- 'SELFFIELDNAMES' : selffieldnames,
- 'COMMENT' : comment,
- 'FIELDNAMES' : ", ".join(m.fieldnames)}
-
- t.write(outf, """
- def ${NAMELOWER}_encode(${SELFFIELDNAMES}):
- '''
- ${COMMENT}
- '''
- msg = MAVLink_${NAMELOWER}_message(${FIELDNAMES})
- msg.pack(self)
- return msg
-
-""", sub)
-
- t.write(outf, """
- def ${NAMELOWER}_send(${SELFFIELDNAMES}):
- '''
- ${COMMENT}
- '''
- return self.send(self.${NAMELOWER}_encode(${FIELDNAMES}))
-
-""", sub)
-
-
-def generate(basename, xml):
- '''generate complete python implemenation'''
- if basename.endswith('.py'):
- filename = basename
- else:
- filename = basename + '.py'
-
- msgs = []
- enums = []
- filelist = []
- for x in xml:
- msgs.extend(x.message)
- enums.extend(x.enum)
- filelist.append(os.path.basename(x.filename))
-
- for m in msgs:
- if xml[0].little_endian:
- m.fmtstr = '<'
- else:
- m.fmtstr = '>'
- for f in m.ordered_fields:
- m.fmtstr += mavfmt(f)
- m.order_map = [ 0 ] * len(m.fieldnames)
- for i in range(0, len(m.fieldnames)):
- m.order_map[i] = m.ordered_fieldnames.index(m.fieldnames[i])
-
- print("Generating %s" % filename)
- outf = open(filename, "w")
- generate_preamble(outf, msgs, filelist, xml[0])
- generate_enums(outf, enums)
- generate_message_ids(outf, msgs)
- generate_classes(outf, msgs)
- generate_mavlink_class(outf, msgs, xml[0])
- generate_methods(outf, msgs)
- outf.close()
- print("Generated %s OK" % filename)
diff --git a/mavlink/share/pyshared/pymavlink/generator/mavparse.py b/mavlink/share/pyshared/pymavlink/generator/mavparse.py
deleted file mode 100644
index cd2e6a55f..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/mavparse.py
+++ /dev/null
@@ -1,372 +0,0 @@
-#!/usr/bin/env python
-'''
-mavlink python parse functions
-
-Copyright Andrew Tridgell 2011
-Released under GNU GPL version 3 or later
-'''
-
-import xml.parsers.expat, os, errno, time, sys, operator, mavutil
-
-PROTOCOL_0_9 = "0.9"
-PROTOCOL_1_0 = "1.0"
-
-class MAVParseError(Exception):
- def __init__(self, message, inner_exception=None):
- self.message = message
- self.inner_exception = inner_exception
- self.exception_info = sys.exc_info()
- def __str__(self):
- return self.message
-
-class MAVField(object):
- def __init__(self, name, type, print_format, xml, description=''):
- self.name = name
- self.name_upper = name.upper()
- self.description = description
- self.array_length = 0
- self.omit_arg = False
- self.const_value = None
- self.print_format = print_format
- lengths = {
- 'float' : 4,
- 'double' : 8,
- 'char' : 1,
- 'int8_t' : 1,
- 'uint8_t' : 1,
- 'uint8_t_mavlink_version' : 1,
- 'int16_t' : 2,
- 'uint16_t' : 2,
- 'int32_t' : 4,
- 'uint32_t' : 4,
- 'int64_t' : 8,
- 'uint64_t' : 8,
- }
-
- if type=='uint8_t_mavlink_version':
- type = 'uint8_t'
- self.omit_arg = True
- self.const_value = xml.version
-
- aidx = type.find("[")
- if aidx != -1:
- assert type[-1:] == ']'
- self.array_length = int(type[aidx+1:-1])
- type = type[0:aidx]
- if type == 'array':
- type = 'int8_t'
- if type in lengths:
- self.type_length = lengths[type]
- self.type = type
- elif (type+"_t") in lengths:
- self.type_length = lengths[type+"_t"]
- self.type = type+'_t'
- else:
- raise MAVParseError("unknown type '%s'" % type)
- if self.array_length != 0:
- self.wire_length = self.array_length * self.type_length
- else:
- self.wire_length = self.type_length
- self.type_upper = self.type.upper()
-
- def gen_test_value(self, i):
- '''generate a testsuite value for a MAVField'''
- if self.const_value:
- return self.const_value
- elif self.type == 'float':
- return 17.0 + self.wire_offset*7 + i
- elif self.type == 'double':
- return 123.0 + self.wire_offset*7 + i
- elif self.type == 'char':
- return chr(ord('A') + (self.wire_offset + i)%26)
- elif self.type in [ 'int8_t', 'uint8_t' ]:
- return (5 + self.wire_offset*67 + i) & 0xFF
- elif self.type in ['int16_t', 'uint16_t']:
- return (17235 + self.wire_offset*52 + i) & 0xFFFF
- elif self.type in ['int32_t', 'uint32_t']:
- return (963497464 + self.wire_offset*52 + i)&0xFFFFFFFF
- elif self.type in ['int64_t', 'uint64_t']:
- return 93372036854775807 + self.wire_offset*63 + i
- else:
- raise MAVError('unknown type %s' % self.type)
-
- def set_test_value(self):
- '''set a testsuite value for a MAVField'''
- if self.array_length:
- self.test_value = []
- for i in range(self.array_length):
- self.test_value.append(self.gen_test_value(i))
- else:
- self.test_value = self.gen_test_value(0)
- if self.type == 'char' and self.array_length:
- v = ""
- for c in self.test_value:
- v += c
- self.test_value = v[:-1]
-
-
-class MAVType(object):
- def __init__(self, name, id, linenumber, description=''):
- self.name = name
- self.name_lower = name.lower()
- self.linenumber = linenumber
- self.id = int(id)
- self.description = description
- self.fields = []
- self.fieldnames = []
-
-class MAVEnumParam(object):
- def __init__(self, index, description=''):
- self.index = index
- self.description = description
-
-class MAVEnumEntry(object):
- def __init__(self, name, value, description='', end_marker=False):
- self.name = name
- self.value = value
- self.description = description
- self.param = []
- self.end_marker = end_marker
-
-class MAVEnum(object):
- def __init__(self, name, linenumber, description=''):
- self.name = name
- self.description = description
- self.entry = []
- self.highest_value = 0
- self.linenumber = linenumber
-
-class MAVXML(object):
- '''parse a mavlink XML file'''
- def __init__(self, filename, wire_protocol_version=PROTOCOL_0_9):
- self.filename = filename
- self.basename = os.path.basename(filename)
- if self.basename.lower().endswith(".xml"):
- self.basename = self.basename[:-4]
- self.basename_upper = self.basename.upper()
- self.message = []
- self.enum = []
- self.parse_time = time.asctime()
- self.version = 2
- self.include = []
- self.wire_protocol_version = wire_protocol_version
-
- if wire_protocol_version == PROTOCOL_0_9:
- self.protocol_marker = ord('U')
- self.sort_fields = False
- self.little_endian = False
- self.crc_extra = False
- elif wire_protocol_version == PROTOCOL_1_0:
- self.protocol_marker = 0xFE
- self.sort_fields = True
- self.little_endian = True
- self.crc_extra = True
- else:
- print("Unknown wire protocol version")
- print("Available versions are: %s %s" % (PROTOCOL_0_9, PROTOCOL_1_0))
- raise MAVParseError('Unknown MAVLink wire protocol version %s' % wire_protocol_version)
-
- in_element_list = []
-
- def check_attrs(attrs, check, where):
- for c in check:
- if not c in attrs:
- raise MAVParseError('expected missing %s "%s" attribute at %s:%u' % (
- where, c, filename, p.CurrentLineNumber))
-
- def start_element(name, attrs):
- in_element_list.append(name)
- in_element = '.'.join(in_element_list)
- #print in_element
- if in_element == "mavlink.messages.message":
- check_attrs(attrs, ['name', 'id'], 'message')
- self.message.append(MAVType(attrs['name'], attrs['id'], p.CurrentLineNumber))
- elif in_element == "mavlink.messages.message.field":
- check_attrs(attrs, ['name', 'type'], 'field')
- if 'print_format' in attrs:
- print_format = attrs['print_format']
- else:
- print_format = None
- self.message[-1].fields.append(MAVField(attrs['name'], attrs['type'],
- print_format, self))
- elif in_element == "mavlink.enums.enum":
- check_attrs(attrs, ['name'], 'enum')
- self.enum.append(MAVEnum(attrs['name'], p.CurrentLineNumber))
- elif in_element == "mavlink.enums.enum.entry":
- check_attrs(attrs, ['name'], 'enum entry')
- if 'value' in attrs:
- value = int(attrs['value'])
- else:
- value = self.enum[-1].highest_value + 1
- if (value > self.enum[-1].highest_value):
- self.enum[-1].highest_value = value
- self.enum[-1].entry.append(MAVEnumEntry(attrs['name'], value))
- elif in_element == "mavlink.enums.enum.entry.param":
- check_attrs(attrs, ['index'], 'enum param')
- self.enum[-1].entry[-1].param.append(MAVEnumParam(attrs['index']))
-
- def end_element(name):
- in_element = '.'.join(in_element_list)
- if in_element == "mavlink.enums.enum":
- # add a ENUM_END
- self.enum[-1].entry.append(MAVEnumEntry("%s_ENUM_END" % self.enum[-1].name,
- self.enum[-1].highest_value+1, end_marker=True))
- in_element_list.pop()
-
- def char_data(data):
- in_element = '.'.join(in_element_list)
- if in_element == "mavlink.messages.message.description":
- self.message[-1].description += data
- elif in_element == "mavlink.messages.message.field":
- self.message[-1].fields[-1].description += data
- elif in_element == "mavlink.enums.enum.description":
- self.enum[-1].description += data
- elif in_element == "mavlink.enums.enum.entry.description":
- self.enum[-1].entry[-1].description += data
- elif in_element == "mavlink.enums.enum.entry.param":
- self.enum[-1].entry[-1].param[-1].description += data
- elif in_element == "mavlink.version":
- self.version = int(data)
- elif in_element == "mavlink.include":
- self.include.append(data)
-
- f = open(filename, mode='rb')
- p = xml.parsers.expat.ParserCreate()
- p.StartElementHandler = start_element
- p.EndElementHandler = end_element
- p.CharacterDataHandler = char_data
- p.ParseFile(f)
- f.close()
-
- self.message_lengths = [ 0 ] * 256
- self.message_crcs = [ 0 ] * 256
- self.message_names = [ None ] * 256
- self.largest_payload = 0
-
- for m in self.message:
- m.wire_length = 0
- m.fieldnames = []
- m.ordered_fieldnames = []
- if self.sort_fields:
- m.ordered_fields = sorted(m.fields,
- key=operator.attrgetter('type_length'),
- reverse=True)
- else:
- m.ordered_fields = m.fields
- for f in m.fields:
- m.fieldnames.append(f.name)
- for f in m.ordered_fields:
- f.wire_offset = m.wire_length
- m.wire_length += f.wire_length
- m.ordered_fieldnames.append(f.name)
- f.set_test_value()
- m.num_fields = len(m.fieldnames)
- if m.num_fields > 64:
- raise MAVParseError("num_fields=%u : Maximum number of field names allowed is" % (
- m.num_fields, 64))
- m.crc_extra = message_checksum(m)
- self.message_lengths[m.id] = m.wire_length
- self.message_names[m.id] = m.name
- self.message_crcs[m.id] = m.crc_extra
- if m.wire_length > self.largest_payload:
- self.largest_payload = m.wire_length
-
- if m.wire_length+8 > 64:
- print("Note: message %s is longer than 64 bytes long (%u bytes), which can cause fragmentation since many radio modems use 64 bytes as maximum air transfer unit." % (m.name, m.wire_length+8))
-
- def __str__(self):
- return "MAVXML for %s from %s (%u message, %u enums)" % (
- self.basename, self.filename, len(self.message), len(self.enum))
-
-
-def message_checksum(msg):
- '''calculate a 8-bit checksum of the key fields of a message, so we
- can detect incompatible XML changes'''
- crc = mavutil.x25crc(msg.name + ' ')
- for f in msg.ordered_fields:
- crc.accumulate(f.type + ' ')
- crc.accumulate(f.name + ' ')
- if f.array_length:
- crc.accumulate(chr(f.array_length))
- return (crc.crc&0xFF) ^ (crc.crc>>8)
-
-def merge_enums(xml):
- '''merge enums between XML files'''
- emap = {}
- for x in xml:
- newenums = []
- for enum in x.enum:
- if enum.name in emap:
- emap[enum.name].entry.pop() # remove end marker
- emap[enum.name].entry.extend(enum.entry)
- print("Merged enum %s" % enum.name)
- else:
- newenums.append(enum)
- emap[enum.name] = enum
- x.enum = newenums
- # sort by value
- for e in emap:
- emap[e].entry = sorted(emap[e].entry,
- key=operator.attrgetter('value'),
- reverse=False)
-
-
-def check_duplicates(xml):
- '''check for duplicate message IDs'''
-
- merge_enums(xml)
-
- msgmap = {}
- enummap = {}
- for x in xml:
- for m in x.message:
- if m.id in msgmap:
- print("ERROR: Duplicate message id %u for %s (%s:%u) also used by %s" % (
- m.id, m.name,
- x.filename, m.linenumber,
- msgmap[m.id]))
- return True
- fieldset = set()
- for f in m.fields:
- if f.name in fieldset:
- print("ERROR: Duplicate field %s in message %s (%s:%u)" % (
- f.name, m.name,
- x.filename, m.linenumber))
- return True
- fieldset.add(f.name)
- msgmap[m.id] = '%s (%s:%u)' % (m.name, x.filename, m.linenumber)
- for enum in x.enum:
- for entry in enum.entry:
- s1 = "%s.%s" % (enum.name, entry.name)
- s2 = "%s.%s" % (enum.name, entry.value)
- if s1 in enummap or s2 in enummap:
- print("ERROR: Duplicate enums %s/%s at %s:%u and %s" % (
- s1, entry.value, x.filename, enum.linenumber,
- enummap.get(s1) or enummap.get(s2)))
- return True
- enummap[s1] = "%s:%u" % (x.filename, enum.linenumber)
- enummap[s2] = "%s:%u" % (x.filename, enum.linenumber)
-
- return False
-
-
-
-def total_msgs(xml):
- '''count total number of msgs'''
- count = 0
- for x in xml:
- count += len(x.message)
- return count
-
-def mkdir_p(dir):
- try:
- os.makedirs(dir)
- except OSError as exc:
- if exc.errno == errno.EEXIST:
- pass
- else: raise
-
-# check version consistent
-# add test.xml
-# finish test suite
-# printf style error macro, if defined call errors
diff --git a/mavlink/share/pyshared/pymavlink/generator/mavtemplate.py b/mavlink/share/pyshared/pymavlink/generator/mavtemplate.py
deleted file mode 100644
index 6ef015315..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/mavtemplate.py
+++ /dev/null
@@ -1,121 +0,0 @@
-#!/usr/bin/env python
-'''
-simple templating system for mavlink generator
-
-Copyright Andrew Tridgell 2011
-Released under GNU GPL version 3 or later
-'''
-
-from mavparse import MAVParseError
-
-class MAVTemplate(object):
- '''simple templating system'''
- def __init__(self,
- start_var_token="${",
- end_var_token="}",
- start_rep_token="${{",
- end_rep_token="}}",
- trim_leading_lf=True,
- checkmissing=True):
- self.start_var_token = start_var_token
- self.end_var_token = end_var_token
- self.start_rep_token = start_rep_token
- self.end_rep_token = end_rep_token
- self.trim_leading_lf = trim_leading_lf
- self.checkmissing = checkmissing
-
- def find_end(self, text, start_token, end_token):
- '''find the of a token.
- Returns the offset in the string immediately after the matching end_token'''
- if not text.startswith(start_token):
- raise MAVParseError("invalid token start")
- offset = len(start_token)
- nesting = 1
- while nesting > 0:
- idx1 = text[offset:].find(start_token)
- idx2 = text[offset:].find(end_token)
- if idx1 == -1 and idx2 == -1:
- raise MAVParseError("token nesting error")
- if idx1 == -1 or idx1 > idx2:
- offset += idx2 + len(end_token)
- nesting -= 1
- else:
- offset += idx1 + len(start_token)
- nesting += 1
- return offset
-
- def find_var_end(self, text):
- '''find the of a variable'''
- return self.find_end(text, self.start_var_token, self.end_var_token)
-
- def find_rep_end(self, text):
- '''find the of a repitition'''
- return self.find_end(text, self.start_rep_token, self.end_rep_token)
-
- def substitute(self, text, subvars={},
- trim_leading_lf=None, checkmissing=None):
- '''substitute variables in a string'''
-
- if trim_leading_lf is None:
- trim_leading_lf = self.trim_leading_lf
- if checkmissing is None:
- checkmissing = self.checkmissing
-
- # handle repititions
- while True:
- subidx = text.find(self.start_rep_token)
- if subidx == -1:
- break
- endidx = self.find_rep_end(text[subidx:])
- if endidx == -1:
- raise MAVParseError("missing end macro in %s" % text[subidx:])
- part1 = text[0:subidx]
- part2 = text[subidx+len(self.start_rep_token):subidx+(endidx-len(self.end_rep_token))]
- part3 = text[subidx+endidx:]
- a = part2.split(':')
- field_name = a[0]
- rest = ':'.join(a[1:])
- v = getattr(subvars, field_name, None)
- if v is None:
- raise MAVParseError('unable to find field %s' % field_name)
- t1 = part1
- for f in v:
- t1 += self.substitute(rest, f, trim_leading_lf=False, checkmissing=False)
- if len(v) != 0 and t1[-1] in ["\n", ","]:
- t1 = t1[:-1]
- t1 += part3
- text = t1
-
- if trim_leading_lf:
- if text[0] == '\n':
- text = text[1:]
- while True:
- idx = text.find(self.start_var_token)
- if idx == -1:
- return text
- endidx = text[idx:].find(self.end_var_token)
- if endidx == -1:
- raise MAVParseError('missing end of variable: %s' % text[idx:idx+10])
- varname = text[idx+2:idx+endidx]
- if isinstance(subvars, dict):
- if not varname in subvars:
- if checkmissing:
- raise MAVParseError("unknown variable in '%s%s%s'" % (
- self.start_var_token, varname, self.end_var_token))
- return text[0:idx+endidx] + self.substitute(text[idx+endidx:], subvars,
- trim_leading_lf=False, checkmissing=False)
- value = subvars[varname]
- else:
- value = getattr(subvars, varname, None)
- if value is None:
- if checkmissing:
- raise MAVParseError("unknown variable in '%s%s%s'" % (
- self.start_var_token, varname, self.end_var_token))
- return text[0:idx+endidx] + self.substitute(text[idx+endidx:], subvars,
- trim_leading_lf=False, checkmissing=False)
- text = text.replace("%s%s%s" % (self.start_var_token, varname, self.end_var_token), str(value))
- return text
-
- def write(self, file, text, subvars={}, trim_leading_lf=True):
- '''write to a file with variable substitution'''
- file.write(self.substitute(text, subvars=subvars, trim_leading_lf=trim_leading_lf))
diff --git a/mavlink/share/pyshared/pymavlink/generator/mavtestgen.py b/mavlink/share/pyshared/pymavlink/generator/mavtestgen.py
deleted file mode 100644
index faffa1c19..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/mavtestgen.py
+++ /dev/null
@@ -1,142 +0,0 @@
-#!/usr/bin/env python
-'''
-generate a MAVLink test suite
-
-Copyright Andrew Tridgell 2011
-Released under GNU GPL version 3 or later
-'''
-
-import sys, textwrap
-from optparse import OptionParser
-
-# mavparse is up a directory level
-sys.path.append('..')
-import mavparse
-
-def gen_value(f, i, language):
- '''generate a test value for the ith field of a message'''
- type = f.type
-
- # could be an array
- if type.find("[") != -1:
- aidx = type.find("[")
- basetype = type[0:aidx]
- if basetype == "array":
- basetype = "int8_t"
- if language == 'C':
- return '(const %s *)"%s%u"' % (basetype, f.name, i)
- return '"%s%u"' % (f.name, i)
-
- if type == 'float':
- return 17.0 + i*7
- if type == 'char':
- return 'A' + i
- if type == 'int8_t':
- return 5 + i
- if type in ['int8_t', 'uint8_t']:
- return 5 + i
- if type in ['uint8_t_mavlink_version']:
- return 2
- if type in ['int16_t', 'uint16_t']:
- return 17235 + i*52
- if type in ['int32_t', 'uint32_t']:
- v = 963497464 + i*52
- if language == 'C':
- return "%sL" % v
- return v
- if type in ['int64_t', 'uint64_t']:
- v = 9223372036854775807 + i*63
- if language == 'C':
- return "%sLL" % v
- return v
-
-
-
-def generate_methods_python(outf, msgs):
- outf.write("""
-'''
-MAVLink protocol test implementation (auto-generated by mavtestgen.py)
-
-Generated from: %s
-
-Note: this file has been auto-generated. DO NOT EDIT
-'''
-
-import mavlink
-
-def generate_outputs(mav):
- '''generate all message types as outputs'''
-""")
- for m in msgs:
- if m.name == "HEARTBEAT": continue
- outf.write("\tmav.%s_send(" % m.name.lower())
- for i in range(0, len(m.fields)):
- f = m.fields[i]
- outf.write("%s=%s" % (f.name, gen_value(f, i, 'py')))
- if i != len(m.fields)-1:
- outf.write(",")
- outf.write(")\n")
-
-
-def generate_methods_C(outf, msgs):
- outf.write("""
-/*
-MAVLink protocol test implementation (auto-generated by mavtestgen.py)
-
-Generated from: %s
-
-Note: this file has been auto-generated. DO NOT EDIT
-*/
-
-static void mavtest_generate_outputs(mavlink_channel_t chan)
-{
-""")
- for m in msgs:
- if m.name == "HEARTBEAT": continue
- outf.write("\tmavlink_msg_%s_send(chan," % m.name.lower())
- for i in range(0, len(m.fields)):
- f = m.fields[i]
- outf.write("%s" % gen_value(f, i, 'C'))
- if i != len(m.fields)-1:
- outf.write(",")
- outf.write(");\n")
- outf.write("}\n")
-
-
-
-######################################################################
-'''main program'''
-
-parser = OptionParser("%prog [options] <XML files>")
-parser.add_option("-o", "--output", dest="output", default="mavtest", help="output folder [default: %default]")
-(opts, args) = parser.parse_args()
-
-if len(args) < 1:
- parser.error("You must supply at least one MAVLink XML protocol definition")
-
-
-msgs = []
-enums = []
-
-for fname in args:
- (m, e) = mavparse.parse_mavlink_xml(fname)
- msgs.extend(m)
- enums.extend(e)
-
-
-if mavparse.check_duplicates(msgs):
- sys.exit(1)
-
-print("Found %u MAVLink message types" % len(msgs))
-
-print("Generating python %s" % (opts.output+'.py'))
-outf = open(opts.output + '.py', "w")
-generate_methods_python(outf, msgs)
-outf.close()
-
-print("Generating C %s" % (opts.output+'.h'))
-outf = open(opts.output + '.h', "w")
-generate_methods_C(outf, msgs)
-outf.close()
-
-print("Generated %s OK" % opts.output)
diff --git a/mavlink/share/pyshared/pymavlink/mavextra.py b/mavlink/share/pyshared/pymavlink/mavextra.py
deleted file mode 100644
index 5395f6036..000000000
--- a/mavlink/share/pyshared/pymavlink/mavextra.py
+++ /dev/null
@@ -1,154 +0,0 @@
-#!/usr/bin/env python
-'''
-useful extra functions for use by mavlink clients
-
-Copyright Andrew Tridgell 2011
-Released under GNU GPL version 3 or later
-'''
-
-from math import *
-
-
-def kmh(mps):
- '''convert m/s to Km/h'''
- return mps*3.6
-
-def altitude(press_abs, ground_press=955.0, ground_temp=30):
- '''calculate barometric altitude'''
- return log(ground_press/press_abs)*(ground_temp+273.15)*29271.267*0.001
-
-
-def mag_heading(RAW_IMU, ATTITUDE, declination=0, SENSOR_OFFSETS=None, ofs=None):
- '''calculate heading from raw magnetometer'''
- mag_x = RAW_IMU.xmag
- mag_y = RAW_IMU.ymag
- mag_z = RAW_IMU.zmag
- if SENSOR_OFFSETS is not None and ofs is not None:
- mag_x += ofs[0] - SENSOR_OFFSETS.mag_ofs_x
- mag_y += ofs[1] - SENSOR_OFFSETS.mag_ofs_y
- mag_z += ofs[2] - SENSOR_OFFSETS.mag_ofs_z
-
- headX = mag_x*cos(ATTITUDE.pitch) + mag_y*sin(ATTITUDE.roll)*sin(ATTITUDE.pitch) + mag_z*cos(ATTITUDE.roll)*sin(ATTITUDE.pitch)
- headY = mag_y*cos(ATTITUDE.roll) - mag_z*sin(ATTITUDE.roll)
- heading = degrees(atan2(-headY,headX)) + declination
- if heading < 0:
- heading += 360
- return heading
-
-def mag_field(RAW_IMU, SENSOR_OFFSETS=None, ofs=None):
- '''calculate magnetic field strength from raw magnetometer'''
- mag_x = RAW_IMU.xmag
- mag_y = RAW_IMU.ymag
- mag_z = RAW_IMU.zmag
- if SENSOR_OFFSETS is not None and ofs is not None:
- mag_x += ofs[0] - SENSOR_OFFSETS.mag_ofs_x
- mag_y += ofs[1] - SENSOR_OFFSETS.mag_ofs_y
- mag_z += ofs[2] - SENSOR_OFFSETS.mag_ofs_z
- return sqrt(mag_x**2 + mag_y**2 + mag_z**2)
-
-def angle_diff(angle1, angle2):
- '''show the difference between two angles in degrees'''
- ret = angle1 - angle2
- if ret > 180:
- ret -= 360;
- if ret < -180:
- ret += 360
- return ret
-
-
-lowpass_data = {}
-
-def lowpass(var, key, factor):
- '''a simple lowpass filter'''
- global lowpass_data
- if not key in lowpass_data:
- lowpass_data[key] = var
- else:
- lowpass_data[key] = factor*lowpass_data[key] + (1.0 - factor)*var
- return lowpass_data[key]
-
-last_delta = {}
-
-def delta(var, key):
- '''calculate slope'''
- global last_delta
- dv = 0
- if key in last_delta:
- dv = var - last_delta[key]
- last_delta[key] = var
- return dv
-
-def delta_angle(var, key):
- '''calculate slope of an angle'''
- global last_delta
- dv = 0
- if key in last_delta:
- dv = var - last_delta[key]
- last_delta[key] = var
- if dv > 180:
- dv -= 360
- if dv < -180:
- dv += 360
- return dv
-
-def roll_estimate(RAW_IMU,smooth=0.7):
- '''estimate roll from accelerometer'''
- rx = lowpass(RAW_IMU.xacc,'rx',smooth)
- ry = lowpass(RAW_IMU.yacc,'ry',smooth)
- rz = lowpass(RAW_IMU.zacc,'rz',smooth)
- return degrees(-asin(ry/sqrt(rx**2+ry**2+rz**2)))
-
-def pitch_estimate(RAW_IMU, smooth=0.7):
- '''estimate pitch from accelerometer'''
- rx = lowpass(RAW_IMU.xacc,'rx',smooth)
- ry = lowpass(RAW_IMU.yacc,'ry',smooth)
- rz = lowpass(RAW_IMU.zacc,'rz',smooth)
- return degrees(asin(rx/sqrt(rx**2+ry**2+rz**2)))
-
-def gravity(RAW_IMU, SENSOR_OFFSETS=None, ofs=None, smooth=0.7):
- '''estimate pitch from accelerometer'''
- rx = RAW_IMU.xacc
- ry = RAW_IMU.yacc
- rz = RAW_IMU.zacc+45
- if SENSOR_OFFSETS is not None and ofs is not None:
- rx += ofs[0] - SENSOR_OFFSETS.accel_cal_x
- ry += ofs[1] - SENSOR_OFFSETS.accel_cal_y
- rz += ofs[2] - SENSOR_OFFSETS.accel_cal_z
- return lowpass(sqrt(rx**2+ry**2+rz**2)*0.01,'_gravity',smooth)
-
-
-
-def pitch_sim(SIMSTATE, GPS_RAW):
- '''estimate pitch from SIMSTATE accels'''
- xacc = SIMSTATE.xacc - lowpass(delta(GPS_RAW.v,"v")*6.6, "v", 0.9)
- zacc = SIMSTATE.zacc
- zacc += SIMSTATE.ygyro * GPS_RAW.v;
- if xacc/zacc >= 1:
- return 0
- if xacc/zacc <= -1:
- return -0
- return degrees(-asin(xacc/zacc))
-
-def distance_two(GPS_RAW1, GPS_RAW2):
- '''distance between two points'''
- lat1 = radians(GPS_RAW1.lat)
- lat2 = radians(GPS_RAW2.lat)
- lon1 = radians(GPS_RAW1.lon)
- lon2 = radians(GPS_RAW2.lon)
- dLat = lat2 - lat1
- dLon = lon2 - lon1
-
- a = sin(0.5*dLat) * sin(0.5*dLat) + sin(0.5*dLon) * sin(0.5*dLon) * cos(lat1) * cos(lat2)
- c = 2.0 * atan2(sqrt(a), sqrt(1.0-a))
- return 6371 * 1000 * c
-
-
-first_fix = None
-
-def distance_home(GPS_RAW):
- '''distance from first fix point'''
- global first_fix
- if first_fix == None or first_fix.fix_type < 2:
- first_fix = GPS_RAW
- return 0
- return distance_two(GPS_RAW, first_fix)
diff --git a/mavlink/share/pyshared/pymavlink/mavlink.py b/mavlink/share/pyshared/pymavlink/mavlink.py
deleted file mode 100644
index 3287a921d..000000000
--- a/mavlink/share/pyshared/pymavlink/mavlink.py
+++ /dev/null
@@ -1,4930 +0,0 @@
-'''
-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))
-
diff --git a/mavlink/share/pyshared/pymavlink/mavlinkv10.py b/mavlink/share/pyshared/pymavlink/mavlinkv10.py
deleted file mode 100644
index a87e8e904..000000000
--- a/mavlink/share/pyshared/pymavlink/mavlinkv10.py
+++ /dev/null
@@ -1,5394 +0,0 @@
-'''
-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 = "1.0"
-
-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', 254, 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 True: # 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 MISSION.
-MAV_CMD_NAV_LOITER_UNLIM = 17 # Loiter around this MISSION an unlimited amount of time
-MAV_CMD_NAV_LOITER_TURNS = 18 # Loiter around this MISSION for X turns
-MAV_CMD_NAV_LOITER_TIME = 19 # Loiter around this MISSION 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 system.
-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_SET_SENSOR_OFFSETS = 242 # Set sensor offsets. 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_PREFLIGHT_REBOOT_SHUTDOWN = 246 # Request the reboot or shutdown of system components.
-MAV_CMD_OVERRIDE_GOTO = 252 # Hold / continue the current action
-MAV_CMD_MISSION_START = 300 # start running a mission
-MAV_CMD_ENUM_END = 301 #
-
-# 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_AUTOPILOT
-MAV_AUTOPILOT_GENERIC = 0 # Generic autopilot, full support for everything
-MAV_AUTOPILOT_PIXHAWK = 1 # PIXHAWK autopilot, http://pixhawk.ethz.ch
-MAV_AUTOPILOT_SLUGS = 2 # SLUGS autopilot, http://slugsuav.soe.ucsc.edu
-MAV_AUTOPILOT_ARDUPILOTMEGA = 3 # ArduPilotMega / ArduCopter, http://diydrones.com
-MAV_AUTOPILOT_OPENPILOT = 4 # OpenPilot, http://openpilot.org
-MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY = 5 # Generic autopilot only supporting simple waypoints
-MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY = 6 # Generic autopilot supporting waypoints and other simple navigation
- # commands
-MAV_AUTOPILOT_GENERIC_MISSION_FULL = 7 # Generic autopilot supporting the full mission command set
-MAV_AUTOPILOT_INVALID = 8 # No valid autopilot, e.g. a GCS or other MAVLink component
-MAV_AUTOPILOT_PPZ = 9 # PPZ UAV - http://nongnu.org/paparazzi
-MAV_AUTOPILOT_UDB = 10 # UAV Dev Board
-MAV_AUTOPILOT_FP = 11 # FlexiPilot
-MAV_AUTOPILOT_ENUM_END = 12 #
-
-# MAV_MODE_FLAG
-MAV_MODE_FLAG_CUSTOM_MODE_ENABLED = 1 # 0b00000001 Reserved for future use.
-MAV_MODE_FLAG_TEST_ENABLED = 2 # 0b00000010 system has a test mode enabled. This flag is intended for
- # temporary system tests and should not be
- # used for stable implementations.
-MAV_MODE_FLAG_AUTO_ENABLED = 4 # 0b00000100 autonomous mode enabled, system finds its own goal
- # positions. Guided flag can be set or not,
- # depends on the actual implementation.
-MAV_MODE_FLAG_GUIDED_ENABLED = 8 # 0b00001000 guided mode enabled, system flies MISSIONs / mission items.
-MAV_MODE_FLAG_STABILIZE_ENABLED = 16 # 0b00010000 system stabilizes electronically its attitude (and
- # optionally position). It needs however
- # further control inputs to move around.
-MAV_MODE_FLAG_HIL_ENABLED = 32 # 0b00100000 hardware in the loop simulation. All motors / actuators are
- # blocked, but internal software is full
- # operational.
-MAV_MODE_FLAG_MANUAL_INPUT_ENABLED = 64 # 0b01000000 remote control input is enabled.
-MAV_MODE_FLAG_SAFETY_ARMED = 128 # 0b10000000 MAV safety set to armed. Motors are enabled / running / can
- # start. Ready to fly.
-MAV_MODE_FLAG_ENUM_END = 129 #
-
-# MAV_MODE_FLAG_DECODE_POSITION
-MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE = 1 # Eighth bit: 00000001
-MAV_MODE_FLAG_DECODE_POSITION_TEST = 2 # Seventh bit: 00000010
-MAV_MODE_FLAG_DECODE_POSITION_AUTO = 4 # Sixt bit: 00000100
-MAV_MODE_FLAG_DECODE_POSITION_GUIDED = 8 # Fifth bit: 00001000
-MAV_MODE_FLAG_DECODE_POSITION_STABILIZE = 16 # Fourth bit: 00010000
-MAV_MODE_FLAG_DECODE_POSITION_HIL = 32 # Third bit: 00100000
-MAV_MODE_FLAG_DECODE_POSITION_MANUAL = 64 # Second bit: 01000000
-MAV_MODE_FLAG_DECODE_POSITION_SAFETY = 128 # First bit: 10000000
-MAV_MODE_FLAG_DECODE_POSITION_ENUM_END = 129 #
-
-# MAV_GOTO
-MAV_GOTO_DO_HOLD = 0 # Hold at the current position.
-MAV_GOTO_DO_CONTINUE = 1 # Continue with the next item in mission execution.
-MAV_GOTO_HOLD_AT_CURRENT_POSITION = 2 # Hold at the current position of the system
-MAV_GOTO_HOLD_AT_SPECIFIED_POSITION = 3 # Hold at the position specified in the parameters of the DO_HOLD action
-MAV_GOTO_ENUM_END = 4 #
-
-# MAV_MODE
-MAV_MODE_PREFLIGHT = 0 # System is not ready to fly, booting, calibrating, etc. No flag is set.
-MAV_MODE_MANUAL_DISARMED = 64 # System is allowed to be active, under manual (RC) control, no
- # stabilization
-MAV_MODE_TEST_DISARMED = 66 # UNDEFINED mode. This solely depends on the autopilot - use with
- # caution, intended for developers only.
-MAV_MODE_STABILIZE_DISARMED = 80 # System is allowed to be active, under assisted RC control.
-MAV_MODE_GUIDED_DISARMED = 88 # System is allowed to be active, under autonomous control, manual
- # setpoint
-MAV_MODE_AUTO_DISARMED = 92 # System is allowed to be active, under autonomous control and
- # navigation (the trajectory is decided
- # onboard and not pre-programmed by MISSIONs)
-MAV_MODE_MANUAL_ARMED = 192 # System is allowed to be active, under manual (RC) control, no
- # stabilization
-MAV_MODE_TEST_ARMED = 194 # UNDEFINED mode. This solely depends on the autopilot - use with
- # caution, intended for developers only.
-MAV_MODE_STABILIZE_ARMED = 208 # System is allowed to be active, under assisted RC control.
-MAV_MODE_GUIDED_ARMED = 216 # System is allowed to be active, under autonomous control, manual
- # setpoint
-MAV_MODE_AUTO_ARMED = 220 # System is allowed to be active, under autonomous control and
- # navigation (the trajectory is decided
- # onboard and not pre-programmed by MISSIONs)
-MAV_MODE_ENUM_END = 221 #
-
-# MAV_STATE
-MAV_STATE_UNINIT = 0 # Uninitialized system, state is unknown.
-MAV_STATE_BOOT = 1 # System is booting up.
-MAV_STATE_CALIBRATING = 2 # System is calibrating and not flight-ready.
-MAV_STATE_STANDBY = 3 # System is grounded and on standby. It can be launched any time.
-MAV_STATE_ACTIVE = 4 # System is active and might be already airborne. Motors are engaged.
-MAV_STATE_CRITICAL = 5 # System is in a non-normal flight mode. It can however still navigate.
-MAV_STATE_EMERGENCY = 6 # System is in a non-normal flight mode. It lost control over parts or
- # over the whole airframe. It is in mayday and
- # going down.
-MAV_STATE_POWEROFF = 7 # System just initialized its power-down sequence, will shut down now.
-MAV_STATE_ENUM_END = 8 #
-
-# MAV_TYPE
-MAV_TYPE_GENERIC = 0 # Generic micro air vehicle.
-MAV_TYPE_FIXED_WING = 1 # Fixed wing aircraft.
-MAV_TYPE_QUADROTOR = 2 # Quadrotor
-MAV_TYPE_COAXIAL = 3 # Coaxial helicopter
-MAV_TYPE_HELICOPTER = 4 # Normal helicopter with tail rotor.
-MAV_TYPE_ANTENNA_TRACKER = 5 # Ground installation
-MAV_TYPE_GCS = 6 # Operator control unit / ground control station
-MAV_TYPE_AIRSHIP = 7 # Airship, controlled
-MAV_TYPE_FREE_BALLOON = 8 # Free balloon, uncontrolled
-MAV_TYPE_ROCKET = 9 # Rocket
-MAV_TYPE_GROUND_ROVER = 10 # Ground rover
-MAV_TYPE_SURFACE_BOAT = 11 # Surface vessel, boat, ship
-MAV_TYPE_SUBMARINE = 12 # Submarine
-MAV_TYPE_HEXAROTOR = 13 # Hexarotor
-MAV_TYPE_OCTOROTOR = 14 # Octorotor
-MAV_TYPE_TRICOPTER = 15 # Octorotor
-MAV_TYPE_FLAPPING_WING = 16 # Flapping wing
-MAV_TYPE_ENUM_END = 17 #
-
-# MAV_COMPONENT
-MAV_COMP_ID_ALL = 0 #
-MAV_COMP_ID_CAMERA = 100 #
-MAV_COMP_ID_SERVO1 = 140 #
-MAV_COMP_ID_SERVO2 = 141 #
-MAV_COMP_ID_SERVO3 = 142 #
-MAV_COMP_ID_SERVO4 = 143 #
-MAV_COMP_ID_SERVO5 = 144 #
-MAV_COMP_ID_SERVO6 = 145 #
-MAV_COMP_ID_SERVO7 = 146 #
-MAV_COMP_ID_SERVO8 = 147 #
-MAV_COMP_ID_SERVO9 = 148 #
-MAV_COMP_ID_SERVO10 = 149 #
-MAV_COMP_ID_SERVO11 = 150 #
-MAV_COMP_ID_SERVO12 = 151 #
-MAV_COMP_ID_SERVO13 = 152 #
-MAV_COMP_ID_SERVO14 = 153 #
-MAV_COMP_ID_MAPPER = 180 #
-MAV_COMP_ID_MISSIONPLANNER = 190 #
-MAV_COMP_ID_PATHPLANNER = 195 #
-MAV_COMP_ID_IMU = 200 #
-MAV_COMP_ID_IMU_2 = 201 #
-MAV_COMP_ID_IMU_3 = 202 #
-MAV_COMP_ID_GPS = 220 #
-MAV_COMP_ID_UDP_BRIDGE = 240 #
-MAV_COMP_ID_UART_BRIDGE = 241 #
-MAV_COMP_ID_SYSTEM_CONTROL = 250 #
-MAV_COMPONENT_ENUM_END = 251 #
-
-# MAV_FRAME
-MAV_FRAME_GLOBAL = 0 # Global coordinate frame, WGS84 coordinate system. First value / x:
- # latitude, second value / y: longitude, third
- # value / z: positive altitude over mean sea
- # level (MSL)
-MAV_FRAME_LOCAL_NED = 1 # Local coordinate frame, Z-up (x: north, y: east, z: down).
-MAV_FRAME_MISSION = 2 # NOT a coordinate frame, indicates a mission command.
-MAV_FRAME_GLOBAL_RELATIVE_ALT = 3 # Global coordinate frame, WGS84 coordinate system, relative altitude
- # over ground with respect to the home
- # position. First value / x: latitude, second
- # value / y: longitude, third value / z:
- # positive altitude with 0 being at the
- # altitude of the home location.
-MAV_FRAME_LOCAL_ENU = 4 # Local coordinate frame, Z-down (x: east, y: north, z: up)
-MAV_FRAME_ENUM_END = 5 #
-
-# MAVLINK_DATA_STREAM_TYPE
-MAVLINK_DATA_STREAM_IMG_JPEG = 1 #
-MAVLINK_DATA_STREAM_IMG_BMP = 2 #
-MAVLINK_DATA_STREAM_IMG_RAW8U = 3 #
-MAVLINK_DATA_STREAM_IMG_RAW32U = 4 #
-MAVLINK_DATA_STREAM_IMG_PGM = 5 #
-MAVLINK_DATA_STREAM_IMG_PNG = 6 #
-MAVLINK_DATA_STREAM_TYPE_ENUM_END = 7 #
-
-# 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 MISSION.
-MAV_ROI_WPINDEX = 2 # Point toward given MISSION.
-MAV_ROI_LOCATION = 3 # Point toward fixed location.
-MAV_ROI_TARGET = 4 # Point toward of given id.
-MAV_ROI_ENUM_END = 5 #
-
-# MAV_CMD_ACK
-MAV_CMD_ACK_OK = 1 # Command / mission item is ok.
-MAV_CMD_ACK_ERR_FAIL = 2 # Generic error message if none of the other reasons fails or if no
- # detailed error reporting is implemented.
-MAV_CMD_ACK_ERR_ACCESS_DENIED = 3 # The system is refusing to accept this command from this source /
- # communication partner.
-MAV_CMD_ACK_ERR_NOT_SUPPORTED = 4 # Command or mission item is not supported, other commands would be
- # accepted.
-MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED = 5 # The coordinate frame of this command / mission item is not supported.
-MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE = 6 # The coordinate frame of this command is ok, but he coordinate values
- # exceed the safety limits of this system.
- # This is a generic error, please use the more
- # specific error messages below if possible.
-MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE = 7 # The X or latitude value is out of range.
-MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE = 8 # The Y or longitude value is out of range.
-MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE = 9 # The Z or altitude value is out of range.
-MAV_CMD_ACK_ENUM_END = 10 #
-
-# MAV_VAR
-MAV_VAR_FLOAT = 0 # 32 bit float
-MAV_VAR_UINT8 = 1 # 8 bit unsigned integer
-MAV_VAR_INT8 = 2 # 8 bit signed integer
-MAV_VAR_UINT16 = 3 # 16 bit unsigned integer
-MAV_VAR_INT16 = 4 # 16 bit signed integer
-MAV_VAR_UINT32 = 5 # 32 bit unsigned integer
-MAV_VAR_INT32 = 6 # 32 bit signed integer
-MAV_VAR_ENUM_END = 7 #
-
-# MAV_RESULT
-MAV_RESULT_ACCEPTED = 0 # Command ACCEPTED and EXECUTED
-MAV_RESULT_TEMPORARILY_REJECTED = 1 # Command TEMPORARY REJECTED/DENIED
-MAV_RESULT_DENIED = 2 # Command PERMANENTLY DENIED
-MAV_RESULT_UNSUPPORTED = 3 # Command UNKNOWN/UNSUPPORTED
-MAV_RESULT_FAILED = 4 # Command executed, but failed
-MAV_RESULT_ENUM_END = 5 #
-
-# MAV_MISSION_RESULT
-MAV_MISSION_ACCEPTED = 0 # mission accepted OK
-MAV_MISSION_ERROR = 1 # generic error / not accepting mission commands at all right now
-MAV_MISSION_UNSUPPORTED_FRAME = 2 # coordinate frame is not supported
-MAV_MISSION_UNSUPPORTED = 3 # command is not supported
-MAV_MISSION_NO_SPACE = 4 # mission item exceeds storage space
-MAV_MISSION_INVALID = 5 # one of the parameters has an invalid value
-MAV_MISSION_INVALID_PARAM1 = 6 # param1 has an invalid value
-MAV_MISSION_INVALID_PARAM2 = 7 # param2 has an invalid value
-MAV_MISSION_INVALID_PARAM3 = 8 # param3 has an invalid value
-MAV_MISSION_INVALID_PARAM4 = 9 # param4 has an invalid value
-MAV_MISSION_INVALID_PARAM5_X = 10 # x/param5 has an invalid value
-MAV_MISSION_INVALID_PARAM6_Y = 11 # y/param6 has an invalid value
-MAV_MISSION_INVALID_PARAM7 = 12 # param7 has an invalid value
-MAV_MISSION_INVALID_SEQUENCE = 13 # received waypoint out of sequence
-MAV_MISSION_DENIED = 14 # not accepting any mission commands from this communication partner
-MAV_MISSION_RESULT_ENUM_END = 15 #
-
-# 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_SYS_STATUS = 1
-MAVLINK_MSG_ID_SYSTEM_TIME = 2
-MAVLINK_MSG_ID_PING = 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_SET_MODE = 11
-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 = 24
-MAVLINK_MSG_ID_GPS_STATUS = 25
-MAVLINK_MSG_ID_SCALED_IMU = 26
-MAVLINK_MSG_ID_RAW_IMU = 27
-MAVLINK_MSG_ID_RAW_PRESSURE = 28
-MAVLINK_MSG_ID_SCALED_PRESSURE = 29
-MAVLINK_MSG_ID_ATTITUDE = 30
-MAVLINK_MSG_ID_ATTITUDE_QUATERNION = 31
-MAVLINK_MSG_ID_LOCAL_POSITION_NED = 32
-MAVLINK_MSG_ID_GLOBAL_POSITION_INT = 33
-MAVLINK_MSG_ID_RC_CHANNELS_SCALED = 34
-MAVLINK_MSG_ID_RC_CHANNELS_RAW = 35
-MAVLINK_MSG_ID_SERVO_OUTPUT_RAW = 36
-MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST = 37
-MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST = 38
-MAVLINK_MSG_ID_MISSION_ITEM = 39
-MAVLINK_MSG_ID_MISSION_REQUEST = 40
-MAVLINK_MSG_ID_MISSION_SET_CURRENT = 41
-MAVLINK_MSG_ID_MISSION_CURRENT = 42
-MAVLINK_MSG_ID_MISSION_REQUEST_LIST = 43
-MAVLINK_MSG_ID_MISSION_COUNT = 44
-MAVLINK_MSG_ID_MISSION_CLEAR_ALL = 45
-MAVLINK_MSG_ID_MISSION_ITEM_REACHED = 46
-MAVLINK_MSG_ID_MISSION_ACK = 47
-MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN = 48
-MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN = 49
-MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT = 50
-MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT = 51
-MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT = 52
-MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT = 53
-MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA = 54
-MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA = 55
-MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST = 56
-MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST = 57
-MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT = 58
-MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT = 59
-MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT = 62
-MAVLINK_MSG_ID_STATE_CORRECTION = 64
-MAVLINK_MSG_ID_REQUEST_DATA_STREAM = 66
-MAVLINK_MSG_ID_DATA_STREAM = 67
-MAVLINK_MSG_ID_MANUAL_CONTROL = 69
-MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE = 70
-MAVLINK_MSG_ID_VFR_HUD = 74
-MAVLINK_MSG_ID_COMMAND_LONG = 76
-MAVLINK_MSG_ID_COMMAND_ACK = 77
-MAVLINK_MSG_ID_HIL_STATE = 90
-MAVLINK_MSG_ID_HIL_CONTROLS = 91
-MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW = 92
-MAVLINK_MSG_ID_OPTICAL_FLOW = 100
-MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE = 101
-MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE = 102
-MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE = 103
-MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE = 104
-MAVLINK_MSG_ID_MEMORY_VECT = 249
-MAVLINK_MSG_ID_DEBUG_VECT = 250
-MAVLINK_MSG_ID_NAMED_VALUE_FLOAT = 251
-MAVLINK_MSG_ID_NAMED_VALUE_INT = 252
-MAVLINK_MSG_ID_STATUSTEXT = 253
-MAVLINK_MSG_ID_DEBUG = 254
-MAVLINK_MSG_ID_EXTENDED_MESSAGE = 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, 134, struct.pack('<fiiffffffhhh', 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, self.mag_ofs_x, self.mag_ofs_y, self.mag_ofs_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, 219, struct.pack('<hhhBB', self.mag_ofs_x, self.mag_ofs_y, self.mag_ofs_z, self.target_system, self.target_component))
-
-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, 84, struct.pack('<fHBBBBBBBBB', self.extra_value, self.shutter_speed, self.target_system, self.target_component, self.mode, self.aperture, self.iso, self.exposure_type, self.command_id, self.engine_cut_off, self.extra_param))
-
-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, 22, struct.pack('<fBBBBbBBBB', self.extra_value, 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))
-
-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, 21, struct.pack('<iiiBBB', self.input_a, self.input_b, self.input_c, self.target_system, self.target_component, 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, 134, struct.pack('<iiiBB', self.pointing_a, self.pointing_b, self.pointing_c, self.target_system, self.target_component))
-
-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, 78, struct.pack('<ffBBBB', self.lat, self.lng, self.target_system, self.target_component, self.idx, self.count))
-
-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, 189, struct.pack('<IHBB', self.breach_time, self.breach_count, self.breach_status, self.breach_type))
-
-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, 21, struct.pack('<HHBBBBB', self.rxerrors, self.fixed, self.rssi, self.remrssi, self.txbuf, self.noise, self.remnoise))
-
-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, base_mode, custom_mode, system_status, mavlink_version):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_HEARTBEAT, 'HEARTBEAT')
- self._fieldnames = ['type', 'autopilot', 'base_mode', 'custom_mode', 'system_status', 'mavlink_version']
- self.type = type
- self.autopilot = autopilot
- self.base_mode = base_mode
- self.custom_mode = custom_mode
- self.system_status = system_status
- self.mavlink_version = mavlink_version
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 50, struct.pack('<IBBBBB', self.custom_mode, self.type, self.autopilot, self.base_mode, self.system_status, self.mavlink_version))
-
-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, onboard_control_sensors_present, onboard_control_sensors_enabled, onboard_control_sensors_health, load, voltage_battery, current_battery, battery_remaining, drop_rate_comm, errors_comm, errors_count1, errors_count2, errors_count3, errors_count4):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_SYS_STATUS, 'SYS_STATUS')
- self._fieldnames = ['onboard_control_sensors_present', 'onboard_control_sensors_enabled', 'onboard_control_sensors_health', 'load', 'voltage_battery', 'current_battery', 'battery_remaining', 'drop_rate_comm', 'errors_comm', 'errors_count1', 'errors_count2', 'errors_count3', 'errors_count4']
- self.onboard_control_sensors_present = onboard_control_sensors_present
- self.onboard_control_sensors_enabled = onboard_control_sensors_enabled
- self.onboard_control_sensors_health = onboard_control_sensors_health
- self.load = load
- self.voltage_battery = voltage_battery
- self.current_battery = current_battery
- self.battery_remaining = battery_remaining
- self.drop_rate_comm = drop_rate_comm
- self.errors_comm = errors_comm
- self.errors_count1 = errors_count1
- self.errors_count2 = errors_count2
- self.errors_count3 = errors_count3
- self.errors_count4 = errors_count4
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 124, struct.pack('<IIIHHhHHHHHHb', self.onboard_control_sensors_present, self.onboard_control_sensors_enabled, self.onboard_control_sensors_health, self.load, self.voltage_battery, self.current_battery, self.drop_rate_comm, self.errors_comm, self.errors_count1, self.errors_count2, self.errors_count3, self.errors_count4, self.battery_remaining))
-
-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_unix_usec, time_boot_ms):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_SYSTEM_TIME, 'SYSTEM_TIME')
- self._fieldnames = ['time_unix_usec', 'time_boot_ms']
- self.time_unix_usec = time_unix_usec
- self.time_boot_ms = time_boot_ms
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 137, struct.pack('<QI', self.time_unix_usec, self.time_boot_ms))
-
-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, time_usec, seq, target_system, target_component):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_PING, 'PING')
- self._fieldnames = ['time_usec', 'seq', 'target_system', 'target_component']
- self.time_usec = time_usec
- self.seq = seq
- self.target_system = target_system
- self.target_component = target_component
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 237, struct.pack('<QIBB', self.time_usec, self.seq, self.target_system, self.target_component))
-
-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_set_mode_message(MAVLink_message):
- '''
- Set the system mode, as defined by enum MAV_MODE. 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_system, base_mode, custom_mode):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_SET_MODE, 'SET_MODE')
- self._fieldnames = ['target_system', 'base_mode', 'custom_mode']
- self.target_system = target_system
- self.base_mode = base_mode
- self.custom_mode = custom_mode
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 89, struct.pack('<IBB', self.custom_mode, self.target_system, self.base_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, 214, struct.pack('<hBB16s', self.param_index, self.target_system, self.target_component, self.param_id))
-
-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_type, param_count, param_index):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_PARAM_VALUE, 'PARAM_VALUE')
- self._fieldnames = ['param_id', 'param_value', 'param_type', 'param_count', 'param_index']
- self.param_id = param_id
- self.param_value = param_value
- self.param_type = param_type
- self.param_count = param_count
- self.param_index = param_index
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 220, struct.pack('<fHH16sB', self.param_value, self.param_count, self.param_index, self.param_id, self.param_type))
-
-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, param_type):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_PARAM_SET, 'PARAM_SET')
- self._fieldnames = ['target_system', 'target_component', 'param_id', 'param_value', 'param_type']
- self.target_system = target_system
- self.target_component = target_component
- self.param_id = param_id
- self.param_value = param_value
- self.param_type = param_type
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 168, struct.pack('<fBB16sB', self.param_value, self.target_system, self.target_component, self.param_id, self.param_type))
-
-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, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_GPS_RAW_INT, 'GPS_RAW_INT')
- self._fieldnames = ['time_usec', 'fix_type', 'lat', 'lon', 'alt', 'eph', 'epv', 'vel', 'cog', 'satellites_visible']
- self.time_usec = time_usec
- self.fix_type = fix_type
- self.lat = lat
- self.lon = lon
- self.alt = alt
- self.eph = eph
- self.epv = epv
- self.vel = vel
- self.cog = cog
- self.satellites_visible = satellites_visible
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 24, struct.pack('<QiiiHHHHBB', self.time_usec, self.lat, self.lon, self.alt, self.eph, self.epv, self.vel, self.cog, self.fix_type, self.satellites_visible))
-
-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, 23, struct.pack('<B20s20s20s20s20s', self.satellites_visible, self.satellite_prn, self.satellite_used, self.satellite_elevation, self.satellite_azimuth, self.satellite_snr))
-
-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, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_SCALED_IMU, 'SCALED_IMU')
- self._fieldnames = ['time_boot_ms', 'xacc', 'yacc', 'zacc', 'xgyro', 'ygyro', 'zgyro', 'xmag', 'ymag', 'zmag']
- self.time_boot_ms = time_boot_ms
- 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, 170, struct.pack('<Ihhhhhhhhh', self.time_boot_ms, self.xacc, self.yacc, self.zacc, self.xgyro, self.ygyro, self.zgyro, self.xmag, self.ymag, self.zmag))
-
-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, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_RAW_IMU, 'RAW_IMU')
- self._fieldnames = ['time_usec', 'xacc', 'yacc', 'zacc', 'xgyro', 'ygyro', 'zgyro', 'xmag', 'ymag', 'zmag']
- self.time_usec = time_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, 144, struct.pack('<Qhhhhhhhhh', self.time_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, time_usec, press_abs, press_diff1, press_diff2, temperature):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_RAW_PRESSURE, 'RAW_PRESSURE')
- self._fieldnames = ['time_usec', 'press_abs', 'press_diff1', 'press_diff2', 'temperature']
- self.time_usec = time_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, 67, struct.pack('<Qhhhh', self.time_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, time_boot_ms, press_abs, press_diff, temperature):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_SCALED_PRESSURE, 'SCALED_PRESSURE')
- self._fieldnames = ['time_boot_ms', 'press_abs', 'press_diff', 'temperature']
- self.time_boot_ms = time_boot_ms
- self.press_abs = press_abs
- self.press_diff = press_diff
- self.temperature = temperature
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 115, struct.pack('<Iffh', self.time_boot_ms, 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, time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_ATTITUDE, 'ATTITUDE')
- self._fieldnames = ['time_boot_ms', 'roll', 'pitch', 'yaw', 'rollspeed', 'pitchspeed', 'yawspeed']
- self.time_boot_ms = time_boot_ms
- 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, 39, struct.pack('<Iffffff', self.time_boot_ms, self.roll, self.pitch, self.yaw, self.rollspeed, self.pitchspeed, self.yawspeed))
-
-class MAVLink_attitude_quaternion_message(MAVLink_message):
- '''
- The attitude in the aeronautical frame (right-handed, Z-down,
- X-front, Y-right), expressed as quaternion.
- '''
- def __init__(self, time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, 'ATTITUDE_QUATERNION')
- self._fieldnames = ['time_boot_ms', 'q1', 'q2', 'q3', 'q4', 'rollspeed', 'pitchspeed', 'yawspeed']
- self.time_boot_ms = time_boot_ms
- self.q1 = q1
- self.q2 = q2
- self.q3 = q3
- self.q4 = q4
- self.rollspeed = rollspeed
- self.pitchspeed = pitchspeed
- self.yawspeed = yawspeed
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 246, struct.pack('<Ifffffff', self.time_boot_ms, self.q1, self.q2, self.q3, self.q4, self.rollspeed, self.pitchspeed, self.yawspeed))
-
-class MAVLink_local_position_ned_message(MAVLink_message):
- '''
- The filtered local position (e.g. fused computer vision and
- accelerometers). Coordinate frame is right-handed, Z-axis down
- (aeronautical frame, NED / north-east-down convention)
- '''
- def __init__(self, time_boot_ms, x, y, z, vx, vy, vz):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_LOCAL_POSITION_NED, 'LOCAL_POSITION_NED')
- self._fieldnames = ['time_boot_ms', 'x', 'y', 'z', 'vx', 'vy', 'vz']
- self.time_boot_ms = time_boot_ms
- 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, 185, struct.pack('<Iffffff', self.time_boot_ms, self.x, self.y, self.z, self.vx, self.vy, self.vz))
-
-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). It is designed as scaled integer message
- since the resolution of float is not sufficient.
- '''
- def __init__(self, time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, 'GLOBAL_POSITION_INT')
- self._fieldnames = ['time_boot_ms', 'lat', 'lon', 'alt', 'relative_alt', 'vx', 'vy', 'vz', 'hdg']
- self.time_boot_ms = time_boot_ms
- self.lat = lat
- self.lon = lon
- self.alt = alt
- self.relative_alt = relative_alt
- self.vx = vx
- self.vy = vy
- self.vz = vz
- self.hdg = hdg
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 104, struct.pack('<IiiiihhhH', self.time_boot_ms, self.lat, self.lon, self.alt, self.relative_alt, self.vx, self.vy, self.vz, self.hdg))
-
-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, time_boot_ms, port, 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 = ['time_boot_ms', 'port', 'chan1_scaled', 'chan2_scaled', 'chan3_scaled', 'chan4_scaled', 'chan5_scaled', 'chan6_scaled', 'chan7_scaled', 'chan8_scaled', 'rssi']
- self.time_boot_ms = time_boot_ms
- self.port = port
- 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, 237, struct.pack('<IhhhhhhhhBB', self.time_boot_ms, 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.port, self.rssi))
-
-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, time_boot_ms, port, 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 = ['time_boot_ms', 'port', 'chan1_raw', 'chan2_raw', 'chan3_raw', 'chan4_raw', 'chan5_raw', 'chan6_raw', 'chan7_raw', 'chan8_raw', 'rssi']
- self.time_boot_ms = time_boot_ms
- self.port = port
- 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, 244, struct.pack('<IHHHHHHHHBB', self.time_boot_ms, 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.port, 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, time_usec, port, 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 = ['time_usec', 'port', 'servo1_raw', 'servo2_raw', 'servo3_raw', 'servo4_raw', 'servo5_raw', 'servo6_raw', 'servo7_raw', 'servo8_raw']
- self.time_usec = time_usec
- self.port = port
- 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, 222, struct.pack('<IHHHHHHHHB', self.time_usec, self.servo1_raw, self.servo2_raw, self.servo3_raw, self.servo4_raw, self.servo5_raw, self.servo6_raw, self.servo7_raw, self.servo8_raw, self.port))
-
-class MAVLink_mission_request_partial_list_message(MAVLink_message):
- '''
- Request the overall list of MISSIONs from the
- system/component.
- http://qgroundcontrol.org/mavlink/waypoint_protocol
- '''
- def __init__(self, target_system, target_component, start_index, end_index):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, 'MISSION_REQUEST_PARTIAL_LIST')
- self._fieldnames = ['target_system', 'target_component', 'start_index', 'end_index']
- self.target_system = target_system
- self.target_component = target_component
- self.start_index = start_index
- self.end_index = end_index
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 212, struct.pack('<hhBB', self.start_index, self.end_index, self.target_system, self.target_component))
-
-class MAVLink_mission_write_partial_list_message(MAVLink_message):
- '''
- This message is sent to the MAV to write a partial list. If
- start index == end index, only one item will be transmitted /
- updated. If the start index is NOT 0 and above the current
- list size, this request should be REJECTED!
- '''
- def __init__(self, target_system, target_component, start_index, end_index):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, 'MISSION_WRITE_PARTIAL_LIST')
- self._fieldnames = ['target_system', 'target_component', 'start_index', 'end_index']
- self.target_system = target_system
- self.target_component = target_component
- self.start_index = start_index
- self.end_index = end_index
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 9, struct.pack('<hhBB', self.start_index, self.end_index, self.target_system, self.target_component))
-
-class MAVLink_mission_item_message(MAVLink_message):
- '''
- Message encoding a mission item. This message is emitted to
- announce the presence of a mission item and to
- set a mission item on the system. The mission item can be
- either in x, y, z meters (type: LOCAL) or x:lat, y:lon,
- z:altitude. Local frame is Z-down, right handed (NED), global
- frame is Z-up, right handed (ENU).
- http://qgroundcontrol.org/mavlink/waypoint_protocol
- '''
- 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_MISSION_ITEM, 'MISSION_ITEM')
- 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, 254, struct.pack('<fffffffHHBBBBB', self.param1, self.param2, self.param3, self.param4, self.x, self.y, self.z, self.seq, self.command, self.target_system, self.target_component, self.frame, self.current, self.autocontinue))
-
-class MAVLink_mission_request_message(MAVLink_message):
- '''
- Request the information of the mission item with the sequence
- number seq. The response of the system to this message should
- be a MISSION_ITEM message.
- http://qgroundcontrol.org/mavlink/waypoint_protocol
- '''
- def __init__(self, target_system, target_component, seq):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_MISSION_REQUEST, 'MISSION_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, 230, struct.pack('<HBB', self.seq, self.target_system, self.target_component))
-
-class MAVLink_mission_set_current_message(MAVLink_message):
- '''
- Set the mission item with sequence number seq as current item.
- This means that the MAV will continue to this mission item on
- the shortest path (not following the mission items in-
- between).
- '''
- def __init__(self, target_system, target_component, seq):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_MISSION_SET_CURRENT, 'MISSION_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, 28, struct.pack('<HBB', self.seq, self.target_system, self.target_component))
-
-class MAVLink_mission_current_message(MAVLink_message):
- '''
- Message that announces the sequence number of the current
- active mission item. The MAV will fly towards this mission
- item.
- '''
- def __init__(self, seq):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_MISSION_CURRENT, 'MISSION_CURRENT')
- self._fieldnames = ['seq']
- self.seq = seq
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 28, struct.pack('<H', self.seq))
-
-class MAVLink_mission_request_list_message(MAVLink_message):
- '''
- Request the overall list of mission items from the
- system/component.
- '''
- def __init__(self, target_system, target_component):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, 'MISSION_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, 132, struct.pack('<BB', self.target_system, self.target_component))
-
-class MAVLink_mission_count_message(MAVLink_message):
- '''
- This message is emitted as response to MISSION_REQUEST_LIST by
- the MAV and to initiate a write transaction. The GCS can then
- request the individual mission item based on the knowledge of
- the total number of MISSIONs.
- '''
- def __init__(self, target_system, target_component, count):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_MISSION_COUNT, 'MISSION_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, 221, struct.pack('<HBB', self.count, self.target_system, self.target_component))
-
-class MAVLink_mission_clear_all_message(MAVLink_message):
- '''
- Delete all mission items at once.
- '''
- def __init__(self, target_system, target_component):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, 'MISSION_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, 232, struct.pack('<BB', self.target_system, self.target_component))
-
-class MAVLink_mission_item_reached_message(MAVLink_message):
- '''
- A certain mission item 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 MISSION.
- '''
- def __init__(self, seq):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, 'MISSION_ITEM_REACHED')
- self._fieldnames = ['seq']
- self.seq = seq
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 11, struct.pack('<H', self.seq))
-
-class MAVLink_mission_ack_message(MAVLink_message):
- '''
- Ack message during MISSION 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_MISSION_ACK, 'MISSION_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, 153, struct.pack('<BBB', self.target_system, self.target_component, self.type))
-
-class MAVLink_set_gps_global_origin_message(MAVLink_message):
- '''
- As local MISSIONs exist, the global MISSION 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, latitude, longitude, altitude):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, 'SET_GPS_GLOBAL_ORIGIN')
- self._fieldnames = ['target_system', 'latitude', 'longitude', 'altitude']
- self.target_system = target_system
- self.latitude = latitude
- self.longitude = longitude
- self.altitude = altitude
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 41, struct.pack('<iiiB', self.latitude, self.longitude, self.altitude, self.target_system))
-
-class MAVLink_gps_global_origin_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_GLOBAL_ORIGIN, 'GPS_GLOBAL_ORIGIN')
- self._fieldnames = ['latitude', 'longitude', 'altitude']
- self.latitude = latitude
- self.longitude = longitude
- self.altitude = altitude
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 39, struct.pack('<iii', self.latitude, self.longitude, self.altitude))
-
-class MAVLink_set_local_position_setpoint_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/MISSION 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, coordinate_frame, x, y, z, yaw):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT, 'SET_LOCAL_POSITION_SETPOINT')
- self._fieldnames = ['target_system', 'target_component', 'coordinate_frame', 'x', 'y', 'z', 'yaw']
- self.target_system = target_system
- self.target_component = target_component
- self.coordinate_frame = coordinate_frame
- self.x = x
- self.y = y
- self.z = z
- self.yaw = yaw
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 214, struct.pack('<ffffBBB', self.x, self.y, self.z, self.yaw, self.target_system, self.target_component, self.coordinate_frame))
-
-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, coordinate_frame, x, y, z, yaw):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, 'LOCAL_POSITION_SETPOINT')
- self._fieldnames = ['coordinate_frame', 'x', 'y', 'z', 'yaw']
- self.coordinate_frame = coordinate_frame
- self.x = x
- self.y = y
- self.z = z
- self.yaw = yaw
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 223, struct.pack('<ffffB', self.x, self.y, self.z, self.yaw, self.coordinate_frame))
-
-class MAVLink_global_position_setpoint_int_message(MAVLink_message):
- '''
- Transmit the current local setpoint of the controller to other
- MAVs (collision avoidance) and to the GCS.
- '''
- def __init__(self, coordinate_frame, latitude, longitude, altitude, yaw):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, 'GLOBAL_POSITION_SETPOINT_INT')
- self._fieldnames = ['coordinate_frame', 'latitude', 'longitude', 'altitude', 'yaw']
- self.coordinate_frame = coordinate_frame
- self.latitude = latitude
- self.longitude = longitude
- self.altitude = altitude
- self.yaw = yaw
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 141, struct.pack('<iiihB', self.latitude, self.longitude, self.altitude, self.yaw, self.coordinate_frame))
-
-class MAVLink_set_global_position_setpoint_int_message(MAVLink_message):
- '''
- Set the current global position setpoint.
- '''
- def __init__(self, coordinate_frame, latitude, longitude, altitude, yaw):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT, 'SET_GLOBAL_POSITION_SETPOINT_INT')
- self._fieldnames = ['coordinate_frame', 'latitude', 'longitude', 'altitude', 'yaw']
- self.coordinate_frame = coordinate_frame
- self.latitude = latitude
- self.longitude = longitude
- self.altitude = altitude
- self.yaw = yaw
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 33, struct.pack('<iiihB', self.latitude, self.longitude, self.altitude, self.yaw, self.coordinate_frame))
-
-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/MISSIONs 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, 15, struct.pack('<ffffffBBB', self.p1x, self.p1y, self.p1z, self.p2x, self.p2y, self.p2z, self.target_system, self.target_component, self.frame))
-
-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, 3, struct.pack('<ffffffB', self.p1x, self.p1y, self.p1z, self.p2x, self.p2y, self.p2z, self.frame))
-
-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, 100, struct.pack('<ffffBB', self.roll, self.pitch, self.yaw, self.thrust, self.target_system, self.target_component))
-
-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, 24, struct.pack('<ffffBB', self.roll_speed, self.pitch_speed, self.yaw_speed, self.thrust, self.target_system, self.target_component))
-
-class MAVLink_roll_pitch_yaw_thrust_setpoint_message(MAVLink_message):
- '''
- Setpoint in roll, pitch, yaw currently active on the system.
- '''
- def __init__(self, time_boot_ms, roll, pitch, yaw, thrust):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, 'ROLL_PITCH_YAW_THRUST_SETPOINT')
- self._fieldnames = ['time_boot_ms', 'roll', 'pitch', 'yaw', 'thrust']
- self.time_boot_ms = time_boot_ms
- self.roll = roll
- self.pitch = pitch
- self.yaw = yaw
- self.thrust = thrust
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 239, struct.pack('<Iffff', self.time_boot_ms, 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_boot_ms, 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_boot_ms', 'roll_speed', 'pitch_speed', 'yaw_speed', 'thrust']
- self.time_boot_ms = time_boot_ms
- 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, 238, struct.pack('<Iffff', self.time_boot_ms, 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, 183, struct.pack('<fffffhhH', self.nav_roll, self.nav_pitch, self.alt_error, self.aspd_error, self.xtrack_error, self.nav_bearing, self.target_bearing, self.wp_dist))
-
-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_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, 148, struct.pack('<HBBBB', self.req_message_rate, self.target_system, self.target_component, self.req_stream_id, self.start_stop))
-
-class MAVLink_data_stream_message(MAVLink_message):
- '''
-
- '''
- def __init__(self, stream_id, message_rate, on_off):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_DATA_STREAM, 'DATA_STREAM')
- self._fieldnames = ['stream_id', 'message_rate', 'on_off']
- self.stream_id = stream_id
- self.message_rate = message_rate
- self.on_off = on_off
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 21, struct.pack('<HBB', self.message_rate, self.stream_id, self.on_off))
-
-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, 52, struct.pack('<ffffBBBBB', self.roll, self.pitch, self.yaw, self.thrust, self.target, 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, 124, struct.pack('<HHHHHHHHBB', 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.target_system, self.target_component))
-
-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, 20, struct.pack('<ffffhH', self.airspeed, self.groundspeed, self.alt, self.climb, self.heading, self.throttle))
-
-class MAVLink_command_long_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, param5, param6, param7):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_COMMAND_LONG, 'COMMAND_LONG')
- self._fieldnames = ['target_system', 'target_component', 'command', 'confirmation', 'param1', 'param2', 'param3', 'param4', 'param5', 'param6', 'param7']
- 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
- self.param5 = param5
- self.param6 = param6
- self.param7 = param7
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 152, struct.pack('<fffffffHBBB', self.param1, self.param2, self.param3, self.param4, self.param5, self.param6, self.param7, self.command, self.target_system, self.target_component, self.confirmation))
-
-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, 143, struct.pack('<HB', self.command, self.result))
-
-class MAVLink_hil_state_message(MAVLink_message):
- '''
- Sent from simulation to autopilot. This packet is useful for
- high throughput applications such as hardware
- in the loop simulations.
- '''
- def __init__(self, time_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 = ['time_usec', 'roll', 'pitch', 'yaw', 'rollspeed', 'pitchspeed', 'yawspeed', 'lat', 'lon', 'alt', 'vx', 'vy', 'vz', 'xacc', 'yacc', 'zacc']
- self.time_usec = time_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, 183, struct.pack('<Qffffffiiihhhhhh', self.time_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):
- '''
- Sent from autopilot to simulation. Hardware in the loop
- control outputs
- '''
- def __init__(self, time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_HIL_CONTROLS, 'HIL_CONTROLS')
- self._fieldnames = ['time_usec', 'roll_ailerons', 'pitch_elevator', 'yaw_rudder', 'throttle', 'aux1', 'aux2', 'aux3', 'aux4', 'mode', 'nav_mode']
- self.time_usec = time_usec
- self.roll_ailerons = roll_ailerons
- self.pitch_elevator = pitch_elevator
- self.yaw_rudder = yaw_rudder
- self.throttle = throttle
- self.aux1 = aux1
- self.aux2 = aux2
- self.aux3 = aux3
- self.aux4 = aux4
- self.mode = mode
- self.nav_mode = nav_mode
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 63, struct.pack('<QffffffffBB', self.time_usec, self.roll_ailerons, self.pitch_elevator, self.yaw_rudder, self.throttle, self.aux1, self.aux2, self.aux3, self.aux4, self.mode, self.nav_mode))
-
-class MAVLink_hil_rc_inputs_raw_message(MAVLink_message):
- '''
- Sent from simulation to autopilot. 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, time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, 'HIL_RC_INPUTS_RAW')
- self._fieldnames = ['time_usec', 'chan1_raw', 'chan2_raw', 'chan3_raw', 'chan4_raw', 'chan5_raw', 'chan6_raw', 'chan7_raw', 'chan8_raw', 'chan9_raw', 'chan10_raw', 'chan11_raw', 'chan12_raw', 'rssi']
- self.time_usec = time_usec
- 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.chan9_raw = chan9_raw
- self.chan10_raw = chan10_raw
- self.chan11_raw = chan11_raw
- self.chan12_raw = chan12_raw
- self.rssi = rssi
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 54, struct.pack('<QHHHHHHHHHHHHB', self.time_usec, 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.chan9_raw, self.chan10_raw, self.chan11_raw, self.chan12_raw, self.rssi))
-
-class MAVLink_optical_flow_message(MAVLink_message):
- '''
- Optical flow from a flow sensor (e.g. optical mouse sensor)
- '''
- def __init__(self, time_usec, sensor_id, flow_x, flow_y, quality, ground_distance):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_OPTICAL_FLOW, 'OPTICAL_FLOW')
- self._fieldnames = ['time_usec', 'sensor_id', 'flow_x', 'flow_y', 'quality', 'ground_distance']
- self.time_usec = time_usec
- 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, 19, struct.pack('<QfhhBB', self.time_usec, self.ground_distance, self.flow_x, self.flow_y, self.sensor_id, self.quality))
-
-class MAVLink_global_vision_position_estimate_message(MAVLink_message):
- '''
-
- '''
- def __init__(self, usec, x, y, z, roll, pitch, yaw):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, 'GLOBAL_VISION_POSITION_ESTIMATE')
- self._fieldnames = ['usec', 'x', 'y', 'z', 'roll', 'pitch', 'yaw']
- self.usec = usec
- self.x = x
- self.y = y
- self.z = z
- self.roll = roll
- self.pitch = pitch
- self.yaw = yaw
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 102, struct.pack('<Qffffff', self.usec, self.x, self.y, self.z, self.roll, self.pitch, self.yaw))
-
-class MAVLink_vision_position_estimate_message(MAVLink_message):
- '''
-
- '''
- def __init__(self, usec, x, y, z, roll, pitch, yaw):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, 'VISION_POSITION_ESTIMATE')
- self._fieldnames = ['usec', 'x', 'y', 'z', 'roll', 'pitch', 'yaw']
- self.usec = usec
- self.x = x
- self.y = y
- self.z = z
- self.roll = roll
- self.pitch = pitch
- self.yaw = yaw
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 158, struct.pack('<Qffffff', self.usec, self.x, self.y, self.z, self.roll, self.pitch, self.yaw))
-
-class MAVLink_vision_speed_estimate_message(MAVLink_message):
- '''
-
- '''
- def __init__(self, usec, x, y, z):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, 'VISION_SPEED_ESTIMATE')
- self._fieldnames = ['usec', 'x', 'y', 'z']
- self.usec = usec
- self.x = x
- self.y = y
- self.z = z
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 208, struct.pack('<Qfff', self.usec, self.x, self.y, self.z))
-
-class MAVLink_vicon_position_estimate_message(MAVLink_message):
- '''
-
- '''
- def __init__(self, usec, x, y, z, roll, pitch, yaw):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, 'VICON_POSITION_ESTIMATE')
- self._fieldnames = ['usec', 'x', 'y', 'z', 'roll', 'pitch', 'yaw']
- self.usec = usec
- self.x = x
- self.y = y
- self.z = z
- self.roll = roll
- self.pitch = pitch
- self.yaw = yaw
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 56, struct.pack('<Qffffff', self.usec, self.x, self.y, self.z, self.roll, self.pitch, self.yaw))
-
-class MAVLink_memory_vect_message(MAVLink_message):
- '''
- Send raw controller memory. 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, address, ver, type, value):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_MEMORY_VECT, 'MEMORY_VECT')
- self._fieldnames = ['address', 'ver', 'type', 'value']
- self.address = address
- self.ver = ver
- self.type = type
- self.value = value
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 204, struct.pack('<HBB32s', self.address, self.ver, self.type, self.value))
-
-class MAVLink_debug_vect_message(MAVLink_message):
- '''
-
- '''
- def __init__(self, name, time_usec, x, y, z):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_DEBUG_VECT, 'DEBUG_VECT')
- self._fieldnames = ['name', 'time_usec', 'x', 'y', 'z']
- self.name = name
- self.time_usec = time_usec
- self.x = x
- self.y = y
- self.z = z
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 49, struct.pack('<Qfff10s', self.time_usec, self.x, self.y, self.z, self.name))
-
-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, time_boot_ms, name, value):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, 'NAMED_VALUE_FLOAT')
- self._fieldnames = ['time_boot_ms', 'name', 'value']
- self.time_boot_ms = time_boot_ms
- self.name = name
- self.value = value
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 170, struct.pack('<If10s', self.time_boot_ms, self.value, self.name))
-
-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, time_boot_ms, name, value):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_NAMED_VALUE_INT, 'NAMED_VALUE_INT')
- self._fieldnames = ['time_boot_ms', 'name', 'value']
- self.time_boot_ms = time_boot_ms
- self.name = name
- self.value = value
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 44, struct.pack('<Ii10s', self.time_boot_ms, self.value, self.name))
-
-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, 83, 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, time_boot_ms, ind, value):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_DEBUG, 'DEBUG')
- self._fieldnames = ['time_boot_ms', 'ind', 'value']
- self.time_boot_ms = time_boot_ms
- self.ind = ind
- self.value = value
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 46, struct.pack('<IfB', self.time_boot_ms, self.value, self.ind))
-
-class MAVLink_extended_message_message(MAVLink_message):
- '''
- Extended message spacer.
- '''
- def __init__(self, target_system, target_component, protocol_flags):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_EXTENDED_MESSAGE, 'EXTENDED_MESSAGE')
- self._fieldnames = ['target_system', 'target_component', 'protocol_flags']
- self.target_system = target_system
- self.target_component = target_component
- self.protocol_flags = protocol_flags
-
- def pack(self, mav):
- return MAVLink_message.pack(self, mav, 247, struct.pack('<BBB', self.target_system, self.target_component, self.protocol_flags))
-
-
-mavlink_map = {
- MAVLINK_MSG_ID_SENSOR_OFFSETS : ( '<fiiffffffhhh', MAVLink_sensor_offsets_message, [9, 10, 11, 0, 1, 2, 3, 4, 5, 6, 7, 8], 134 ),
- MAVLINK_MSG_ID_SET_MAG_OFFSETS : ( '<hhhBB', MAVLink_set_mag_offsets_message, [3, 4, 0, 1, 2], 219 ),
- 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 : ( '<fHBBBBBBBBB', MAVLink_digicam_configure_message, [2, 3, 4, 1, 5, 6, 7, 8, 9, 10, 0], 84 ),
- MAVLINK_MSG_ID_DIGICAM_CONTROL : ( '<fBBBBbBBBB', MAVLink_digicam_control_message, [1, 2, 3, 4, 5, 6, 7, 8, 9, 0], 22 ),
- MAVLINK_MSG_ID_MOUNT_CONFIGURE : ( '<BBBBBB', MAVLink_mount_configure_message, [0, 1, 2, 3, 4, 5], 19 ),
- MAVLINK_MSG_ID_MOUNT_CONTROL : ( '<iiiBBB', MAVLink_mount_control_message, [3, 4, 0, 1, 2, 5], 21 ),
- MAVLINK_MSG_ID_MOUNT_STATUS : ( '<iiiBB', MAVLink_mount_status_message, [3, 4, 0, 1, 2], 134 ),
- MAVLINK_MSG_ID_FENCE_POINT : ( '<ffBBBB', MAVLink_fence_point_message, [2, 3, 4, 5, 0, 1], 78 ),
- MAVLINK_MSG_ID_FENCE_FETCH_POINT : ( '<BBB', MAVLink_fence_fetch_point_message, [0, 1, 2], 68 ),
- MAVLINK_MSG_ID_FENCE_STATUS : ( '<IHBB', MAVLink_fence_status_message, [2, 1, 3, 0], 189 ),
- 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 : ( '<HHBBBBB', MAVLink_radio_message, [2, 3, 4, 5, 6, 0, 1], 21 ),
- MAVLINK_MSG_ID_HEARTBEAT : ( '<IBBBBB', MAVLink_heartbeat_message, [1, 2, 3, 0, 4, 5], 50 ),
- MAVLINK_MSG_ID_SYS_STATUS : ( '<IIIHHhHHHHHHb', MAVLink_sys_status_message, [0, 1, 2, 3, 4, 5, 12, 6, 7, 8, 9, 10, 11], 124 ),
- MAVLINK_MSG_ID_SYSTEM_TIME : ( '<QI', MAVLink_system_time_message, [0, 1], 137 ),
- MAVLINK_MSG_ID_PING : ( '<QIBB', MAVLink_ping_message, [0, 1, 2, 3], 237 ),
- 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_SET_MODE : ( '<IBB', MAVLink_set_mode_message, [1, 2, 0], 89 ),
- MAVLINK_MSG_ID_PARAM_REQUEST_READ : ( '<hBB16s', MAVLink_param_request_read_message, [1, 2, 3, 0], 214 ),
- MAVLINK_MSG_ID_PARAM_REQUEST_LIST : ( '<BB', MAVLink_param_request_list_message, [0, 1], 159 ),
- MAVLINK_MSG_ID_PARAM_VALUE : ( '<fHH16sB', MAVLink_param_value_message, [3, 0, 4, 1, 2], 220 ),
- MAVLINK_MSG_ID_PARAM_SET : ( '<fBB16sB', MAVLink_param_set_message, [1, 2, 3, 0, 4], 168 ),
- MAVLINK_MSG_ID_GPS_RAW_INT : ( '<QiiiHHHHBB', MAVLink_gps_raw_int_message, [0, 8, 1, 2, 3, 4, 5, 6, 7, 9], 24 ),
- MAVLINK_MSG_ID_GPS_STATUS : ( '<B20s20s20s20s20s', MAVLink_gps_status_message, [0, 1, 2, 3, 4, 5], 23 ),
- MAVLINK_MSG_ID_SCALED_IMU : ( '<Ihhhhhhhhh', MAVLink_scaled_imu_message, [0, 1, 2, 3, 4, 5, 6, 7, 8, 9], 170 ),
- MAVLINK_MSG_ID_RAW_IMU : ( '<Qhhhhhhhhh', MAVLink_raw_imu_message, [0, 1, 2, 3, 4, 5, 6, 7, 8, 9], 144 ),
- MAVLINK_MSG_ID_RAW_PRESSURE : ( '<Qhhhh', MAVLink_raw_pressure_message, [0, 1, 2, 3, 4], 67 ),
- MAVLINK_MSG_ID_SCALED_PRESSURE : ( '<Iffh', MAVLink_scaled_pressure_message, [0, 1, 2, 3], 115 ),
- MAVLINK_MSG_ID_ATTITUDE : ( '<Iffffff', MAVLink_attitude_message, [0, 1, 2, 3, 4, 5, 6], 39 ),
- MAVLINK_MSG_ID_ATTITUDE_QUATERNION : ( '<Ifffffff', MAVLink_attitude_quaternion_message, [0, 1, 2, 3, 4, 5, 6, 7], 246 ),
- MAVLINK_MSG_ID_LOCAL_POSITION_NED : ( '<Iffffff', MAVLink_local_position_ned_message, [0, 1, 2, 3, 4, 5, 6], 185 ),
- MAVLINK_MSG_ID_GLOBAL_POSITION_INT : ( '<IiiiihhhH', MAVLink_global_position_int_message, [0, 1, 2, 3, 4, 5, 6, 7, 8], 104 ),
- MAVLINK_MSG_ID_RC_CHANNELS_SCALED : ( '<IhhhhhhhhBB', MAVLink_rc_channels_scaled_message, [0, 9, 1, 2, 3, 4, 5, 6, 7, 8, 10], 237 ),
- MAVLINK_MSG_ID_RC_CHANNELS_RAW : ( '<IHHHHHHHHBB', MAVLink_rc_channels_raw_message, [0, 9, 1, 2, 3, 4, 5, 6, 7, 8, 10], 244 ),
- MAVLINK_MSG_ID_SERVO_OUTPUT_RAW : ( '<IHHHHHHHHB', MAVLink_servo_output_raw_message, [0, 9, 1, 2, 3, 4, 5, 6, 7, 8], 222 ),
- MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST : ( '<hhBB', MAVLink_mission_request_partial_list_message, [2, 3, 0, 1], 212 ),
- MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST : ( '<hhBB', MAVLink_mission_write_partial_list_message, [2, 3, 0, 1], 9 ),
- MAVLINK_MSG_ID_MISSION_ITEM : ( '<fffffffHHBBBBB', MAVLink_mission_item_message, [9, 10, 7, 11, 8, 12, 13, 0, 1, 2, 3, 4, 5, 6], 254 ),
- MAVLINK_MSG_ID_MISSION_REQUEST : ( '<HBB', MAVLink_mission_request_message, [1, 2, 0], 230 ),
- MAVLINK_MSG_ID_MISSION_SET_CURRENT : ( '<HBB', MAVLink_mission_set_current_message, [1, 2, 0], 28 ),
- MAVLINK_MSG_ID_MISSION_CURRENT : ( '<H', MAVLink_mission_current_message, [0], 28 ),
- MAVLINK_MSG_ID_MISSION_REQUEST_LIST : ( '<BB', MAVLink_mission_request_list_message, [0, 1], 132 ),
- MAVLINK_MSG_ID_MISSION_COUNT : ( '<HBB', MAVLink_mission_count_message, [1, 2, 0], 221 ),
- MAVLINK_MSG_ID_MISSION_CLEAR_ALL : ( '<BB', MAVLink_mission_clear_all_message, [0, 1], 232 ),
- MAVLINK_MSG_ID_MISSION_ITEM_REACHED : ( '<H', MAVLink_mission_item_reached_message, [0], 11 ),
- MAVLINK_MSG_ID_MISSION_ACK : ( '<BBB', MAVLink_mission_ack_message, [0, 1, 2], 153 ),
- MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN : ( '<iiiB', MAVLink_set_gps_global_origin_message, [3, 0, 1, 2], 41 ),
- MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN : ( '<iii', MAVLink_gps_global_origin_message, [0, 1, 2], 39 ),
- MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT : ( '<ffffBBB', MAVLink_set_local_position_setpoint_message, [4, 5, 6, 0, 1, 2, 3], 214 ),
- MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT : ( '<ffffB', MAVLink_local_position_setpoint_message, [4, 0, 1, 2, 3], 223 ),
- MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT : ( '<iiihB', MAVLink_global_position_setpoint_int_message, [4, 0, 1, 2, 3], 141 ),
- MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT : ( '<iiihB', MAVLink_set_global_position_setpoint_int_message, [4, 0, 1, 2, 3], 33 ),
- MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA : ( '<ffffffBBB', MAVLink_safety_set_allowed_area_message, [6, 7, 8, 0, 1, 2, 3, 4, 5], 15 ),
- MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA : ( '<ffffffB', MAVLink_safety_allowed_area_message, [6, 0, 1, 2, 3, 4, 5], 3 ),
- MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST : ( '<ffffBB', MAVLink_set_roll_pitch_yaw_thrust_message, [4, 5, 0, 1, 2, 3], 100 ),
- MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST : ( '<ffffBB', MAVLink_set_roll_pitch_yaw_speed_thrust_message, [4, 5, 0, 1, 2, 3], 24 ),
- MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT : ( '<Iffff', MAVLink_roll_pitch_yaw_thrust_setpoint_message, [0, 1, 2, 3, 4], 239 ),
- MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT : ( '<Iffff', MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message, [0, 1, 2, 3, 4], 238 ),
- MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT : ( '<fffffhhH', MAVLink_nav_controller_output_message, [0, 1, 5, 6, 7, 2, 3, 4], 183 ),
- MAVLINK_MSG_ID_STATE_CORRECTION : ( '<fffffffff', MAVLink_state_correction_message, [0, 1, 2, 3, 4, 5, 6, 7, 8], 130 ),
- MAVLINK_MSG_ID_REQUEST_DATA_STREAM : ( '<HBBBB', MAVLink_request_data_stream_message, [1, 2, 3, 0, 4], 148 ),
- MAVLINK_MSG_ID_DATA_STREAM : ( '<HBB', MAVLink_data_stream_message, [1, 0, 2], 21 ),
- MAVLINK_MSG_ID_MANUAL_CONTROL : ( '<ffffBBBBB', MAVLink_manual_control_message, [4, 0, 1, 2, 3, 5, 6, 7, 8], 52 ),
- MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE : ( '<HHHHHHHHBB', MAVLink_rc_channels_override_message, [8, 9, 0, 1, 2, 3, 4, 5, 6, 7], 124 ),
- MAVLINK_MSG_ID_VFR_HUD : ( '<ffffhH', MAVLink_vfr_hud_message, [0, 1, 4, 5, 2, 3], 20 ),
- MAVLINK_MSG_ID_COMMAND_LONG : ( '<fffffffHBBB', MAVLink_command_long_message, [8, 9, 7, 10, 0, 1, 2, 3, 4, 5, 6], 152 ),
- MAVLINK_MSG_ID_COMMAND_ACK : ( '<HB', MAVLink_command_ack_message, [0, 1], 143 ),
- 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], 183 ),
- MAVLINK_MSG_ID_HIL_CONTROLS : ( '<QffffffffBB', MAVLink_hil_controls_message, [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10], 63 ),
- MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW : ( '<QHHHHHHHHHHHHB', MAVLink_hil_rc_inputs_raw_message, [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13], 54 ),
- MAVLINK_MSG_ID_OPTICAL_FLOW : ( '<QfhhBB', MAVLink_optical_flow_message, [0, 4, 2, 3, 5, 1], 19 ),
- MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE : ( '<Qffffff', MAVLink_global_vision_position_estimate_message, [0, 1, 2, 3, 4, 5, 6], 102 ),
- MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE : ( '<Qffffff', MAVLink_vision_position_estimate_message, [0, 1, 2, 3, 4, 5, 6], 158 ),
- MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE : ( '<Qfff', MAVLink_vision_speed_estimate_message, [0, 1, 2, 3], 208 ),
- MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE : ( '<Qffffff', MAVLink_vicon_position_estimate_message, [0, 1, 2, 3, 4, 5, 6], 56 ),
- MAVLINK_MSG_ID_MEMORY_VECT : ( '<HBB32s', MAVLink_memory_vect_message, [0, 1, 2, 3], 204 ),
- MAVLINK_MSG_ID_DEBUG_VECT : ( '<Qfff10s', MAVLink_debug_vect_message, [4, 0, 1, 2, 3], 49 ),
- MAVLINK_MSG_ID_NAMED_VALUE_FLOAT : ( '<If10s', MAVLink_named_value_float_message, [0, 2, 1], 170 ),
- MAVLINK_MSG_ID_NAMED_VALUE_INT : ( '<Ii10s', MAVLink_named_value_int_message, [0, 2, 1], 44 ),
- MAVLINK_MSG_ID_STATUSTEXT : ( '<B50s', MAVLink_statustext_message, [0, 1], 83 ),
- MAVLINK_MSG_ID_DEBUG : ( '<IfB', MAVLink_debug_message, [0, 2, 1], 46 ),
- MAVLINK_MSG_ID_EXTENDED_MESSAGE : ( '<BBB', MAVLink_extended_message_message, [0, 1, 2], 247 ),
-}
-
-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 = 254
- self.little_endian = True
- self.crc_extra = True
- self.sort_fields = True
- 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] != 254:
- 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) != 254:
- 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 True: # 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 True:
- 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, base_mode, custom_mode, system_status, mavlink_version=3):
- '''
- 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 : Autopilot type / class. defined in MAV_CLASS ENUM (uint8_t)
- base_mode : System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h (uint8_t)
- custom_mode : Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific. (uint32_t)
- system_status : System status flag, see MAV_STATUS ENUM (uint8_t)
- mavlink_version : MAVLink version (uint8_t)
-
- '''
- msg = MAVLink_heartbeat_message(type, autopilot, base_mode, custom_mode, system_status, mavlink_version)
- msg.pack(self)
- return msg
-
- def heartbeat_send(self, type, autopilot, base_mode, custom_mode, system_status, mavlink_version=3):
- '''
- 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 : Autopilot type / class. defined in MAV_CLASS ENUM (uint8_t)
- base_mode : System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h (uint8_t)
- custom_mode : Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific. (uint32_t)
- system_status : System status flag, see MAV_STATUS ENUM (uint8_t)
- mavlink_version : MAVLink version (uint8_t)
-
- '''
- return self.send(self.heartbeat_encode(type, autopilot, base_mode, custom_mode, system_status, mavlink_version))
-
- def sys_status_encode(self, onboard_control_sensors_present, onboard_control_sensors_enabled, onboard_control_sensors_health, load, voltage_battery, current_battery, battery_remaining, drop_rate_comm, errors_comm, errors_count1, errors_count2, errors_count3, errors_count4):
- '''
- 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.
-
- onboard_control_sensors_present : Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control (uint32_t)
- onboard_control_sensors_enabled : Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control (uint32_t)
- onboard_control_sensors_health : Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control (uint32_t)
- load : Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 (uint16_t)
- voltage_battery : Battery voltage, in millivolts (1 = 1 millivolt) (uint16_t)
- current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t)
- battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery (int8_t)
- drop_rate_comm : Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) (uint16_t)
- errors_comm : Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) (uint16_t)
- errors_count1 : Autopilot-specific errors (uint16_t)
- errors_count2 : Autopilot-specific errors (uint16_t)
- errors_count3 : Autopilot-specific errors (uint16_t)
- errors_count4 : Autopilot-specific errors (uint16_t)
-
- '''
- msg = MAVLink_sys_status_message(onboard_control_sensors_present, onboard_control_sensors_enabled, onboard_control_sensors_health, load, voltage_battery, current_battery, battery_remaining, drop_rate_comm, errors_comm, errors_count1, errors_count2, errors_count3, errors_count4)
- msg.pack(self)
- return msg
-
- def sys_status_send(self, onboard_control_sensors_present, onboard_control_sensors_enabled, onboard_control_sensors_health, load, voltage_battery, current_battery, battery_remaining, drop_rate_comm, errors_comm, errors_count1, errors_count2, errors_count3, errors_count4):
- '''
- 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.
-
- onboard_control_sensors_present : Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control (uint32_t)
- onboard_control_sensors_enabled : Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control (uint32_t)
- onboard_control_sensors_health : Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control (uint32_t)
- load : Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 (uint16_t)
- voltage_battery : Battery voltage, in millivolts (1 = 1 millivolt) (uint16_t)
- current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t)
- battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery (int8_t)
- drop_rate_comm : Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) (uint16_t)
- errors_comm : Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) (uint16_t)
- errors_count1 : Autopilot-specific errors (uint16_t)
- errors_count2 : Autopilot-specific errors (uint16_t)
- errors_count3 : Autopilot-specific errors (uint16_t)
- errors_count4 : Autopilot-specific errors (uint16_t)
-
- '''
- return self.send(self.sys_status_encode(onboard_control_sensors_present, onboard_control_sensors_enabled, onboard_control_sensors_health, load, voltage_battery, current_battery, battery_remaining, drop_rate_comm, errors_comm, errors_count1, errors_count2, errors_count3, errors_count4))
-
- def system_time_encode(self, time_unix_usec, time_boot_ms):
- '''
- The system time is the time of the master clock, typically the
- computer clock of the main onboard computer.
-
- time_unix_usec : Timestamp of the master clock in microseconds since UNIX epoch. (uint64_t)
- time_boot_ms : Timestamp of the component clock since boot time in milliseconds. (uint32_t)
-
- '''
- msg = MAVLink_system_time_message(time_unix_usec, time_boot_ms)
- msg.pack(self)
- return msg
-
- def system_time_send(self, time_unix_usec, time_boot_ms):
- '''
- The system time is the time of the master clock, typically the
- computer clock of the main onboard computer.
-
- time_unix_usec : Timestamp of the master clock in microseconds since UNIX epoch. (uint64_t)
- time_boot_ms : Timestamp of the component clock since boot time in milliseconds. (uint32_t)
-
- '''
- return self.send(self.system_time_encode(time_unix_usec, time_boot_ms))
-
- def ping_encode(self, time_usec, seq, target_system, target_component):
- '''
- 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.
-
- time_usec : Unix timestamp in microseconds (uint64_t)
- 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)
-
- '''
- msg = MAVLink_ping_message(time_usec, seq, target_system, target_component)
- msg.pack(self)
- return msg
-
- def ping_send(self, time_usec, seq, target_system, target_component):
- '''
- 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.
-
- time_usec : Unix timestamp in microseconds (uint64_t)
- 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)
-
- '''
- return self.send(self.ping_encode(time_usec, seq, target_system, target_component))
-
- 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 set_mode_encode(self, target_system, base_mode, custom_mode):
- '''
- Set the system mode, as defined by enum MAV_MODE. There is no target
- component id as the mode is by definition for the
- overall aircraft, not only for one component.
-
- target_system : The system setting the mode (uint8_t)
- base_mode : The new base mode (uint8_t)
- custom_mode : The new autopilot-specific mode. This field can be ignored by an autopilot. (uint32_t)
-
- '''
- msg = MAVLink_set_mode_message(target_system, base_mode, custom_mode)
- msg.pack(self)
- return msg
-
- def set_mode_send(self, target_system, base_mode, custom_mode):
- '''
- Set the system mode, as defined by enum MAV_MODE. There is no target
- component id as the mode is by definition for the
- overall aircraft, not only for one component.
-
- target_system : The system setting the mode (uint8_t)
- base_mode : The new base mode (uint8_t)
- custom_mode : The new autopilot-specific mode. This field can be ignored by an autopilot. (uint32_t)
-
- '''
- return self.send(self.set_mode_encode(target_system, base_mode, custom_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 (char)
- 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 (char)
- 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_type, 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 (char)
- param_value : Onboard parameter value (float)
- param_type : Onboard parameter type: see MAV_VAR enum (uint8_t)
- 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_type, param_count, param_index)
- msg.pack(self)
- return msg
-
- def param_value_send(self, param_id, param_value, param_type, 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 (char)
- param_value : Onboard parameter value (float)
- param_type : Onboard parameter type: see MAV_VAR enum (uint8_t)
- 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_type, param_count, param_index))
-
- def param_set_encode(self, target_system, target_component, param_id, param_value, param_type):
- '''
- 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 (char)
- param_value : Onboard parameter value (float)
- param_type : Onboard parameter type: see MAV_VAR enum (uint8_t)
-
- '''
- msg = MAVLink_param_set_message(target_system, target_component, param_id, param_value, param_type)
- msg.pack(self)
- return msg
-
- def param_set_send(self, target_system, target_component, param_id, param_value, param_type):
- '''
- 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 (char)
- param_value : Onboard parameter value (float)
- param_type : Onboard parameter type: see MAV_VAR enum (uint8_t)
-
- '''
- return self.send(self.param_set_encode(target_system, target_component, param_id, param_value, param_type))
-
- def gps_raw_int_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible):
- '''
- 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)
-
- time_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) above MSL (int32_t)
- eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t)
- epv : GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t)
- vel : GPS ground speed (m/s * 100). If unknown, set to: 65535 (uint16_t)
- cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t)
- satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t)
-
- '''
- msg = MAVLink_gps_raw_int_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible)
- msg.pack(self)
- return msg
-
- def gps_raw_int_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible):
- '''
- 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)
-
- time_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) above MSL (int32_t)
- eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t)
- epv : GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t)
- vel : GPS ground speed (m/s * 100). If unknown, set to: 65535 (uint16_t)
- cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t)
- satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t)
-
- '''
- return self.send(self.gps_raw_int_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible))
-
- 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 (uint8_t)
- satellite_used : 0: Satellite not used, 1: used for localization (uint8_t)
- satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (uint8_t)
- satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (uint8_t)
- satellite_snr : Signal to noise ratio of satellite (uint8_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 (uint8_t)
- satellite_used : 0: Satellite not used, 1: used for localization (uint8_t)
- satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (uint8_t)
- satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (uint8_t)
- satellite_snr : Signal to noise ratio of satellite (uint8_t)
-
- '''
- return self.send(self.gps_status_encode(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr))
-
- def scaled_imu_encode(self, time_boot_ms, 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
-
- time_boot_ms : Timestamp (milliseconds since system boot) (uint32_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(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)
- msg.pack(self)
- return msg
-
- def scaled_imu_send(self, time_boot_ms, 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
-
- time_boot_ms : Timestamp (milliseconds since system boot) (uint32_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(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag))
-
- def raw_imu_encode(self, time_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.
-
- time_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(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)
- msg.pack(self)
- return msg
-
- def raw_imu_send(self, time_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.
-
- time_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(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag))
-
- def raw_pressure_encode(self, time_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.
-
- time_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(time_usec, press_abs, press_diff1, press_diff2, temperature)
- msg.pack(self)
- return msg
-
- def raw_pressure_send(self, time_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.
-
- time_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(time_usec, press_abs, press_diff1, press_diff2, temperature))
-
- def scaled_pressure_encode(self, time_boot_ms, 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.
-
- time_boot_ms : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint32_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(time_boot_ms, press_abs, press_diff, temperature)
- msg.pack(self)
- return msg
-
- def scaled_pressure_send(self, time_boot_ms, 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.
-
- time_boot_ms : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint32_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(time_boot_ms, press_abs, press_diff, temperature))
-
- def attitude_encode(self, time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed):
- '''
- The attitude in the aeronautical frame (right-handed, Z-down, X-front,
- Y-right).
-
- time_boot_ms : Timestamp (milliseconds since system boot) (uint32_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(time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed)
- msg.pack(self)
- return msg
-
- def attitude_send(self, time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed):
- '''
- The attitude in the aeronautical frame (right-handed, Z-down, X-front,
- Y-right).
-
- time_boot_ms : Timestamp (milliseconds since system boot) (uint32_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(time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed))
-
- def attitude_quaternion_encode(self, time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed):
- '''
- The attitude in the aeronautical frame (right-handed, Z-down, X-front,
- Y-right), expressed as quaternion.
-
- time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
- q1 : Quaternion component 1 (float)
- q2 : Quaternion component 2 (float)
- q3 : Quaternion component 3 (float)
- q4 : Quaternion component 4 (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_quaternion_message(time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed)
- msg.pack(self)
- return msg
-
- def attitude_quaternion_send(self, time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed):
- '''
- The attitude in the aeronautical frame (right-handed, Z-down, X-front,
- Y-right), expressed as quaternion.
-
- time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
- q1 : Quaternion component 1 (float)
- q2 : Quaternion component 2 (float)
- q3 : Quaternion component 3 (float)
- q4 : Quaternion component 4 (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_quaternion_encode(time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed))
-
- def local_position_ned_encode(self, time_boot_ms, 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, NED / north-east-down
- convention)
-
- time_boot_ms : Timestamp (milliseconds since system boot) (uint32_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_ned_message(time_boot_ms, x, y, z, vx, vy, vz)
- msg.pack(self)
- return msg
-
- def local_position_ned_send(self, time_boot_ms, 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, NED / north-east-down
- convention)
-
- time_boot_ms : Timestamp (milliseconds since system boot) (uint32_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_ned_encode(time_boot_ms, x, y, z, vx, vy, vz))
-
- def global_position_int_encode(self, time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg):
- '''
- The filtered global position (e.g. fused GPS and accelerometers). The
- position is in GPS-frame (right-handed, Z-up). It
- is designed as scaled integer message since the
- resolution of float is not sufficient.
-
- time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
- lat : Latitude, expressed as * 1E7 (int32_t)
- lon : Longitude, expressed as * 1E7 (int32_t)
- alt : Altitude in meters, expressed as * 1000 (millimeters), above MSL (int32_t)
- relative_alt : Altitude above ground 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)
- hdg : Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t)
-
- '''
- msg = MAVLink_global_position_int_message(time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg)
- msg.pack(self)
- return msg
-
- def global_position_int_send(self, time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg):
- '''
- The filtered global position (e.g. fused GPS and accelerometers). The
- position is in GPS-frame (right-handed, Z-up). It
- is designed as scaled integer message since the
- resolution of float is not sufficient.
-
- time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
- lat : Latitude, expressed as * 1E7 (int32_t)
- lon : Longitude, expressed as * 1E7 (int32_t)
- alt : Altitude in meters, expressed as * 1000 (millimeters), above MSL (int32_t)
- relative_alt : Altitude above ground 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)
- hdg : Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t)
-
- '''
- return self.send(self.global_position_int_encode(time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg))
-
- def rc_channels_scaled_encode(self, time_boot_ms, port, 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
-
- time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
- port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t)
- 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(time_boot_ms, port, 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, time_boot_ms, port, 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
-
- time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
- port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t)
- 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(time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi))
-
- def rc_channels_raw_encode(self, time_boot_ms, port, 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.
-
- time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
- port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (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)
- rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t)
-
- '''
- msg = MAVLink_rc_channels_raw_message(time_boot_ms, port, 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, time_boot_ms, port, 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.
-
- time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
- port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (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)
- rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t)
-
- '''
- return self.send(self.rc_channels_raw_encode(time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi))
-
- def servo_output_raw_encode(self, time_usec, port, 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%.
-
- time_usec : Timestamp (since UNIX epoch or microseconds since system boot) (uint32_t)
- port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t)
- 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(time_usec, port, 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, time_usec, port, 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%.
-
- time_usec : Timestamp (since UNIX epoch or microseconds since system boot) (uint32_t)
- port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t)
- 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(time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw))
-
- def mission_request_partial_list_encode(self, target_system, target_component, start_index, end_index):
- '''
- Request the overall list of MISSIONs from the system/component.
- http://qgroundcontrol.org/mavlink/waypoint_protocol
-
- target_system : System ID (uint8_t)
- target_component : Component ID (uint8_t)
- start_index : Start index, 0 by default (int16_t)
- end_index : End index, -1 by default (-1: send list to end). Else a valid index of the list (int16_t)
-
- '''
- msg = MAVLink_mission_request_partial_list_message(target_system, target_component, start_index, end_index)
- msg.pack(self)
- return msg
-
- def mission_request_partial_list_send(self, target_system, target_component, start_index, end_index):
- '''
- Request the overall list of MISSIONs from the system/component.
- http://qgroundcontrol.org/mavlink/waypoint_protocol
-
- target_system : System ID (uint8_t)
- target_component : Component ID (uint8_t)
- start_index : Start index, 0 by default (int16_t)
- end_index : End index, -1 by default (-1: send list to end). Else a valid index of the list (int16_t)
-
- '''
- return self.send(self.mission_request_partial_list_encode(target_system, target_component, start_index, end_index))
-
- def mission_write_partial_list_encode(self, target_system, target_component, start_index, end_index):
- '''
- This message is sent to the MAV to write a partial list. If start
- index == end index, only one item will be transmitted
- / updated. If the start index is NOT 0 and above the
- current list size, this request should be REJECTED!
-
- target_system : System ID (uint8_t)
- target_component : Component ID (uint8_t)
- start_index : Start index, 0 by default and smaller / equal to the largest index of the current onboard list. (int16_t)
- end_index : End index, equal or greater than start index. (int16_t)
-
- '''
- msg = MAVLink_mission_write_partial_list_message(target_system, target_component, start_index, end_index)
- msg.pack(self)
- return msg
-
- def mission_write_partial_list_send(self, target_system, target_component, start_index, end_index):
- '''
- This message is sent to the MAV to write a partial list. If start
- index == end index, only one item will be transmitted
- / updated. If the start index is NOT 0 and above the
- current list size, this request should be REJECTED!
-
- target_system : System ID (uint8_t)
- target_component : Component ID (uint8_t)
- start_index : Start index, 0 by default and smaller / equal to the largest index of the current onboard list. (int16_t)
- end_index : End index, equal or greater than start index. (int16_t)
-
- '''
- return self.send(self.mission_write_partial_list_encode(target_system, target_component, start_index, end_index))
-
- def mission_item_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z):
- '''
- Message encoding a mission item. This message is emitted to announce
- the presence of a mission item and to set a mission
- item on the system. The mission item can be either in
- x, y, z meters (type: LOCAL) or x:lat, y:lon,
- z:altitude. Local frame is Z-down, right handed (NED),
- global frame is Z-up, right handed (ENU).
- http://qgroundcontrol.org/mavlink/waypoint_protocol
-
- target_system : System ID (uint8_t)
- target_component : Component ID (uint8_t)
- seq : Sequence (uint16_t)
- frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t)
- command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t)
- current : false:0, true:1 (uint8_t)
- autocontinue : autocontinue to next wp (uint8_t)
- param1 : PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters (float)
- param2 : PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds (float)
- param3 : PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, 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 MISSIONs: 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_mission_item_message(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)
- msg.pack(self)
- return msg
-
- def mission_item_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z):
- '''
- Message encoding a mission item. This message is emitted to announce
- the presence of a mission item and to set a mission
- item on the system. The mission item can be either in
- x, y, z meters (type: LOCAL) or x:lat, y:lon,
- z:altitude. Local frame is Z-down, right handed (NED),
- global frame is Z-up, right handed (ENU).
- http://qgroundcontrol.org/mavlink/waypoint_protocol
-
- target_system : System ID (uint8_t)
- target_component : Component ID (uint8_t)
- seq : Sequence (uint16_t)
- frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t)
- command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t)
- current : false:0, true:1 (uint8_t)
- autocontinue : autocontinue to next wp (uint8_t)
- param1 : PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters (float)
- param2 : PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds (float)
- param3 : PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, 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 MISSIONs: 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.mission_item_encode(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z))
-
- def mission_request_encode(self, target_system, target_component, seq):
- '''
- Request the information of the mission item with the sequence number
- seq. The response of the system to this message should
- be a MISSION_ITEM message.
- http://qgroundcontrol.org/mavlink/waypoint_protocol
-
- target_system : System ID (uint8_t)
- target_component : Component ID (uint8_t)
- seq : Sequence (uint16_t)
-
- '''
- msg = MAVLink_mission_request_message(target_system, target_component, seq)
- msg.pack(self)
- return msg
-
- def mission_request_send(self, target_system, target_component, seq):
- '''
- Request the information of the mission item with the sequence number
- seq. The response of the system to this message should
- be a MISSION_ITEM message.
- http://qgroundcontrol.org/mavlink/waypoint_protocol
-
- target_system : System ID (uint8_t)
- target_component : Component ID (uint8_t)
- seq : Sequence (uint16_t)
-
- '''
- return self.send(self.mission_request_encode(target_system, target_component, seq))
-
- def mission_set_current_encode(self, target_system, target_component, seq):
- '''
- Set the mission item with sequence number seq as current item. This
- means that the MAV will continue to this mission item
- on the shortest path (not following the mission items
- in-between).
-
- target_system : System ID (uint8_t)
- target_component : Component ID (uint8_t)
- seq : Sequence (uint16_t)
-
- '''
- msg = MAVLink_mission_set_current_message(target_system, target_component, seq)
- msg.pack(self)
- return msg
-
- def mission_set_current_send(self, target_system, target_component, seq):
- '''
- Set the mission item with sequence number seq as current item. This
- means that the MAV will continue to this mission item
- on the shortest path (not following the mission items
- in-between).
-
- target_system : System ID (uint8_t)
- target_component : Component ID (uint8_t)
- seq : Sequence (uint16_t)
-
- '''
- return self.send(self.mission_set_current_encode(target_system, target_component, seq))
-
- def mission_current_encode(self, seq):
- '''
- Message that announces the sequence number of the current active
- mission item. The MAV will fly towards this mission
- item.
-
- seq : Sequence (uint16_t)
-
- '''
- msg = MAVLink_mission_current_message(seq)
- msg.pack(self)
- return msg
-
- def mission_current_send(self, seq):
- '''
- Message that announces the sequence number of the current active
- mission item. The MAV will fly towards this mission
- item.
-
- seq : Sequence (uint16_t)
-
- '''
- return self.send(self.mission_current_encode(seq))
-
- def mission_request_list_encode(self, target_system, target_component):
- '''
- Request the overall list of mission items from the system/component.
-
- target_system : System ID (uint8_t)
- target_component : Component ID (uint8_t)
-
- '''
- msg = MAVLink_mission_request_list_message(target_system, target_component)
- msg.pack(self)
- return msg
-
- def mission_request_list_send(self, target_system, target_component):
- '''
- Request the overall list of mission items from the system/component.
-
- target_system : System ID (uint8_t)
- target_component : Component ID (uint8_t)
-
- '''
- return self.send(self.mission_request_list_encode(target_system, target_component))
-
- def mission_count_encode(self, target_system, target_component, count):
- '''
- This message is emitted as response to MISSION_REQUEST_LIST by the MAV
- and to initiate a write transaction. The GCS can then
- request the individual mission item based on the
- knowledge of the total number of MISSIONs.
-
- target_system : System ID (uint8_t)
- target_component : Component ID (uint8_t)
- count : Number of mission items in the sequence (uint16_t)
-
- '''
- msg = MAVLink_mission_count_message(target_system, target_component, count)
- msg.pack(self)
- return msg
-
- def mission_count_send(self, target_system, target_component, count):
- '''
- This message is emitted as response to MISSION_REQUEST_LIST by the MAV
- and to initiate a write transaction. The GCS can then
- request the individual mission item based on the
- knowledge of the total number of MISSIONs.
-
- target_system : System ID (uint8_t)
- target_component : Component ID (uint8_t)
- count : Number of mission items in the sequence (uint16_t)
-
- '''
- return self.send(self.mission_count_encode(target_system, target_component, count))
-
- def mission_clear_all_encode(self, target_system, target_component):
- '''
- Delete all mission items at once.
-
- target_system : System ID (uint8_t)
- target_component : Component ID (uint8_t)
-
- '''
- msg = MAVLink_mission_clear_all_message(target_system, target_component)
- msg.pack(self)
- return msg
-
- def mission_clear_all_send(self, target_system, target_component):
- '''
- Delete all mission items at once.
-
- target_system : System ID (uint8_t)
- target_component : Component ID (uint8_t)
-
- '''
- return self.send(self.mission_clear_all_encode(target_system, target_component))
-
- def mission_item_reached_encode(self, seq):
- '''
- A certain mission item 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
- MISSION.
-
- seq : Sequence (uint16_t)
-
- '''
- msg = MAVLink_mission_item_reached_message(seq)
- msg.pack(self)
- return msg
-
- def mission_item_reached_send(self, seq):
- '''
- A certain mission item 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
- MISSION.
-
- seq : Sequence (uint16_t)
-
- '''
- return self.send(self.mission_item_reached_encode(seq))
-
- def mission_ack_encode(self, target_system, target_component, type):
- '''
- Ack message during MISSION 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 : See MAV_MISSION_RESULT enum (uint8_t)
-
- '''
- msg = MAVLink_mission_ack_message(target_system, target_component, type)
- msg.pack(self)
- return msg
-
- def mission_ack_send(self, target_system, target_component, type):
- '''
- Ack message during MISSION 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 : See MAV_MISSION_RESULT enum (uint8_t)
-
- '''
- return self.send(self.mission_ack_encode(target_system, target_component, type))
-
- def set_gps_global_origin_encode(self, target_system, latitude, longitude, altitude):
- '''
- As local MISSIONs exist, the global MISSION 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)
- latitude : global position * 1E7 (int32_t)
- longitude : global position * 1E7 (int32_t)
- altitude : global position * 1000 (int32_t)
-
- '''
- msg = MAVLink_set_gps_global_origin_message(target_system, latitude, longitude, altitude)
- msg.pack(self)
- return msg
-
- def set_gps_global_origin_send(self, target_system, latitude, longitude, altitude):
- '''
- As local MISSIONs exist, the global MISSION 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)
- latitude : global position * 1E7 (int32_t)
- longitude : global position * 1E7 (int32_t)
- altitude : global position * 1000 (int32_t)
-
- '''
- return self.send(self.set_gps_global_origin_encode(target_system, latitude, longitude, altitude))
-
- def gps_global_origin_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_global_origin_message(latitude, longitude, altitude)
- msg.pack(self)
- return msg
-
- def gps_global_origin_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_global_origin_encode(latitude, longitude, altitude))
-
- def set_local_position_setpoint_encode(self, target_system, target_component, coordinate_frame, 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/MISSION 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)
- coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU (uint8_t)
- x : x position (float)
- y : y position (float)
- z : z position (float)
- yaw : Desired yaw angle (float)
-
- '''
- msg = MAVLink_set_local_position_setpoint_message(target_system, target_component, coordinate_frame, x, y, z, yaw)
- msg.pack(self)
- return msg
-
- def set_local_position_setpoint_send(self, target_system, target_component, coordinate_frame, 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/MISSION 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)
- coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU (uint8_t)
- x : x position (float)
- y : y position (float)
- z : z position (float)
- yaw : Desired yaw angle (float)
-
- '''
- return self.send(self.set_local_position_setpoint_encode(target_system, target_component, coordinate_frame, x, y, z, yaw))
-
- def local_position_setpoint_encode(self, coordinate_frame, x, y, z, yaw):
- '''
- Transmit the current local setpoint of the controller to other MAVs
- (collision avoidance) and to the GCS.
-
- coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU (uint8_t)
- x : x position (float)
- y : y position (float)
- z : z position (float)
- yaw : Desired yaw angle (float)
-
- '''
- msg = MAVLink_local_position_setpoint_message(coordinate_frame, x, y, z, yaw)
- msg.pack(self)
- return msg
-
- def local_position_setpoint_send(self, coordinate_frame, x, y, z, yaw):
- '''
- Transmit the current local setpoint of the controller to other MAVs
- (collision avoidance) and to the GCS.
-
- coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU (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_encode(coordinate_frame, x, y, z, yaw))
-
- def global_position_setpoint_int_encode(self, coordinate_frame, latitude, longitude, altitude, yaw):
- '''
- Transmit the current local setpoint of the controller to other MAVs
- (collision avoidance) and to the GCS.
-
- coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT (uint8_t)
- latitude : WGS84 Latitude position in degrees * 1E7 (int32_t)
- longitude : WGS84 Longitude position in degrees * 1E7 (int32_t)
- altitude : WGS84 Altitude in meters * 1000 (positive for up) (int32_t)
- yaw : Desired yaw angle in degrees * 100 (int16_t)
-
- '''
- msg = MAVLink_global_position_setpoint_int_message(coordinate_frame, latitude, longitude, altitude, yaw)
- msg.pack(self)
- return msg
-
- def global_position_setpoint_int_send(self, coordinate_frame, latitude, longitude, altitude, yaw):
- '''
- Transmit the current local setpoint of the controller to other MAVs
- (collision avoidance) and to the GCS.
-
- coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT (uint8_t)
- latitude : WGS84 Latitude position in degrees * 1E7 (int32_t)
- longitude : WGS84 Longitude position in degrees * 1E7 (int32_t)
- altitude : WGS84 Altitude in meters * 1000 (positive for up) (int32_t)
- yaw : Desired yaw angle in degrees * 100 (int16_t)
-
- '''
- return self.send(self.global_position_setpoint_int_encode(coordinate_frame, latitude, longitude, altitude, yaw))
-
- def set_global_position_setpoint_int_encode(self, coordinate_frame, latitude, longitude, altitude, yaw):
- '''
- Set the current global position setpoint.
-
- coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT (uint8_t)
- latitude : WGS84 Latitude position in degrees * 1E7 (int32_t)
- longitude : WGS84 Longitude position in degrees * 1E7 (int32_t)
- altitude : WGS84 Altitude in meters * 1000 (positive for up) (int32_t)
- yaw : Desired yaw angle in degrees * 100 (int16_t)
-
- '''
- msg = MAVLink_set_global_position_setpoint_int_message(coordinate_frame, latitude, longitude, altitude, yaw)
- msg.pack(self)
- return msg
-
- def set_global_position_setpoint_int_send(self, coordinate_frame, latitude, longitude, altitude, yaw):
- '''
- Set the current global position setpoint.
-
- coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT (uint8_t)
- latitude : WGS84 Latitude position in degrees * 1E7 (int32_t)
- longitude : WGS84 Longitude position in degrees * 1E7 (int32_t)
- altitude : WGS84 Altitude in meters * 1000 (positive for up) (int32_t)
- yaw : Desired yaw angle in degrees * 100 (int16_t)
-
- '''
- return self.send(self.set_global_position_setpoint_int_encode(coordinate_frame, latitude, longitude, altitude, 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/MISSIONs 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/MISSIONs 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_boot_ms, roll, pitch, yaw, thrust):
- '''
- Setpoint in roll, pitch, yaw currently active on the system.
-
- time_boot_ms : Timestamp in milliseconds since system boot (uint32_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_boot_ms, roll, pitch, yaw, thrust)
- msg.pack(self)
- return msg
-
- def roll_pitch_yaw_thrust_setpoint_send(self, time_boot_ms, roll, pitch, yaw, thrust):
- '''
- Setpoint in roll, pitch, yaw currently active on the system.
-
- time_boot_ms : Timestamp in milliseconds since system boot (uint32_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_boot_ms, roll, pitch, yaw, thrust))
-
- def roll_pitch_yaw_speed_thrust_setpoint_encode(self, time_boot_ms, roll_speed, pitch_speed, yaw_speed, thrust):
- '''
- Setpoint in rollspeed, pitchspeed, yawspeed currently active on the
- system.
-
- time_boot_ms : Timestamp in milliseconds since system boot (uint32_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_boot_ms, roll_speed, pitch_speed, yaw_speed, thrust)
- msg.pack(self)
- return msg
-
- def roll_pitch_yaw_speed_thrust_setpoint_send(self, time_boot_ms, roll_speed, pitch_speed, yaw_speed, thrust):
- '''
- Setpoint in rollspeed, pitchspeed, yawspeed currently active on the
- system.
-
- time_boot_ms : Timestamp in milliseconds since system boot (uint32_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_boot_ms, 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 MISSION/target in degrees (int16_t)
- wp_dist : Distance to active MISSION 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 MISSION/target in degrees (int16_t)
- wp_dist : Distance to active MISSION 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 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 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 data stream (uint8_t)
- req_message_rate : The requested interval between two messages of this type (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 data stream (uint8_t)
- req_message_rate : The requested interval between two messages of this type (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 data_stream_encode(self, stream_id, message_rate, on_off):
- '''
-
-
- stream_id : The ID of the requested data stream (uint8_t)
- message_rate : The requested interval between two messages of this type (uint16_t)
- on_off : 1 stream is enabled, 0 stream is stopped. (uint8_t)
-
- '''
- msg = MAVLink_data_stream_message(stream_id, message_rate, on_off)
- msg.pack(self)
- return msg
-
- def data_stream_send(self, stream_id, message_rate, on_off):
- '''
-
-
- stream_id : The ID of the requested data stream (uint8_t)
- message_rate : The requested interval between two messages of this type (uint16_t)
- on_off : 1 stream is enabled, 0 stream is stopped. (uint8_t)
-
- '''
- return self.send(self.data_stream_encode(stream_id, message_rate, on_off))
-
- 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 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_long_encode(self, target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7):
- '''
- 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. (uint16_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)
- param5 : Parameter 5, as defined by MAV_CMD enum. (float)
- param6 : Parameter 6, as defined by MAV_CMD enum. (float)
- param7 : Parameter 7, as defined by MAV_CMD enum. (float)
-
- '''
- msg = MAVLink_command_long_message(target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7)
- msg.pack(self)
- return msg
-
- def command_long_send(self, target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7):
- '''
- 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. (uint16_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)
- param5 : Parameter 5, as defined by MAV_CMD enum. (float)
- param6 : Parameter 6, as defined by MAV_CMD enum. (float)
- param7 : Parameter 7, as defined by MAV_CMD enum. (float)
-
- '''
- return self.send(self.command_long_encode(target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7))
-
- def command_ack_encode(self, command, result):
- '''
- Report status of a command. Includes feedback wether the command was
- executed
-
- command : Command ID, as defined by MAV_CMD enum. (uint16_t)
- result : See MAV_RESULT enum (uint8_t)
-
- '''
- 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 : Command ID, as defined by MAV_CMD enum. (uint16_t)
- result : See MAV_RESULT enum (uint8_t)
-
- '''
- return self.send(self.command_ack_encode(command, result))
-
- def hil_state_encode(self, time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc):
- '''
- Sent from simulation to autopilot. This packet is useful for high
- throughput applications such as
- hardware in the loop simulations.
-
- time_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(time_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, time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc):
- '''
- Sent from simulation to autopilot. This packet is useful for high
- throughput applications such as
- hardware in the loop simulations.
-
- time_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(time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc))
-
- def hil_controls_encode(self, time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode):
- '''
- Sent from autopilot to simulation. Hardware in the loop control
- outputs
-
- time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
- roll_ailerons : Control output -1 .. 1 (float)
- pitch_elevator : Control output -1 .. 1 (float)
- yaw_rudder : Control output -1 .. 1 (float)
- throttle : Throttle 0 .. 1 (float)
- aux1 : Aux 1, -1 .. 1 (float)
- aux2 : Aux 2, -1 .. 1 (float)
- aux3 : Aux 3, -1 .. 1 (float)
- aux4 : Aux 4, -1 .. 1 (float)
- mode : System mode (MAV_MODE) (uint8_t)
- nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t)
-
- '''
- msg = MAVLink_hil_controls_message(time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode)
- msg.pack(self)
- return msg
-
- def hil_controls_send(self, time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode):
- '''
- Sent from autopilot to simulation. Hardware in the loop control
- outputs
-
- time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
- roll_ailerons : Control output -1 .. 1 (float)
- pitch_elevator : Control output -1 .. 1 (float)
- yaw_rudder : Control output -1 .. 1 (float)
- throttle : Throttle 0 .. 1 (float)
- aux1 : Aux 1, -1 .. 1 (float)
- aux2 : Aux 2, -1 .. 1 (float)
- aux3 : Aux 3, -1 .. 1 (float)
- aux4 : Aux 4, -1 .. 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_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode))
-
- def hil_rc_inputs_raw_encode(self, time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi):
- '''
- Sent from simulation to autopilot. 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.
-
- time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_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)
- chan9_raw : RC channel 9 value, in microseconds (uint16_t)
- chan10_raw : RC channel 10 value, in microseconds (uint16_t)
- chan11_raw : RC channel 11 value, in microseconds (uint16_t)
- chan12_raw : RC channel 12 value, in microseconds (uint16_t)
- rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t)
-
- '''
- msg = MAVLink_hil_rc_inputs_raw_message(time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi)
- msg.pack(self)
- return msg
-
- def hil_rc_inputs_raw_send(self, time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi):
- '''
- Sent from simulation to autopilot. 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.
-
- time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_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)
- chan9_raw : RC channel 9 value, in microseconds (uint16_t)
- chan10_raw : RC channel 10 value, in microseconds (uint16_t)
- chan11_raw : RC channel 11 value, in microseconds (uint16_t)
- chan12_raw : RC channel 12 value, in microseconds (uint16_t)
- rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t)
-
- '''
- return self.send(self.hil_rc_inputs_raw_encode(time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi))
-
- def optical_flow_encode(self, time_usec, sensor_id, flow_x, flow_y, quality, ground_distance):
- '''
- Optical flow from a flow sensor (e.g. optical mouse sensor)
-
- time_usec : 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_usec, sensor_id, flow_x, flow_y, quality, ground_distance)
- msg.pack(self)
- return msg
-
- def optical_flow_send(self, time_usec, sensor_id, flow_x, flow_y, quality, ground_distance):
- '''
- Optical flow from a flow sensor (e.g. optical mouse sensor)
-
- time_usec : 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_usec, sensor_id, flow_x, flow_y, quality, ground_distance))
-
- def global_vision_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw):
- '''
-
-
- usec : Timestamp (milliseconds) (uint64_t)
- x : Global X position (float)
- y : Global Y position (float)
- z : Global Z position (float)
- roll : Roll angle in rad (float)
- pitch : Pitch angle in rad (float)
- yaw : Yaw angle in rad (float)
-
- '''
- msg = MAVLink_global_vision_position_estimate_message(usec, x, y, z, roll, pitch, yaw)
- msg.pack(self)
- return msg
-
- def global_vision_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw):
- '''
-
-
- usec : Timestamp (milliseconds) (uint64_t)
- x : Global X position (float)
- y : Global Y position (float)
- z : Global Z position (float)
- roll : Roll angle in rad (float)
- pitch : Pitch angle in rad (float)
- yaw : Yaw angle in rad (float)
-
- '''
- return self.send(self.global_vision_position_estimate_encode(usec, x, y, z, roll, pitch, yaw))
-
- def vision_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw):
- '''
-
-
- usec : Timestamp (milliseconds) (uint64_t)
- x : Global X position (float)
- y : Global Y position (float)
- z : Global Z position (float)
- roll : Roll angle in rad (float)
- pitch : Pitch angle in rad (float)
- yaw : Yaw angle in rad (float)
-
- '''
- msg = MAVLink_vision_position_estimate_message(usec, x, y, z, roll, pitch, yaw)
- msg.pack(self)
- return msg
-
- def vision_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw):
- '''
-
-
- usec : Timestamp (milliseconds) (uint64_t)
- x : Global X position (float)
- y : Global Y position (float)
- z : Global Z position (float)
- roll : Roll angle in rad (float)
- pitch : Pitch angle in rad (float)
- yaw : Yaw angle in rad (float)
-
- '''
- return self.send(self.vision_position_estimate_encode(usec, x, y, z, roll, pitch, yaw))
-
- def vision_speed_estimate_encode(self, usec, x, y, z):
- '''
-
-
- usec : Timestamp (milliseconds) (uint64_t)
- x : Global X speed (float)
- y : Global Y speed (float)
- z : Global Z speed (float)
-
- '''
- msg = MAVLink_vision_speed_estimate_message(usec, x, y, z)
- msg.pack(self)
- return msg
-
- def vision_speed_estimate_send(self, usec, x, y, z):
- '''
-
-
- usec : Timestamp (milliseconds) (uint64_t)
- x : Global X speed (float)
- y : Global Y speed (float)
- z : Global Z speed (float)
-
- '''
- return self.send(self.vision_speed_estimate_encode(usec, x, y, z))
-
- def vicon_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw):
- '''
-
-
- usec : Timestamp (milliseconds) (uint64_t)
- x : Global X position (float)
- y : Global Y position (float)
- z : Global Z position (float)
- roll : Roll angle in rad (float)
- pitch : Pitch angle in rad (float)
- yaw : Yaw angle in rad (float)
-
- '''
- msg = MAVLink_vicon_position_estimate_message(usec, x, y, z, roll, pitch, yaw)
- msg.pack(self)
- return msg
-
- def vicon_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw):
- '''
-
-
- usec : Timestamp (milliseconds) (uint64_t)
- x : Global X position (float)
- y : Global Y position (float)
- z : Global Z position (float)
- roll : Roll angle in rad (float)
- pitch : Pitch angle in rad (float)
- yaw : Yaw angle in rad (float)
-
- '''
- return self.send(self.vicon_position_estimate_encode(usec, x, y, z, roll, pitch, yaw))
-
- def memory_vect_encode(self, address, ver, type, value):
- '''
- Send raw controller memory. The use of this message is discouraged for
- normal packets, but a quite efficient way for testing
- new messages and getting experimental debug output.
-
- address : Starting address of the debug variables (uint16_t)
- ver : Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below (uint8_t)
- type : Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 (uint8_t)
- value : Memory contents at specified address (int8_t)
-
- '''
- msg = MAVLink_memory_vect_message(address, ver, type, value)
- msg.pack(self)
- return msg
-
- def memory_vect_send(self, address, ver, type, value):
- '''
- Send raw controller memory. The use of this message is discouraged for
- normal packets, but a quite efficient way for testing
- new messages and getting experimental debug output.
-
- address : Starting address of the debug variables (uint16_t)
- ver : Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below (uint8_t)
- type : Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 (uint8_t)
- value : Memory contents at specified address (int8_t)
-
- '''
- return self.send(self.memory_vect_encode(address, ver, type, value))
-
- def debug_vect_encode(self, name, time_usec, x, y, z):
- '''
-
-
- name : Name (char)
- time_usec : Timestamp (uint64_t)
- x : x (float)
- y : y (float)
- z : z (float)
-
- '''
- msg = MAVLink_debug_vect_message(name, time_usec, x, y, z)
- msg.pack(self)
- return msg
-
- def debug_vect_send(self, name, time_usec, x, y, z):
- '''
-
-
- name : Name (char)
- time_usec : Timestamp (uint64_t)
- x : x (float)
- y : y (float)
- z : z (float)
-
- '''
- return self.send(self.debug_vect_encode(name, time_usec, x, y, z))
-
- def named_value_float_encode(self, time_boot_ms, 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.
-
- time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
- name : Name of the debug variable (char)
- value : Floating point value (float)
-
- '''
- msg = MAVLink_named_value_float_message(time_boot_ms, name, value)
- msg.pack(self)
- return msg
-
- def named_value_float_send(self, time_boot_ms, 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.
-
- time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
- name : Name of the debug variable (char)
- value : Floating point value (float)
-
- '''
- return self.send(self.named_value_float_encode(time_boot_ms, name, value))
-
- def named_value_int_encode(self, time_boot_ms, 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.
-
- time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
- name : Name of the debug variable (char)
- value : Signed integer value (int32_t)
-
- '''
- msg = MAVLink_named_value_int_message(time_boot_ms, name, value)
- msg.pack(self)
- return msg
-
- def named_value_int_send(self, time_boot_ms, 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.
-
- time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
- name : Name of the debug variable (char)
- value : Signed integer value (int32_t)
-
- '''
- return self.send(self.named_value_int_encode(time_boot_ms, 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 (char)
-
- '''
- 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 (char)
-
- '''
- return self.send(self.statustext_encode(severity, text))
-
- def debug_encode(self, time_boot_ms, 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.
-
- time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
- ind : index of debug variable (uint8_t)
- value : DEBUG value (float)
-
- '''
- msg = MAVLink_debug_message(time_boot_ms, ind, value)
- msg.pack(self)
- return msg
-
- def debug_send(self, time_boot_ms, 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.
-
- time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t)
- ind : index of debug variable (uint8_t)
- value : DEBUG value (float)
-
- '''
- return self.send(self.debug_encode(time_boot_ms, ind, value))
-
- def extended_message_encode(self, target_system, target_component, protocol_flags):
- '''
- Extended message spacer.
-
- target_system : System which should execute the command (uint8_t)
- target_component : Component which should execute the command, 0 for all components (uint8_t)
- protocol_flags : Retransmission / ACK flags (uint8_t)
-
- '''
- msg = MAVLink_extended_message_message(target_system, target_component, protocol_flags)
- msg.pack(self)
- return msg
-
- def extended_message_send(self, target_system, target_component, protocol_flags):
- '''
- Extended message spacer.
-
- target_system : System which should execute the command (uint8_t)
- target_component : Component which should execute the command, 0 for all components (uint8_t)
- protocol_flags : Retransmission / ACK flags (uint8_t)
-
- '''
- return self.send(self.extended_message_encode(target_system, target_component, protocol_flags))
-
diff --git a/mavlink/share/pyshared/pymavlink/mavutil.py b/mavlink/share/pyshared/pymavlink/mavutil.py
deleted file mode 100644
index c0f625214..000000000
--- a/mavlink/share/pyshared/pymavlink/mavutil.py
+++ /dev/null
@@ -1,678 +0,0 @@
-#!/usr/bin/env python
-'''
-mavlink python utility functions
-
-Copyright Andrew Tridgell 2011
-Released under GNU GPL version 3 or later
-'''
-
-import socket, math, struct, time, os, fnmatch, array, sys, errno
-from math import *
-from mavextra import *
-
-if os.getenv('MAVLINK10'):
- import mavlinkv10 as mavlink
-else:
- import mavlink
-
-def evaluate_expression(expression, vars):
- '''evaluation an expression'''
- try:
- v = eval(expression, globals(), vars)
- except NameError:
- return None
- return v
-
-def evaluate_condition(condition, vars):
- '''evaluation a conditional (boolean) statement'''
- if condition is None:
- return True
- v = evaluate_expression(condition, vars)
- if v is None:
- return False
- return v
-
-
-class mavfile(object):
- '''a generic mavlink port'''
- def __init__(self, fd, address, source_system=255, notimestamps=False):
- self.fd = fd
- self.address = address
- self.messages = { 'MAV' : self }
- if mavlink.WIRE_PROTOCOL_VERSION == "1.0":
- self.messages['HOME'] = mavlink.MAVLink_gps_raw_int_message(0,0,0,0,0,0,0,0,0,0)
- mavlink.MAVLink_waypoint_message = mavlink.MAVLink_mission_item_message
- else:
- self.messages['HOME'] = mavlink.MAVLink_gps_raw_message(0,0,0,0,0,0,0,0,0)
- self.params = {}
- self.mav = None
- self.target_system = 0
- self.target_component = 0
- self.mav = mavlink.MAVLink(self, srcSystem=source_system)
- self.mav.robust_parsing = True
- self.logfile = None
- self.logfile_raw = None
- self.param_fetch_in_progress = False
- self.param_fetch_complete = False
- self.start_time = time.time()
- self.flightmode = "UNKNOWN"
- self.timestamp = 0
- self.message_hooks = []
- self.idle_hooks = []
- self.usec = 0
- self.notimestamps = notimestamps
- self._timestamp = None
-
- def recv(self, n=None):
- '''default recv method'''
- raise RuntimeError('no recv() method supplied')
-
- def close(self, n=None):
- '''default close method'''
- raise RuntimeError('no close() method supplied')
-
- def write(self, buf):
- '''default write method'''
- raise RuntimeError('no write() method supplied')
-
- def pre_message(self):
- '''default pre message call'''
- return
-
- def post_message(self, msg):
- '''default post message call'''
- msg._timestamp = time.time()
- type = msg.get_type()
- self.messages[type] = msg
-
- if self._timestamp is not None:
- if self.notimestamps:
- if 'usec' in msg.__dict__:
- self.usec = msg.usec / 1.0e6
- msg._timestamp = self.usec
- else:
- msg._timestamp = self._timestamp
-
- self.timestamp = msg._timestamp
- if type == 'HEARTBEAT':
- self.target_system = msg.get_srcSystem()
- self.target_component = msg.get_srcComponent()
- if mavlink.WIRE_PROTOCOL_VERSION == '1.0':
- self.flightmode = mode_string_v10(msg)
- elif type == 'PARAM_VALUE':
- self.params[str(msg.param_id)] = msg.param_value
- if msg.param_index+1 == msg.param_count:
- self.param_fetch_in_progress = False
- self.param_fetch_complete = True
- elif type == 'SYS_STATUS' and mavlink.WIRE_PROTOCOL_VERSION == '0.9':
- self.flightmode = mode_string_v09(msg)
- elif type == 'GPS_RAW':
- if self.messages['HOME'].fix_type < 2:
- self.messages['HOME'] = msg
- for hook in self.message_hooks:
- hook(self, msg)
-
-
- def recv_msg(self):
- '''message receive routine'''
- self.pre_message()
- while True:
- n = self.mav.bytes_needed()
- s = self.recv(n)
- if len(s) == 0 and len(self.mav.buf) == 0:
- return None
- if self.logfile_raw:
- self.logfile_raw.write(str(s))
- msg = self.mav.parse_char(s)
- if msg:
- self.post_message(msg)
- return msg
-
- def recv_match(self, condition=None, type=None, blocking=False):
- '''recv the next MAVLink message that matches the given condition'''
- while True:
- m = self.recv_msg()
- if m is None:
- if blocking:
- for hook in self.idle_hooks:
- hook(self)
- time.sleep(0.01)
- continue
- return None
- if type is not None and type != m.get_type():
- continue
- if not evaluate_condition(condition, self.messages):
- continue
- return m
-
- def setup_logfile(self, logfile, mode='w'):
- '''start logging to the given logfile, with timestamps'''
- self.logfile = open(logfile, mode=mode)
-
- def setup_logfile_raw(self, logfile, mode='w'):
- '''start logging raw bytes to the given logfile, without timestamps'''
- self.logfile_raw = open(logfile, mode=mode)
-
- def wait_heartbeat(self, blocking=True):
- '''wait for a heartbeat so we know the target system IDs'''
- return self.recv_match(type='HEARTBEAT', blocking=blocking)
-
- def param_fetch_all(self):
- '''initiate fetch of all parameters'''
- if time.time() - getattr(self, 'param_fetch_start', 0) < 2.0:
- # don't fetch too often
- return
- self.param_fetch_start = time.time()
- self.param_fetch_in_progress = True
- self.mav.param_request_list_send(self.target_system, self.target_component)
-
- def time_since(self, mtype):
- '''return the time since the last message of type mtype was received'''
- if not mtype in self.messages:
- return time.time() - self.start_time
- return time.time() - self.messages[mtype]._timestamp
-
- def param_set_send(self, parm_name, parm_value, parm_type=None):
- '''wrapper for parameter set'''
- if mavlink.WIRE_PROTOCOL_VERSION == '1.0':
- if parm_type == None:
- parm_type = mavlink.MAV_VAR_FLOAT
- self.mav.param_set_send(self.target_system, self.target_component,
- parm_name, parm_value, parm_type)
- else:
- self.mav.param_set_send(self.target_system, self.target_component,
- parm_name, parm_value)
-
- def waypoint_request_list_send(self):
- '''wrapper for waypoint_request_list_send'''
- if mavlink.WIRE_PROTOCOL_VERSION == '1.0':
- self.mav.mission_request_list_send(self.target_system, self.target_component)
- else:
- self.mav.waypoint_request_list_send(self.target_system, self.target_component)
-
- def waypoint_clear_all_send(self):
- '''wrapper for waypoint_clear_all_send'''
- if mavlink.WIRE_PROTOCOL_VERSION == '1.0':
- self.mav.mission_clear_all_send(self.target_system, self.target_component)
- else:
- self.mav.waypoint_clear_all_send(self.target_system, self.target_component)
-
- def waypoint_request_send(self, seq):
- '''wrapper for waypoint_request_send'''
- if mavlink.WIRE_PROTOCOL_VERSION == '1.0':
- self.mav.mission_request_send(self.target_system, self.target_component, seq)
- else:
- self.mav.waypoint_request_send(self.target_system, self.target_component, seq)
-
- def waypoint_set_current_send(self, seq):
- '''wrapper for waypoint_set_current_send'''
- if mavlink.WIRE_PROTOCOL_VERSION == '1.0':
- self.mav.mission_set_current_send(self.target_system, self.target_component, seq)
- else:
- self.mav.waypoint_set_current_send(self.target_system, self.target_component, seq)
-
- def waypoint_count_send(self, seq):
- '''wrapper for waypoint_count_send'''
- if mavlink.WIRE_PROTOCOL_VERSION == '1.0':
- self.mav.mission_count_send(self.target_system, self.target_component, seq)
- else:
- self.mav.waypoint_count_send(self.target_system, self.target_component, seq)
-
-
-class mavserial(mavfile):
- '''a serial mavlink port'''
- def __init__(self, device, baud=115200, autoreconnect=False, source_system=255):
- import serial
- self.baud = baud
- self.device = device
- self.autoreconnect = autoreconnect
- self.port = serial.Serial(self.device, self.baud, timeout=0,
- dsrdtr=False, rtscts=False, xonxoff=False)
-
- try:
- fd = self.port.fileno()
- except Exception:
- fd = None
- mavfile.__init__(self, fd, device, source_system=source_system)
-
- def close(self):
- self.port.close()
-
- def recv(self,n=None):
- if n is None:
- n = self.mav.bytes_needed()
- if self.fd is None:
- waiting = self.port.inWaiting()
- if waiting < n:
- n = waiting
- return self.port.read(n)
-
- def write(self, buf):
- try:
- return self.port.write(buf)
- except OSError:
- if self.autoreconnect:
- self.reset()
- return -1
-
- def reset(self):
- import serial
- self.port.close()
- while True:
- try:
- self.port = serial.Serial(self.device, self.baud, timeout=1,
- dsrdtr=False, rtscts=False, xonxoff=False)
- try:
- self.fd = self.port.fileno()
- except Exception:
- self.fd = None
- return
- except Exception:
- print("Failed to reopen %s" % self.device)
- time.sleep(1)
-
-
-class mavudp(mavfile):
- '''a UDP mavlink socket'''
- def __init__(self, device, input=True, source_system=255):
- a = device.split(':')
- if len(a) != 2:
- print("UDP ports must be specified as host:port")
- sys.exit(1)
- self.port = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
- self.udp_server = input
- if input:
- self.port.bind((a[0], int(a[1])))
- else:
- self.destination_addr = (a[0], int(a[1]))
- self.port.setblocking(0)
- self.last_address = None
- mavfile.__init__(self, self.port.fileno(), device, source_system=source_system)
-
- def close(self):
- self.port.close()
-
- def recv(self,n=None):
- try:
- data, self.last_address = self.port.recvfrom(300)
- except socket.error as e:
- if e.errno in [ errno.EAGAIN, errno.EWOULDBLOCK ]:
- return ""
- raise
- return data
-
- def write(self, buf):
- try:
- if self.udp_server:
- if self.last_address:
- self.port.sendto(buf, self.last_address)
- else:
- self.port.sendto(buf, self.destination_addr)
- except socket.error:
- pass
-
- def recv_msg(self):
- '''message receive routine for UDP link'''
- self.pre_message()
- s = self.recv()
- if len(s) == 0:
- return None
- msg = self.mav.parse_buffer(s)
- if msg is not None:
- for m in msg:
- self.post_message(m)
- return msg[0]
- return None
-
-
-class mavtcp(mavfile):
- '''a TCP mavlink socket'''
- def __init__(self, device, source_system=255):
- a = device.split(':')
- if len(a) != 2:
- print("TCP ports must be specified as host:port")
- sys.exit(1)
- self.port = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
- self.destination_addr = (a[0], int(a[1]))
- self.port.connect(self.destination_addr)
- self.port.setblocking(0)
- self.port.setsockopt(socket.SOL_TCP, socket.TCP_NODELAY, 1)
- mavfile.__init__(self, self.port.fileno(), device, source_system=source_system)
-
- def close(self):
- self.port.close()
-
- def recv(self,n=None):
- if n is None:
- n = self.mav.bytes_needed()
- try:
- data = self.port.recv(n)
- except socket.error as e:
- if e.errno in [ errno.EAGAIN, errno.EWOULDBLOCK ]:
- return ""
- raise
- return data
-
- def write(self, buf):
- try:
- self.port.send(buf)
- except socket.error:
- pass
-
-
-class mavlogfile(mavfile):
- '''a MAVLink logfile reader/writer'''
- def __init__(self, filename, planner_format=None,
- write=False, append=False,
- robust_parsing=True, notimestamps=False, source_system=255):
- self.filename = filename
- self.writeable = write
- self.robust_parsing = robust_parsing
- self.planner_format = planner_format
- self._two64 = math.pow(2.0, 63)
- mode = 'rb'
- if self.writeable:
- if append:
- mode = 'ab'
- else:
- mode = 'wb'
- self.f = open(filename, mode)
- self.filesize = os.path.getsize(filename)
- self.percent = 0
- mavfile.__init__(self, None, filename, source_system=source_system, notimestamps=notimestamps)
- if self.notimestamps:
- self._timestamp = 0
- else:
- self._timestamp = time.time()
-
- def close(self):
- self.f.close()
-
- def recv(self,n=None):
- if n is None:
- n = self.mav.bytes_needed()
- return self.f.read(n)
-
- def write(self, buf):
- self.f.write(buf)
-
- def pre_message(self):
- '''read timestamp if needed'''
- # read the timestamp
- self.percent = (100.0 * self.f.tell()) / self.filesize
- if self.notimestamps:
- return
- if self.planner_format:
- tbuf = self.f.read(21)
- if len(tbuf) != 21 or tbuf[0] != '-' or tbuf[20] != ':':
- raise RuntimeError('bad planner timestamp %s' % tbuf)
- hnsec = self._two64 + float(tbuf[0:20])
- t = hnsec * 1.0e-7 # convert to seconds
- t -= 719163 * 24 * 60 * 60 # convert to 1970 base
- else:
- tbuf = self.f.read(8)
- if len(tbuf) != 8:
- return
- (tusec,) = struct.unpack('>Q', tbuf)
- t = tusec * 1.0e-6
- self._timestamp = t
-
- def post_message(self, msg):
- '''add timestamp to message'''
- # read the timestamp
- super(mavlogfile, self).post_message(msg)
- if self.planner_format:
- self.f.read(1) # trailing newline
- self.timestamp = msg._timestamp
-
-class mavchildexec(mavfile):
- '''a MAVLink child processes reader/writer'''
- def __init__(self, filename, source_system=255):
- from subprocess import Popen, PIPE
- import fcntl
-
- self.filename = filename
- self.child = Popen(filename, shell=True, stdout=PIPE, stdin=PIPE)
- self.fd = self.child.stdout.fileno()
-
- fl = fcntl.fcntl(self.fd, fcntl.F_GETFL)
- fcntl.fcntl(self.fd, fcntl.F_SETFL, fl | os.O_NONBLOCK)
-
- fl = fcntl.fcntl(self.child.stdout.fileno(), fcntl.F_GETFL)
- fcntl.fcntl(self.child.stdout.fileno(), fcntl.F_SETFL, fl | os.O_NONBLOCK)
-
- mavfile.__init__(self, self.fd, filename, source_system=source_system)
-
- def close(self):
- self.child.close()
-
- def recv(self,n=None):
- try:
- x = self.child.stdout.read(1)
- except Exception:
- return ''
- return x
-
- def write(self, buf):
- self.child.stdin.write(buf)
-
-
-def mavlink_connection(device, baud=115200, source_system=255,
- planner_format=None, write=False, append=False,
- robust_parsing=True, notimestamps=False, input=True):
- '''make a serial or UDP mavlink connection'''
- if device.startswith('tcp:'):
- return mavtcp(device[4:], source_system=source_system)
- if device.startswith('udp:'):
- return mavudp(device[4:], input=input, source_system=source_system)
- if device.find(':') != -1 and not device.endswith('log'):
- return mavudp(device, source_system=source_system, input=input)
- if os.path.isfile(device):
- if device.endswith(".elf"):
- return mavchildexec(device, source_system=source_system)
- else:
- return mavlogfile(device, planner_format=planner_format, write=write,
- append=append, robust_parsing=robust_parsing, notimestamps=notimestamps,
- source_system=source_system)
- return mavserial(device, baud=baud, source_system=source_system)
-
-class periodic_event(object):
- '''a class for fixed frequency events'''
- def __init__(self, frequency):
- self.frequency = float(frequency)
- self.last_time = time.time()
-
- def force(self):
- '''force immediate triggering'''
- self.last_time = 0
-
- def trigger(self):
- '''return True if we should trigger now'''
- tnow = time.time()
- if self.last_time + (1.0/self.frequency) <= tnow:
- self.last_time = tnow
- return True
- return False
-
-
-try:
- from curses import ascii
- have_ascii = True
-except:
- have_ascii = False
-
-def is_printable(c):
- '''see if a character is printable'''
- global have_ascii
- if have_ascii:
- return ascii.isprint(c)
- if isinstance(c, int):
- ic = c
- else:
- ic = ord(c)
- return ic >= 32 and ic <= 126
-
-def all_printable(buf):
- '''see if a string is all printable'''
- for c in buf:
- if not is_printable(c) and not c in ['\r', '\n', '\t']:
- return False
- return True
-
-class SerialPort(object):
- '''auto-detected serial port'''
- def __init__(self, device, description=None, hwid=None):
- self.device = device
- self.description = description
- self.hwid = hwid
-
- def __str__(self):
- ret = self.device
- if self.description is not None:
- ret += " : " + self.description
- if self.hwid is not None:
- ret += " : " + self.hwid
- return ret
-
-def auto_detect_serial_win32(preferred_list=['*']):
- '''try to auto-detect serial ports on win32'''
- try:
- import scanwin32
- list = sorted(scanwin32.comports())
- except:
- return []
- ret = []
- for order, port, desc, hwid in list:
- for preferred in preferred_list:
- if fnmatch.fnmatch(desc, preferred) or fnmatch.fnmatch(hwid, preferred):
- ret.append(SerialPort(port, description=desc, hwid=hwid))
- if len(ret) > 0:
- return ret
- # now the rest
- for order, port, desc, hwid in list:
- ret.append(SerialPort(port, description=desc, hwid=hwid))
- return ret
-
-
-
-
-def auto_detect_serial_unix(preferred_list=['*']):
- '''try to auto-detect serial ports on win32'''
- import glob
- glist = glob.glob('/dev/ttyS*') + glob.glob('/dev/ttyUSB*') + glob.glob('/dev/ttyACM*') + glob.glob('/dev/serial/by-id/*')
- ret = []
- # try preferred ones first
- for d in glist:
- for preferred in preferred_list:
- if fnmatch.fnmatch(d, preferred):
- ret.append(SerialPort(d))
- if len(ret) > 0:
- return ret
- # now the rest
- for d in glist:
- ret.append(SerialPort(d))
- return ret
-
-
-
-def auto_detect_serial(preferred_list=['*']):
- '''try to auto-detect serial port'''
- # see if
- if os.name == 'nt':
- return auto_detect_serial_win32(preferred_list=preferred_list)
- return auto_detect_serial_unix(preferred_list=preferred_list)
-
-def mode_string_v09(msg):
- '''mode string for 0.9 protocol'''
- mode = msg.mode
- nav_mode = msg.nav_mode
-
- MAV_MODE_UNINIT = 0
- MAV_MODE_MANUAL = 2
- MAV_MODE_GUIDED = 3
- MAV_MODE_AUTO = 4
- MAV_MODE_TEST1 = 5
- MAV_MODE_TEST2 = 6
- MAV_MODE_TEST3 = 7
-
- MAV_NAV_GROUNDED = 0
- MAV_NAV_LIFTOFF = 1
- MAV_NAV_HOLD = 2
- MAV_NAV_WAYPOINT = 3
- MAV_NAV_VECTOR = 4
- MAV_NAV_RETURNING = 5
- MAV_NAV_LANDING = 6
- MAV_NAV_LOST = 7
- MAV_NAV_LOITER = 8
-
- cmode = (mode, nav_mode)
- mapping = {
- (MAV_MODE_UNINIT, MAV_NAV_GROUNDED) : "INITIALISING",
- (MAV_MODE_MANUAL, MAV_NAV_VECTOR) : "MANUAL",
- (MAV_MODE_TEST3, MAV_NAV_VECTOR) : "CIRCLE",
- (MAV_MODE_GUIDED, MAV_NAV_VECTOR) : "GUIDED",
- (MAV_MODE_TEST1, MAV_NAV_VECTOR) : "STABILIZE",
- (MAV_MODE_TEST2, MAV_NAV_LIFTOFF) : "FBWA",
- (MAV_MODE_AUTO, MAV_NAV_WAYPOINT) : "AUTO",
- (MAV_MODE_AUTO, MAV_NAV_RETURNING) : "RTL",
- (MAV_MODE_AUTO, MAV_NAV_LOITER) : "LOITER",
- (MAV_MODE_AUTO, MAV_NAV_LIFTOFF) : "TAKEOFF",
- (MAV_MODE_AUTO, MAV_NAV_LANDING) : "LANDING",
- (MAV_MODE_AUTO, MAV_NAV_HOLD) : "LOITER",
- (MAV_MODE_GUIDED, MAV_NAV_VECTOR) : "GUIDED",
- (MAV_MODE_GUIDED, MAV_NAV_WAYPOINT) : "GUIDED",
- (100, MAV_NAV_VECTOR) : "STABILIZE",
- (101, MAV_NAV_VECTOR) : "ACRO",
- (102, MAV_NAV_VECTOR) : "ALT_HOLD",
- (107, MAV_NAV_VECTOR) : "CIRCLE",
- (109, MAV_NAV_VECTOR) : "LAND",
- }
- if cmode in mapping:
- return mapping[cmode]
- return "Mode(%s,%s)" % cmode
-
-def mode_string_v10(msg):
- '''mode string for 1.0 protocol, from heartbeat'''
- if not msg.base_mode & mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED:
- return "Mode(0x%08x)" % msg.base_mode
- mapping = {
- 0 : 'MANUAL',
- 1 : 'CIRCLE',
- 2 : 'STABILIZE',
- 5 : 'FBWA',
- 6 : 'FBWB',
- 7 : 'FBWC',
- 10 : 'AUTO',
- 11 : 'RTL',
- 12 : 'LOITER',
- 13 : 'TAKEOFF',
- 14 : 'LAND',
- 15 : 'GUIDED',
- 16 : 'INITIALISING'
- }
- if msg.custom_mode in mapping:
- return mapping[msg.custom_mode]
- return "Mode(%u)" % msg.custom_mode
-
-
-
-class x25crc(object):
- '''x25 CRC - based on checksum.h from mavlink library'''
- def __init__(self, buf=''):
- self.crc = 0xffff
- self.accumulate(buf)
-
- def accumulate(self, buf):
- '''add in some more bytes'''
- bytes = array.array('B')
- if isinstance(buf, array.array):
- bytes.extend(buf)
- else:
- bytes.fromstring(buf)
- accum = self.crc
- for b in bytes:
- tmp = b ^ (accum & 0xff)
- tmp = (tmp ^ (tmp<<4)) & 0xFF
- accum = (accum>>8) ^ (tmp<<8) ^ (tmp<<3) ^ (tmp>>4)
- accum = accum & 0xFFFF
- self.crc = accum
diff --git a/mavlink/share/pyshared/pymavlink/mavwp.py b/mavlink/share/pyshared/pymavlink/mavwp.py
deleted file mode 100644
index 6fd1e10e2..000000000
--- a/mavlink/share/pyshared/pymavlink/mavwp.py
+++ /dev/null
@@ -1,200 +0,0 @@
-'''
-module for loading/saving waypoints
-'''
-
-import os
-
-if os.getenv('MAVLINK10'):
- import mavlinkv10 as mavlink
-else:
- import mavlink
-
-class MAVWPError(Exception):
- '''MAVLink WP error class'''
- def __init__(self, msg):
- Exception.__init__(self, msg)
- self.message = msg
-
-class MAVWPLoader(object):
- '''MAVLink waypoint loader'''
- def __init__(self, target_system=0, target_component=0):
- self.wpoints = []
- self.target_system = target_system
- self.target_component = target_component
-
-
- def count(self):
- '''return number of waypoints'''
- return len(self.wpoints)
-
- def wp(self, i):
- '''return a waypoint'''
- return self.wpoints[i]
-
- def add(self, w):
- '''add a waypoint'''
- w.seq = self.count()
- self.wpoints.append(w)
-
- def remove(self, w):
- '''remove a waypoint'''
- self.wpoints.remove(w)
-
- def clear(self):
- '''clear waypoint list'''
- self.wpoints = []
-
- def _read_waypoint_v100(self, line):
- '''read a version 100 waypoint'''
- cmdmap = {
- 2 : mavlink.MAV_CMD_NAV_TAKEOFF,
- 3 : mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH,
- 4 : mavlink.MAV_CMD_NAV_LAND,
- 24: mavlink.MAV_CMD_NAV_TAKEOFF,
- 26: mavlink.MAV_CMD_NAV_LAND,
- 25: mavlink.MAV_CMD_NAV_WAYPOINT ,
- 27: mavlink.MAV_CMD_NAV_LOITER_UNLIM
- }
- a = line.split()
- if len(a) != 13:
- raise MAVWPError("invalid waypoint line with %u values" % len(a))
- w = mavlink.MAVLink_waypoint_message(self.target_system, self.target_component,
- int(a[0]), # seq
- int(a[1]), # frame
- int(a[2]), # action
- int(a[7]), # current
- int(a[12]), # autocontinue
- float(a[5]), # param1,
- float(a[6]), # param2,
- float(a[3]), # param3
- float(a[4]), # param4
- float(a[9]), # x, latitude
- float(a[8]), # y, longitude
- float(a[10]) # z
- )
- if not w.command in cmdmap:
- raise MAVWPError("Unknown v100 waypoint action %u" % w.command)
-
- w.command = cmdmap[w.command]
- return w
-
- def _read_waypoint_v110(self, line):
- '''read a version 110 waypoint'''
- a = line.split()
- if len(a) != 12:
- raise MAVWPError("invalid waypoint line with %u values" % len(a))
- w = mavlink.MAVLink_waypoint_message(self.target_system, self.target_component,
- int(a[0]), # seq
- int(a[2]), # frame
- int(a[3]), # command
- int(a[1]), # current
- int(a[11]), # autocontinue
- float(a[4]), # param1,
- float(a[5]), # param2,
- float(a[6]), # param3
- float(a[7]), # param4
- float(a[8]), # x (latitude)
- float(a[9]), # y (longitude)
- float(a[10]) # z (altitude)
- )
- return w
-
-
- def load(self, filename):
- '''load waypoints from a file.
- returns number of waypoints loaded'''
- f = open(filename, mode='r')
- version_line = f.readline().strip()
- if version_line == "QGC WPL 100":
- readfn = self._read_waypoint_v100
- elif version_line == "QGC WPL 110":
- readfn = self._read_waypoint_v110
- else:
- f.close()
- raise MAVWPError("Unsupported waypoint format '%s'" % version_line)
-
- self.clear()
-
- for line in f:
- if line.startswith('#'):
- continue
- line = line.strip()
- if not line:
- continue
- w = readfn(line)
- if w is not None:
- self.add(w)
- f.close()
- return len(self.wpoints)
-
-
- def save(self, filename):
- '''save waypoints to a file'''
- f = open(filename, mode='w')
- f.write("QGC WPL 110\n")
- for w in self.wpoints:
- f.write("%u\t%u\t%u\t%u\t%f\t%f\t%f\t%f\t%f\t%f\t%f\t%u\n" % (
- w.seq, w.current, w.frame, w.command,
- w.param1, w.param2, w.param3, w.param4,
- w.x, w.y, w.z, w.autocontinue))
- f.close()
-
-
-class MAVFenceError(Exception):
- '''MAVLink fence error class'''
- def __init__(self, msg):
- Exception.__init__(self, msg)
- self.message = msg
-
-class MAVFenceLoader(object):
- '''MAVLink geo-fence loader'''
- def __init__(self, target_system=0, target_component=0):
- self.points = []
- self.target_system = target_system
- self.target_component = target_component
-
- def count(self):
- '''return number of points'''
- return len(self.points)
-
- def point(self, i):
- '''return a point'''
- return self.points[i]
-
- def add(self, p):
- '''add a point'''
- self.points.append(p)
-
- def clear(self):
- '''clear point list'''
- self.points = []
-
- def load(self, filename):
- '''load points from a file.
- returns number of points loaded'''
- f = open(filename, mode='r')
- self.clear()
- for line in f:
- if line.startswith('#'):
- continue
- line = line.strip()
- if not line:
- continue
- a = line.split()
- if len(a) != 2:
- raise MAVFenceError("invalid fence point line: %s" % line)
- p = mavlink.MAVLink_fence_point_message(self.target_system, self.target_component,
- self.count(), 0, float(a[0]), float(a[1]))
- self.add(p)
- f.close()
- for i in range(self.count()):
- self.points[i].count = self.count()
- return len(self.points)
-
-
- def save(self, filename):
- '''save fence points to a file'''
- f = open(filename, mode='w')
- for p in self.points:
- f.write("%f\t%f\n" % (p.lat, p.lng))
- f.close()
diff --git a/mavlink/share/pyshared/pymavlink/scanwin32.py b/mavlink/share/pyshared/pymavlink/scanwin32.py
deleted file mode 100644
index f90ed5f4d..000000000
--- a/mavlink/share/pyshared/pymavlink/scanwin32.py
+++ /dev/null
@@ -1,236 +0,0 @@
-#!/usr/bin/env python
-
-# this is taken from the pySerial documentation at
-# http://pyserial.sourceforge.net/examples.html
-import ctypes
-import re
-
-def ValidHandle(value):
- if value == 0:
- raise ctypes.WinError()
- return value
-
-NULL = 0
-HDEVINFO = ctypes.c_int
-BOOL = ctypes.c_int
-CHAR = ctypes.c_char
-PCTSTR = ctypes.c_char_p
-HWND = ctypes.c_uint
-DWORD = ctypes.c_ulong
-PDWORD = ctypes.POINTER(DWORD)
-ULONG = ctypes.c_ulong
-ULONG_PTR = ctypes.POINTER(ULONG)
-#~ PBYTE = ctypes.c_char_p
-PBYTE = ctypes.c_void_p
-
-class GUID(ctypes.Structure):
- _fields_ = [
- ('Data1', ctypes.c_ulong),
- ('Data2', ctypes.c_ushort),
- ('Data3', ctypes.c_ushort),
- ('Data4', ctypes.c_ubyte*8),
- ]
- def __str__(self):
- return "{%08x-%04x-%04x-%s-%s}" % (
- self.Data1,
- self.Data2,
- self.Data3,
- ''.join(["%02x" % d for d in self.Data4[:2]]),
- ''.join(["%02x" % d for d in self.Data4[2:]]),
- )
-
-class SP_DEVINFO_DATA(ctypes.Structure):
- _fields_ = [
- ('cbSize', DWORD),
- ('ClassGuid', GUID),
- ('DevInst', DWORD),
- ('Reserved', ULONG_PTR),
- ]
- def __str__(self):
- return "ClassGuid:%s DevInst:%s" % (self.ClassGuid, self.DevInst)
-PSP_DEVINFO_DATA = ctypes.POINTER(SP_DEVINFO_DATA)
-
-class SP_DEVICE_INTERFACE_DATA(ctypes.Structure):
- _fields_ = [
- ('cbSize', DWORD),
- ('InterfaceClassGuid', GUID),
- ('Flags', DWORD),
- ('Reserved', ULONG_PTR),
- ]
- def __str__(self):
- return "InterfaceClassGuid:%s Flags:%s" % (self.InterfaceClassGuid, self.Flags)
-
-PSP_DEVICE_INTERFACE_DATA = ctypes.POINTER(SP_DEVICE_INTERFACE_DATA)
-
-PSP_DEVICE_INTERFACE_DETAIL_DATA = ctypes.c_void_p
-
-class dummy(ctypes.Structure):
- _fields_=[("d1", DWORD), ("d2", CHAR)]
- _pack_ = 1
-SIZEOF_SP_DEVICE_INTERFACE_DETAIL_DATA_A = ctypes.sizeof(dummy)
-
-SetupDiDestroyDeviceInfoList = ctypes.windll.setupapi.SetupDiDestroyDeviceInfoList
-SetupDiDestroyDeviceInfoList.argtypes = [HDEVINFO]
-SetupDiDestroyDeviceInfoList.restype = BOOL
-
-SetupDiGetClassDevs = ctypes.windll.setupapi.SetupDiGetClassDevsA
-SetupDiGetClassDevs.argtypes = [ctypes.POINTER(GUID), PCTSTR, HWND, DWORD]
-SetupDiGetClassDevs.restype = ValidHandle # HDEVINFO
-
-SetupDiEnumDeviceInterfaces = ctypes.windll.setupapi.SetupDiEnumDeviceInterfaces
-SetupDiEnumDeviceInterfaces.argtypes = [HDEVINFO, PSP_DEVINFO_DATA, ctypes.POINTER(GUID), DWORD, PSP_DEVICE_INTERFACE_DATA]
-SetupDiEnumDeviceInterfaces.restype = BOOL
-
-SetupDiGetDeviceInterfaceDetail = ctypes.windll.setupapi.SetupDiGetDeviceInterfaceDetailA
-SetupDiGetDeviceInterfaceDetail.argtypes = [HDEVINFO, PSP_DEVICE_INTERFACE_DATA, PSP_DEVICE_INTERFACE_DETAIL_DATA, DWORD, PDWORD, PSP_DEVINFO_DATA]
-SetupDiGetDeviceInterfaceDetail.restype = BOOL
-
-SetupDiGetDeviceRegistryProperty = ctypes.windll.setupapi.SetupDiGetDeviceRegistryPropertyA
-SetupDiGetDeviceRegistryProperty.argtypes = [HDEVINFO, PSP_DEVINFO_DATA, DWORD, PDWORD, PBYTE, DWORD, PDWORD]
-SetupDiGetDeviceRegistryProperty.restype = BOOL
-
-
-GUID_CLASS_COMPORT = GUID(0x86e0d1e0L, 0x8089, 0x11d0,
- (ctypes.c_ubyte*8)(0x9c, 0xe4, 0x08, 0x00, 0x3e, 0x30, 0x1f, 0x73))
-
-DIGCF_PRESENT = 2
-DIGCF_DEVICEINTERFACE = 16
-INVALID_HANDLE_VALUE = 0
-ERROR_INSUFFICIENT_BUFFER = 122
-SPDRP_HARDWAREID = 1
-SPDRP_FRIENDLYNAME = 12
-SPDRP_LOCATION_INFORMATION = 13
-ERROR_NO_MORE_ITEMS = 259
-
-def comports(available_only=True):
- """This generator scans the device registry for com ports and yields
- (order, port, desc, hwid). If available_only is true only return currently
- existing ports. Order is a helper to get sorted lists. it can be ignored
- otherwise."""
- flags = DIGCF_DEVICEINTERFACE
- if available_only:
- flags |= DIGCF_PRESENT
- g_hdi = SetupDiGetClassDevs(ctypes.byref(GUID_CLASS_COMPORT), None, NULL, flags);
- #~ for i in range(256):
- for dwIndex in range(256):
- did = SP_DEVICE_INTERFACE_DATA()
- did.cbSize = ctypes.sizeof(did)
-
- if not SetupDiEnumDeviceInterfaces(
- g_hdi,
- None,
- ctypes.byref(GUID_CLASS_COMPORT),
- dwIndex,
- ctypes.byref(did)
- ):
- if ctypes.GetLastError() != ERROR_NO_MORE_ITEMS:
- raise ctypes.WinError()
- break
-
- dwNeeded = DWORD()
- # get the size
- if not SetupDiGetDeviceInterfaceDetail(
- g_hdi,
- ctypes.byref(did),
- None, 0, ctypes.byref(dwNeeded),
- None
- ):
- # Ignore ERROR_INSUFFICIENT_BUFFER
- if ctypes.GetLastError() != ERROR_INSUFFICIENT_BUFFER:
- raise ctypes.WinError()
- # allocate buffer
- class SP_DEVICE_INTERFACE_DETAIL_DATA_A(ctypes.Structure):
- _fields_ = [
- ('cbSize', DWORD),
- ('DevicePath', CHAR*(dwNeeded.value - ctypes.sizeof(DWORD))),
- ]
- def __str__(self):
- return "DevicePath:%s" % (self.DevicePath,)
- idd = SP_DEVICE_INTERFACE_DETAIL_DATA_A()
- idd.cbSize = SIZEOF_SP_DEVICE_INTERFACE_DETAIL_DATA_A
- devinfo = SP_DEVINFO_DATA()
- devinfo.cbSize = ctypes.sizeof(devinfo)
- if not SetupDiGetDeviceInterfaceDetail(
- g_hdi,
- ctypes.byref(did),
- ctypes.byref(idd), dwNeeded, None,
- ctypes.byref(devinfo)
- ):
- raise ctypes.WinError()
-
- # hardware ID
- szHardwareID = ctypes.create_string_buffer(250)
- if not SetupDiGetDeviceRegistryProperty(
- g_hdi,
- ctypes.byref(devinfo),
- SPDRP_HARDWAREID,
- None,
- ctypes.byref(szHardwareID), ctypes.sizeof(szHardwareID) - 1,
- None
- ):
- # Ignore ERROR_INSUFFICIENT_BUFFER
- if ctypes.GetLastError() != ERROR_INSUFFICIENT_BUFFER:
- raise ctypes.WinError()
-
- # friendly name
- szFriendlyName = ctypes.create_string_buffer(1024)
- if not SetupDiGetDeviceRegistryProperty(
- g_hdi,
- ctypes.byref(devinfo),
- SPDRP_FRIENDLYNAME,
- None,
- ctypes.byref(szFriendlyName), ctypes.sizeof(szFriendlyName) - 1,
- None
- ):
- # Ignore ERROR_INSUFFICIENT_BUFFER
- if ctypes.GetLastError() != ERROR_INSUFFICIENT_BUFFER:
- #~ raise ctypes.WinError()
- # not getting friendly name for com0com devices, try something else
- szFriendlyName = ctypes.create_string_buffer(1024)
- if SetupDiGetDeviceRegistryProperty(
- g_hdi,
- ctypes.byref(devinfo),
- SPDRP_LOCATION_INFORMATION,
- None,
- ctypes.byref(szFriendlyName), ctypes.sizeof(szFriendlyName) - 1,
- None
- ):
- port_name = "\\\\.\\" + szFriendlyName.value
- order = None
- else:
- port_name = szFriendlyName.value
- order = None
- else:
- try:
- m = re.search(r"\((.*?(\d+))\)", szFriendlyName.value)
- #~ print szFriendlyName.value, m.groups()
- port_name = m.group(1)
- order = int(m.group(2))
- except AttributeError, msg:
- port_name = szFriendlyName.value
- order = None
- yield order, port_name, szFriendlyName.value, szHardwareID.value
-
- SetupDiDestroyDeviceInfoList(g_hdi)
-
-
-if __name__ == '__main__':
- import serial
- print "-"*78
- print "Serial ports"
- print "-"*78
- for order, port, desc, hwid in sorted(comports()):
- print "%-10s: %s (%s) ->" % (port, desc, hwid),
- try:
- serial.Serial(port) # test open
- except serial.serialutil.SerialException:
- print "can't be openend"
- else:
- print "Ready"
- print
- # list of all ports the system knows
- print "-"*78
- print "All serial ports (registry)"
- print "-"*78
- for order, port, desc, hwid in sorted(comports(False)):
- print "%-10s: %s (%s)" % (port, desc, hwid)
diff --git a/mavlink/share/pyshared/pymavlink/tools/images/gtk-quit.gif b/mavlink/share/pyshared/pymavlink/tools/images/gtk-quit.gif
deleted file mode 100644
index 3cce0867b..000000000
--- a/mavlink/share/pyshared/pymavlink/tools/images/gtk-quit.gif
+++ /dev/null
Binary files differ
diff --git a/mavlink/share/pyshared/pymavlink/tools/images/media-playback-pause.gif b/mavlink/share/pyshared/pymavlink/tools/images/media-playback-pause.gif
deleted file mode 100644
index 4dc439b78..000000000
--- a/mavlink/share/pyshared/pymavlink/tools/images/media-playback-pause.gif
+++ /dev/null
Binary files differ
diff --git a/mavlink/share/pyshared/pymavlink/tools/images/media-playback-start.gif b/mavlink/share/pyshared/pymavlink/tools/images/media-playback-start.gif
deleted file mode 100644
index ec4136399..000000000
--- a/mavlink/share/pyshared/pymavlink/tools/images/media-playback-start.gif
+++ /dev/null
Binary files differ
diff --git a/mavlink/share/pyshared/pymavlink/tools/images/media-playback-stop.gif b/mavlink/share/pyshared/pymavlink/tools/images/media-playback-stop.gif
deleted file mode 100644
index 306271a89..000000000
--- a/mavlink/share/pyshared/pymavlink/tools/images/media-playback-stop.gif
+++ /dev/null
Binary files differ
diff --git a/mavlink/share/pyshared/pymavlink/tools/images/media-seek-backward.gif b/mavlink/share/pyshared/pymavlink/tools/images/media-seek-backward.gif
deleted file mode 100644
index 23fcf6d82..000000000
--- a/mavlink/share/pyshared/pymavlink/tools/images/media-seek-backward.gif
+++ /dev/null
Binary files differ
diff --git a/mavlink/share/pyshared/pymavlink/tools/images/media-seek-forward.gif b/mavlink/share/pyshared/pymavlink/tools/images/media-seek-forward.gif
deleted file mode 100644
index 3439c54fd..000000000
--- a/mavlink/share/pyshared/pymavlink/tools/images/media-seek-forward.gif
+++ /dev/null
Binary files differ
diff --git a/mavlink/share/pyshared/pymavlink/tools/images/player_end.gif b/mavlink/share/pyshared/pymavlink/tools/images/player_end.gif
deleted file mode 100644
index 9496957d2..000000000
--- a/mavlink/share/pyshared/pymavlink/tools/images/player_end.gif
+++ /dev/null
Binary files differ
diff --git a/mavlink/share/pyshared/pymavlink/tools/mavplayback.py b/mavlink/share/pyshared/pymavlink/tools/mavplayback.py
deleted file mode 100644
index 033746697..000000000
--- a/mavlink/share/pyshared/pymavlink/tools/mavplayback.py
+++ /dev/null
@@ -1,246 +0,0 @@
-#!/usr/bin/env python
-
-'''
-play back a mavlink log as a FlightGear FG NET stream, and as a
-realtime mavlink stream
-
-Useful for visualising flights
-'''
-
-import sys, time, os, struct
-import Tkinter
-
-# allow import from the parent directory, where mavlink.py is
-sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..'))
-
-import fgFDM
-
-from optparse import OptionParser
-parser = OptionParser("mavplayback.py [options]")
-
-parser.add_option("--planner",dest="planner", action='store_true', help="use planner file format")
-parser.add_option("--condition",dest="condition", default=None, help="select packets by condition")
-parser.add_option("--gpsalt", action='store_true', default=False, help="Use GPS altitude")
-parser.add_option("--mav10", action='store_true', default=False, help="Use MAVLink protocol 1.0")
-parser.add_option("--out", help="MAVLink output port (IP:port)",
- action='append', default=['127.0.0.1:14550'])
-parser.add_option("--fgout", action='append', default=['127.0.0.1:5503'],
- help="flightgear FDM NET output (IP:port)")
-parser.add_option("--baudrate", type='int', default=57600, help='baud rate')
-(opts, args) = parser.parse_args()
-
-if opts.mav10:
- os.environ['MAVLINK10'] = '1'
-import mavutil
-
-if len(args) < 1:
- parser.print_help()
- sys.exit(1)
-
-filename = args[0]
-
-
-def LoadImage(filename):
- '''return an image from the images/ directory'''
- app_dir = os.path.dirname(os.path.realpath(__file__))
- path = os.path.join(app_dir, 'files/images', filename)
- return Tkinter.PhotoImage(file=path)
-
-
-class App():
- def __init__(self, filename):
- self.root = Tkinter.Tk()
-
- self.filesize = os.path.getsize(filename)
- self.filepos = 0.0
-
- self.mlog = mavutil.mavlink_connection(filename, planner_format=opts.planner,
- robust_parsing=True)
- self.mout = []
- for m in opts.out:
- self.mout.append(mavutil.mavlink_connection(m, input=False, baud=opts.baudrate))
-
- self.fgout = []
- for f in opts.fgout:
- self.fgout.append(mavutil.mavudp(f, input=False))
-
- self.fdm = fgFDM.fgFDM()
-
- self.msg = self.mlog.recv_match(condition=opts.condition)
- if self.msg is None:
- sys.exit(1)
- self.last_timestamp = getattr(self.msg, '_timestamp')
-
- self.paused = False
-
- self.topframe = Tkinter.Frame(self.root)
- self.topframe.pack(side=Tkinter.TOP)
-
- self.frame = Tkinter.Frame(self.root)
- self.frame.pack(side=Tkinter.LEFT)
-
- self.slider = Tkinter.Scale(self.topframe, from_=0, to=1.0, resolution=0.01,
- orient=Tkinter.HORIZONTAL, command=self.slew)
- self.slider.pack(side=Tkinter.LEFT)
-
- self.clock = Tkinter.Label(self.topframe,text="")
- self.clock.pack(side=Tkinter.RIGHT)
-
- self.playback = Tkinter.Spinbox(self.topframe, from_=0, to=20, increment=0.1, width=3)
- self.playback.pack(side=Tkinter.BOTTOM)
- self.playback.delete(0, "end")
- self.playback.insert(0, 1)
-
- self.buttons = {}
- self.button('quit', 'gtk-quit.gif', self.frame.quit)
- self.button('pause', 'media-playback-pause.gif', self.pause)
- self.button('rewind', 'media-seek-backward.gif', self.rewind)
- self.button('forward', 'media-seek-forward.gif', self.forward)
- self.button('status', 'Status', self.status)
- self.flightmode = Tkinter.Label(self.frame,text="")
- self.flightmode.pack(side=Tkinter.RIGHT)
-
- self.next_message()
- self.root.mainloop()
-
- def button(self, name, filename, command):
- '''add a button'''
- try:
- img = LoadImage(filename)
- b = Tkinter.Button(self.frame, image=img, command=command)
- b.image = img
- except Exception:
- b = Tkinter.Button(self.frame, text=filename, command=command)
- b.pack(side=Tkinter.LEFT)
- self.buttons[name] = b
-
-
- def pause(self):
- '''pause playback'''
- self.paused = not self.paused
-
- def rewind(self):
- '''rewind 10%'''
- pos = int(self.mlog.f.tell() - 0.1*self.filesize)
- if pos < 0:
- pos = 0
- self.mlog.f.seek(pos)
- self.find_message()
-
- def forward(self):
- '''forward 10%'''
- pos = int(self.mlog.f.tell() + 0.1*self.filesize)
- if pos > self.filesize:
- pos = self.filesize - 2048
- self.mlog.f.seek(pos)
- self.find_message()
-
- def status(self):
- '''show status'''
- for m in sorted(self.mlog.messages.keys()):
- print(str(self.mlog.messages[m]))
-
-
-
- def find_message(self):
- '''find the next valid message'''
- while True:
- self.msg = self.mlog.recv_match(condition=opts.condition)
- if self.msg is not None and self.msg.get_type() != 'BAD_DATA':
- break
- if self.mlog.f.tell() > self.filesize - 10:
- self.paused = True
- break
- self.last_timestamp = getattr(self.msg, '_timestamp')
-
- def slew(self, value):
- '''move to a given position in the file'''
- if float(value) != self.filepos:
- pos = float(value) * self.filesize
- self.mlog.f.seek(int(pos))
- self.find_message()
-
-
- def next_message(self):
- '''called as each msg is ready'''
-
- msg = self.msg
- if msg is None:
- self.paused = True
-
- if self.paused:
- self.root.after(100, self.next_message)
- return
-
- speed = float(self.playback.get())
- timestamp = getattr(msg, '_timestamp')
-
- now = time.strftime("%H:%M:%S", time.localtime(timestamp))
- self.clock.configure(text=now)
-
- if speed == 0.0:
- self.root.after(200, self.next_message)
- else:
- self.root.after(int(1000*(timestamp - self.last_timestamp) / speed), self.next_message)
- self.last_timestamp = timestamp
-
- while True:
- self.msg = self.mlog.recv_match(condition=opts.condition)
- if self.msg is None and self.mlog.f.tell() > self.filesize - 10:
- self.paused = True
- return
- if self.msg is not None and self.msg.get_type() != "BAD_DATA":
- break
-
- pos = float(self.mlog.f.tell()) / self.filesize
- self.slider.set(pos)
- self.filepos = self.slider.get()
-
- if msg.get_type() != "BAD_DATA":
- for m in self.mout:
- m.write(msg.get_msgbuf().tostring())
-
- if msg.get_type() == "GPS_RAW":
- self.fdm.set('latitude', msg.lat, units='degrees')
- self.fdm.set('longitude', msg.lon, units='degrees')
- if opts.gpsalt:
- self.fdm.set('altitude', msg.alt, units='meters')
-
- if msg.get_type() == "VFR_HUD":
- if not opts.gpsalt:
- self.fdm.set('altitude', msg.alt, units='meters')
- self.fdm.set('num_engines', 1)
- self.fdm.set('vcas', msg.airspeed, units='mps')
-
- if msg.get_type() == "ATTITUDE":
- self.fdm.set('phi', msg.roll, units='radians')
- self.fdm.set('theta', msg.pitch, units='radians')
- self.fdm.set('psi', msg.yaw, units='radians')
- self.fdm.set('phidot', msg.rollspeed, units='rps')
- self.fdm.set('thetadot', msg.pitchspeed, units='rps')
- self.fdm.set('psidot', msg.yawspeed, units='rps')
-
- if msg.get_type() == "RC_CHANNELS_SCALED":
- self.fdm.set("right_aileron", msg.chan1_scaled*0.0001)
- self.fdm.set("left_aileron", -msg.chan1_scaled*0.0001)
- self.fdm.set("rudder", msg.chan4_scaled*0.0001)
- self.fdm.set("elevator", msg.chan2_scaled*0.0001)
- self.fdm.set('rpm', msg.chan3_scaled*0.01)
-
- if msg.get_type() == 'STATUSTEXT':
- print("APM: %s" % msg.text)
-
- if msg.get_type() == 'SYS_STATUS':
- self.flightmode.configure(text=self.mlog.flightmode)
-
- if msg.get_type() == "BAD_DATA":
- if mavutil.all_printable(msg.data):
- sys.stdout.write(msg.data)
- sys.stdout.flush()
-
- if self.fdm.get('latitude') != 0:
- for f in self.fgout:
- f.write(self.fdm.pack())
-
-
-app=App(filename)