mavgenerate.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 """\
00003 generate.py is a GUI front-end for mavgen, a python based MAVLink
00004 header generation tool.
00005 
00006 Notes:
00007 -----
00008 * 2012-7-16 -- dagoodman
00009     Working on Mac 10.6.8 darwin, with Python 2.7.1
00010 
00011 * 2012-7-17 -- dagoodman
00012     Only GUI code working on Mac 10.6.8 darwin, with Python 3.2.3
00013     Working on Windows 7 SP1, with Python 2.7.3 and 3.2.3
00014     Mavgen doesn't work with Python 3.x yet
00015 
00016 * 2012-9-25 -- dagoodman
00017     Passing error limit into mavgen to make output cleaner.
00018 
00019 Copyright 2012 David Goodman (dagoodman@soe.ucsc.edu)
00020 Released under GNU GPL version 3 or later
00021 
00022 """
00023 import os
00024 import re
00025 
00026 # Python 2.x and 3.x compatibility
00027 try:
00028     from tkinter import *
00029     import tkinter.filedialog
00030     import tkinter.messagebox
00031 except ImportError as ex:
00032     # Must be using Python 2.x, import and rename
00033     from Tkinter import *
00034     import tkFileDialog
00035     import tkMessageBox
00036 
00037     tkinter.filedialog = tkFileDialog
00038     del tkFileDialog
00039     tkinter.messagebox = tkMessageBox
00040     del tkMessageBox
00041 
00042 from pymavlink.generator import mavgen
00043 from pymavlink.generator import mavparse
00044 
00045 title = "MAVLink Generator"
00046 error_limit = 5
00047 
00048 
00049 class Application(Frame):
00050     def __init__(self, master=None):
00051         Frame.__init__(self, master)
00052         self.pack_propagate(0)
00053         self.grid( sticky=N+S+E+W)
00054         self.createWidgets()
00055 
00056     """\
00057     Creates the gui and all of its content.
00058     """
00059     def createWidgets(self):
00060 
00061 
00062         #----------------------------------------
00063         # Create the XML entry
00064 
00065         self.xml_value = StringVar()
00066         self.xml_label = Label( self, text="XML" )
00067         self.xml_label.grid(row=0, column = 0)
00068         self.xml_entry = Entry( self, width = 26, textvariable=self.xml_value )
00069         self.xml_entry.grid(row=0, column = 1)
00070         self.xml_button = Button (self, text="Browse", command=self.browseXMLFile)
00071         self.xml_button.grid(row=0, column = 2)
00072 
00073         #----------------------------------------
00074         # Create the Out entry
00075 
00076         self.out_value = StringVar()
00077         self.out_label = Label( self, text="Out" )
00078         self.out_label.grid(row=1,column = 0)
00079         self.out_entry = Entry( self, width = 26, textvariable=self.out_value )
00080         self.out_entry.grid(row=1, column = 1)
00081         self.out_button = Button (self, text="Browse", command=self.browseOutDirectory)
00082         self.out_button.grid(row=1, column = 2)
00083 
00084         #----------------------------------------
00085         # Create the Lang box
00086 
00087         self.language_value = StringVar()
00088         self.language_choices = mavgen.supportedLanguages
00089         self.language_label = Label( self, text="Language" )
00090         self.language_label.grid(row=2, column=0)
00091         self.language_menu = OptionMenu(self,self.language_value,*self.language_choices)
00092         self.language_value.set(mavgen.DEFAULT_LANGUAGE)
00093         self.language_menu.config(width=10)
00094         self.language_menu.grid(row=2, column=1,sticky=W)
00095 
00096         #----------------------------------------
00097         # Create the Protocol box
00098 
00099         self.protocol_value = StringVar()
00100         self.protocol_choices = [mavparse.PROTOCOL_1_0, mavparse.PROTOCOL_2_0]
00101         self.protocol_label = Label( self, text="Protocol")
00102         self.protocol_label.grid(row=3, column=0)
00103         self.protocol_menu = OptionMenu(self,self.protocol_value,*self.protocol_choices)
00104         self.protocol_value.set(mavgen.DEFAULT_WIRE_PROTOCOL)
00105         self.protocol_menu.config(width=10)
00106         self.protocol_menu.grid(row=3, column=1,sticky=W)
00107 
00108         #----------------------------------------
00109         # Create the Validate box
00110 
00111         self.validate_value = BooleanVar()
00112         self.validate_label = Label( self, text="Validate")
00113         self.validate_label.grid(row=4, column=0)
00114         self.validate_button = Checkbutton(self, variable=self.validate_value, onvalue=True, offvalue=False)
00115         self.validate_value.set(mavgen.DEFAULT_VALIDATE)
00116         self.validate_button.config(width=10)
00117         self.validate_button.grid(row=4, column=1,sticky=W)
00118 
00119         #----------------------------------------
00120         # Create the generate button
00121 
00122         self.generate_button = Button ( self, text="Generate", command=self.generateHeaders)
00123         self.generate_button.grid(row=5,column=1)
00124 
00125     """\
00126     Open a file selection window to choose the XML message definition.
00127     """
00128     def browseXMLFile(self):
00129         # TODO Allow specification of multiple XML definitions
00130         xml_file = tkinter.filedialog.askopenfilename(parent=self, title='Choose a definition file')
00131         if xml_file != None:
00132             self.xml_value.set(xml_file)
00133 
00134     """\
00135     Open a directory selection window to choose an output directory for
00136     headers.
00137     """
00138     def browseOutDirectory(self):
00139         mavlinkFolder = os.path.dirname(os.path.realpath(__file__))
00140         out_dir = tkinter.filedialog.askdirectory(parent=self,initialdir=mavlinkFolder,title='Please select an output directory')
00141         if out_dir != None:
00142             self.out_value.set(out_dir)
00143 
00144     """\
00145     Generates the header files and place them in the output directory.
00146     """
00147     def generateHeaders(self):
00148         # Verify settings
00149         rex = re.compile(".*\\.xml$", re.IGNORECASE)
00150         if not self.xml_value.get():
00151             tkinter.messagebox.showerror('Error Generating Headers','An XML message definition file must be specified.')
00152             return
00153 
00154         if not self.out_value.get():
00155             tkinter.messagebox.showerror('Error Generating Headers', 'An output directory must be specified.')
00156             return
00157 
00158 
00159         if os.path.isdir(self.out_value.get()):
00160             if not tkinter.messagebox.askokcancel('Overwrite Headers?','The output directory \'{0}\' already exists. Headers may be overwritten if they already exist.'.format(self.out_value.get())):
00161                 return
00162 
00163         # Generate headers
00164         opts = mavgen.Opts(self.out_value.get(), wire_protocol=self.protocol_value.get(), language=self.language_value.get(), validate=self.validate_value.get(), error_limit=error_limit);
00165         args = [self.xml_value.get()]
00166         try:
00167             mavgen.mavgen(opts,args)
00168             tkinter.messagebox.showinfo('Successfully Generated Headers', 'Headers generated successfully.')
00169 
00170         except Exception as ex:
00171             exStr = formatErrorMessage(str(ex));
00172             tkinter.messagebox.showerror('Error Generating Headers','{0!s}'.format(exStr))
00173             return
00174 
00175 """\
00176 Format the mavgen exceptions by removing 'ERROR: '.
00177 """
00178 def formatErrorMessage(message):
00179     reObj = re.compile(r'^(ERROR):\s+',re.M);
00180     matches = re.findall(reObj, message);
00181     prefix = ("An error occurred in mavgen:" if len(matches) == 1 else "Errors occurred in mavgen:\n")
00182     message = re.sub(reObj, '\n', message);
00183 
00184     return prefix + message
00185 
00186 
00187 # End of Application class
00188 # ---------------------------------
00189 
00190 # ---------------------------------
00191 # Start
00192 
00193 if __name__ == '__main__':
00194   app = Application()
00195   app.master.title(title)
00196   app.mainloop()


mavlink
Author(s): Lorenz Meier
autogenerated on Thu Jun 6 2019 19:01:57