00001
00002
00003 import codecs
00004 try:
00005 codecs.lookup('mbcs')
00006 except LookupError:
00007 ascii = codecs.lookup('ascii')
00008 func = lambda name, enc=ascii: {True: enc}.get(name=='mbcs')
00009 codecs.register(func)
00010
00011 from setuptools import setup, Extension
00012 import glob, os, shutil, fnmatch, platform
00013
00014 version = '1.1.73'
00015
00016 from generator import mavgen, mavparse
00017
00018
00019 mdef_path = os.path.join(os.path.dirname(os.path.realpath(__file__)), '..', 'message_definitions')
00020 dialects_path = os.path.join(os.path.dirname(os.path.realpath(__file__)), 'dialects')
00021
00022 v10_dialects = glob.glob(os.path.join(mdef_path, 'v1.0', '*.xml'))
00023
00024
00025 v20_dialects = glob.glob(os.path.join(mdef_path, 'v1.0', '*.xml'))
00026
00027 if not "NOGEN" in os.environ:
00028 for xml in v10_dialects:
00029 shutil.copy(xml, os.path.join(dialects_path, 'v10'))
00030 for xml in v20_dialects:
00031 shutil.copy(xml, os.path.join(dialects_path, 'v20'))
00032
00033 for xml in v10_dialects:
00034 dialect = os.path.basename(xml)[:-4]
00035 wildcard = os.getenv("MAVLINK_DIALECT",'*')
00036 if not fnmatch.fnmatch(dialect, wildcard):
00037 continue
00038 print("Building %s for protocol 1.0" % xml)
00039 mavgen.mavgen_python_dialect(dialect, mavparse.PROTOCOL_1_0)
00040
00041 for xml in v20_dialects:
00042 dialect = os.path.basename(xml)[:-4]
00043 wildcard = os.getenv("MAVLINK_DIALECT",'*')
00044 if not fnmatch.fnmatch(dialect, wildcard):
00045 continue
00046 print("Building %s for protocol 2.0" % xml)
00047 mavgen.mavgen_python_dialect(dialect, mavparse.PROTOCOL_2_0)
00048
00049 extensions = []
00050 if platform.system() != 'Windows':
00051 extensions = [ Extension('mavnative',
00052 sources = ['mavnative/mavnative.c'],
00053 include_dirs = [
00054 'generator/C/include_v1.0',
00055 'generator/C/include_v2.0',
00056 'mavnative'
00057 ]
00058 ) ]
00059 else:
00060 print("Skipping mavnative due to Windows possibly missing a compiler...")
00061
00062 setup (name = 'pymavlink',
00063 version = version,
00064 description = 'Python MAVLink code',
00065 long_description = '''A Python library for handling MAVLink protocol streams and log files. This allows for the creation of simple scripts to analyse telemetry logs from autopilots such as ArduPilot which use the MAVLink protocol. See the scripts that come with the package for examples of small, useful scripts that use pymavlink. For more information about the MAVLink protocol see http://qgroundcontrol.org/mavlink/''',
00066 url = 'http://github.com/mavlink/mavlink',
00067 classifiers=['Development Status :: 4 - Beta',
00068 'Environment :: Console',
00069 'Intended Audience :: Science/Research',
00070 'License :: OSI Approved :: GNU Lesser General Public License v3 (LGPLv3)',
00071 'Operating System :: OS Independent',
00072 'Programming Language :: Python :: 2.7',
00073 'Topic :: Scientific/Engineering'
00074 ],
00075 license='LGPLv3',
00076 package_dir = { 'pymavlink' : '.' },
00077 package_data = { 'pymavlink.dialects.v10' : ['*.xml'],
00078 'pymavlink.dialects.v20' : ['*.xml'],
00079 'pymavlink.generator' : [ '*.xsd',
00080 'java/lib/*.*',
00081 'java/lib/Messages/*.*',
00082 'C/include_v1.0/*.h',
00083 'C/include_v1.0/*.hpp',
00084 'C/include_v2.0/*.h',
00085 'C/include_v2.0/*.hpp' ],
00086 'pymavlink.generator.lib.minixsv': [ '*.xsd' ],
00087 'pymavlink' : ['mavnative/*.h'] },
00088 packages = ['pymavlink',
00089 'pymavlink.generator',
00090 'pymavlink.generator.lib',
00091 'pymavlink.generator.lib.genxmlif',
00092 'pymavlink.generator.lib.minixsv',
00093 'pymavlink.dialects',
00094 'pymavlink.dialects.v10',
00095 'pymavlink.dialects.v20'],
00096 scripts = [ 'tools/magfit_delta.py', 'tools/mavextract.py',
00097 'tools/mavgraph.py', 'tools/mavparmdiff.py',
00098 'tools/mavtogpx.py', 'tools/magfit_gps.py',
00099 'tools/mavflightmodes.py', 'tools/mavlogdump.py',
00100 'tools/mavparms.py', 'tools/magfit_motors.py',
00101 'tools/mavflighttime.py', 'tools/mavloss.py',
00102 'tools/mavplayback.py', 'tools/magfit.py',
00103 'tools/mavgpslock.py',
00104 'tools/mavmission.py',
00105 'tools/mavsigloss.py',
00106 'tools/mavsearch.py',
00107 'tools/mavtomfile.py',
00108 'tools/mavgen.py',
00109 'tools/mavkml.py',
00110 'tools/mavfft.py',
00111 'tools/mavsummarize.py',
00112 'tools/MPU6KSearch.py'],
00113 ext_modules = extensions
00114 )