Пример #1
0
def init(_mpstate):
    '''initialise module'''
    global mpstate
    mpstate = _mpstate
    mpstate.console_state = module_state()
    mpstate.console = wxconsole.MessageConsole(title='Console')

    # setup some default status information
    mpstate.console.set_status('Mode', 'UNKNOWN', row=0, fg='blue')
    mpstate.console.set_status('GPS', 'GPS: --', fg='red', row=0)
    mpstate.console.set_status('Vcc', 'Vcc: --', fg='red', row=0)
    mpstate.console.set_status('Radio', 'Radio: --', row=0)
    mpstate.console.set_status('Heading', 'Hdg ---/---', row=2)
    mpstate.console.set_status('Alt', 'Alt ---', row=2)
    mpstate.console.set_status('AGL', 'AGL ---', row=2)
    mpstate.console.set_status('AirSpeed', 'AirSpeed --', row=2)
    mpstate.console.set_status('GPSSpeed', 'GPSSpeed --', row=2)
    mpstate.console.set_status('Thr', 'Thr ---', row=2)
    mpstate.console.set_status('Roll', 'Roll ---', row=2)
    mpstate.console.set_status('Pitch', 'Pitch ---', row=2)
    mpstate.console.set_status('WP', 'WP --', row=3)
    mpstate.console.set_status('WPDist', 'Distance ---', row=3)
    mpstate.console.set_status('WPBearing', 'Bearing ---', row=3)
    mpstate.console.set_status('AltError', 'AltError --', row=3)
    mpstate.console.set_status('AspdError', 'AspdError --', row=3)
    mpstate.console.set_status('FlightTime', 'FlightTime --', row=3)
    mpstate.console.set_status('ETR', 'ETR --', row=3)

    mpstate.console.ElevationMap = mp_elevation.ElevationModel()
Пример #2
0
    def __init__(self, mpstate):
        super(MapModule, self).__init__(mpstate,
                                        "map",
                                        "map display",
                                        public=True)
        self.lat = None
        self.lon = None
        self.heading = 0
        self.wp_change_time = 0
        self.fence_change_time = 0
        self.rally_change_time = 0
        self.have_simstate = False
        self.have_vehicle = {}
        self.move_wp = -1
        self.moving_wp = None
        self.moving_fencepoint = None
        self.moving_rally = None
        self.mission_list = None
        self.icon_counter = 0
        self.click_position = None
        self.click_time = 0
        self.draw_line = None
        self.draw_callback = None
        self.have_global_position = False
        self.vehicle_type_name = 'plane'
        self.ElevationMap = mp_elevation.ElevationModel()
        self.map_settings = mp_settings.MPSettings([
            ('showgpspos', int, 0), ('showgps2pos', int, 1),
            ('showsimpos', int, 0), ('showahrs2pos', int, 0),
            ('brightness', float, 1), ('rallycircle', bool, False),
            ('loitercircle', bool, False)
        ])
        service = 'OviHybrid'
        if 'MAP_SERVICE' in os.environ:
            service = os.environ['MAP_SERVICE']
        import platform
        mpstate.map = mp_slipmap.MPSlipMap(service=service,
                                           elevation=True,
                                           title='Map')
        mpstate.map_functions = {'draw_lines': self.draw_lines}

        mpstate.map.add_callback(functools.partial(self.map_callback))
        self.add_command('map', self.cmd_map, "map control",
                         ['icon', 'set (MAPSETTING)'])
        self.add_completion_function('(MAPSETTING)',
                                     self.map_settings.completion)

        self.default_popup = MPMenuSubMenu('Popup', items=[])
        self.add_menu(
            MPMenuItem('Fly To',
                       'Fly To',
                       '# guided ',
                       handler=MPMenuCallTextDialog(title='Altitude (m)',
                                                    default=100)))
        self.add_menu(MPMenuItem('Set Home', 'Set Home', '# map sethome '))
        self.add_menu(
            MPMenuItem('Terrain Check', 'Terrain Check', '# terrain check'))
        self.add_menu(
            MPMenuItem('Show Position', 'Show Position', 'showPosition'))
Пример #3
0
    def __init__(self, parent, state):
        from MAVProxy.modules.lib import mp_widgets

        wx.Panel.__init__(self, parent)
        self.state = state
        self.img = None
        self.map_img = None
        self.redraw_timer = wx.Timer(self)
        self.Bind(wx.EVT_TIMER, self.on_redraw_timer, self.redraw_timer)
        self.Bind(wx.EVT_SET_FOCUS, self.on_focus)
        self.redraw_timer.Start(200)
        self.mouse_pos = None
        self.mouse_down = None
        self.click_pos = None
        self.last_click_pos = None
        if state.elevation:
            self.ElevationMap = mp_elevation.ElevationModel()

        self.mainSizer = wx.BoxSizer(wx.VERTICAL)
        self.SetSizer(self.mainSizer)

        # display for lat/lon/elevation
        self.position = wx.TextCtrl(self, style=wx.TE_MULTILINE|wx.TE_READONLY)
        if os.name == 'nt':
            self.position.SetValue("line 1\nline 2\n")
            size = self.position.GetBestSize()
            self.position.SetMinSize(size)
            self.position.SetValue("")
        else:
            textsize = tuple(self.position.GetFullTextExtent('line 1\nline 2\n')[0:2])
            self.position.SetMinSize(textsize)

        self.mainSizer.AddSpacer(2)
        self.mainSizer.Add(self.position, flag=wx.LEFT | wx.BOTTOM | wx.GROW, border=0)
        self.position.Bind(wx.EVT_SET_FOCUS, self.on_focus)

        # a place to put control flags
        self.controls = wx.BoxSizer(wx.HORIZONTAL)
        self.mainSizer.Add(self.controls, 0, flag=wx.ALIGN_LEFT | wx.TOP | wx.GROW)
        self.mainSizer.AddSpacer(2)

        # a place to put information like image details
        self.information = wx.BoxSizer(wx.HORIZONTAL)
        self.mainSizer.Add(self.information, 0, flag=wx.ALIGN_LEFT | wx.TOP | wx.GROW)
        self.mainSizer.AddSpacer(2)

        # panel for the main map image
        self.imagePanel = mp_widgets.ImagePanel(self, np.zeros((state.height, state.width, 3), dtype=np.uint8))
        self.mainSizer.Add(self.imagePanel, flag=wx.GROW, border=5)
        self.imagePanel.Bind(wx.EVT_MOUSE_EVENTS, self.on_mouse)
        self.imagePanel.Bind(wx.EVT_KEY_DOWN, self.on_key_down)
        self.imagePanel.Bind(wx.EVT_MOUSEWHEEL, self.on_mouse_wheel)

        # a function to convert from (lat,lon) to (px,py) on the map
        self.pixmapper = functools.partial(self.pixel_coords)

        self.last_view = None
        self.redraw_map()
        state.frame.Fit()
Пример #4
0
def get_ground_alt(lat, lon):
        '''get terrain height at a location'''
        global ElevationMap
        if ElevationMap is None:
                ElevationMap = mp_elevation.ElevationModel()
        if not ElevationMap:
                return 0
        return ElevationMap.GetElevation(lat, lon)
Пример #5
0
    def __init__(self, mpstate):
        super(ConsoleModule, self).__init__(mpstate, "console", "GUI console", public=True, multi_vehicle=True)
        self.in_air = False
        self.start_time = 0.0
        self.total_time = 0.0
        self.speed = 0
        self.max_link_num = 0
        self.last_sys_status_health = 0
        mpstate.console = wxconsole.MessageConsole(title='Console')

        # setup some default status information
        mpstate.console.set_status('Mode', 'UNKNOWN', row=0, fg='blue')
        mpstate.console.set_status('SysID', '', row=0, fg='blue')
        mpstate.console.set_status('ARM', 'ARM', fg='grey', row=0)
        mpstate.console.set_status('GPS', 'GPS: --', fg='red', row=0)
        mpstate.console.set_status('Vcc', 'Vcc: --', fg='red', row=0)
        mpstate.console.set_status('Radio', 'Radio: --', row=0)
        mpstate.console.set_status('INS', 'INS', fg='grey', row=0)
        mpstate.console.set_status('MAG', 'MAG', fg='grey', row=0)
        mpstate.console.set_status('AS', 'AS', fg='grey', row=0)
        mpstate.console.set_status('RNG', 'RNG', fg='grey', row=0)
        mpstate.console.set_status('AHRS', 'AHRS', fg='grey', row=0)
        mpstate.console.set_status('EKF', 'EKF', fg='grey', row=0)
        mpstate.console.set_status('LOG', 'LOG', fg='grey', row=0)
        mpstate.console.set_status('Heading', 'Hdg ---/---', row=2)
        mpstate.console.set_status('Alt', 'Alt ---', row=2)
        mpstate.console.set_status('AGL', 'AGL ---/---', row=2)
        mpstate.console.set_status('AirSpeed', 'AirSpeed --', row=2)
        mpstate.console.set_status('GPSSpeed', 'GPSSpeed --', row=2)
        mpstate.console.set_status('Thr', 'Thr ---', row=2)
        mpstate.console.set_status('Roll', 'Roll ---', row=2)
        mpstate.console.set_status('Pitch', 'Pitch ---', row=2)
        mpstate.console.set_status('Wind', 'Wind ---/---', row=2)
        mpstate.console.set_status('WP', 'WP --', row=3)
        mpstate.console.set_status('WPDist', 'Distance ---', row=3)
        mpstate.console.set_status('WPBearing', 'Bearing ---', row=3)
        mpstate.console.set_status('AltError', 'AltError --', row=3)
        mpstate.console.set_status('AspdError', 'AspdError --', row=3)
        mpstate.console.set_status('FlightTime', 'FlightTime --', row=3)
        mpstate.console.set_status('ETR', 'ETR --', row=3)

        mpstate.console.ElevationMap = mp_elevation.ElevationModel()

        self.vehicle_list = []
        self.vehicle_menu = None
        self.vehicle_name_by_sysid = {}
        self.component_name = {}
        self.last_param_sysid_timestamp = None

        # create the main menu
        if mp_util.has_wxpython:
            self.menu = MPMenuTop([])
            self.add_menu(MPMenuSubMenu('MAVProxy',
                                        items=[MPMenuItem('Settings', 'Settings', 'menuSettings'),
                                               MPMenuItem('Map', 'Load Map', '# module load map')]))
            self.vehicle_menu = MPMenuSubMenu('Vehicle', items=[])
            self.add_menu(self.vehicle_menu)
    def __init__(self, mpstate):
        super(ConsoleModule, self).__init__(mpstate,
                                            "console",
                                            "GUI console",
                                            public=True)
        self.in_air = False
        self.start_time = 0.0
        self.total_time = 0.0
        self.speed = 0
        self.max_link_num = 0
        mpstate.console = wxconsole.MessageConsole(title='Console')

        # setup some default status information
        mpstate.console.set_status('Mode', 'UNKNOWN', row=0, fg='blue')
        mpstate.console.set_status('GPS', 'GPS: --', fg='red', row=0)
        mpstate.console.set_status('Vcc', 'Vcc: --', fg='red', row=0)
        mpstate.console.set_status('Radio', 'Radio: --', row=0)
        mpstate.console.set_status('INS', 'INS', fg='grey', row=0)
        mpstate.console.set_status('MAG', 'MAG', fg='grey', row=0)
        mpstate.console.set_status('AS', 'AS', fg='grey', row=0)
        mpstate.console.set_status('RNG', 'RNG', fg='grey', row=0)
        mpstate.console.set_status('AHRS', 'AHRS', fg='grey', row=0)
        mpstate.console.set_status('Heading', 'Hdg ---/---', row=2)
        mpstate.console.set_status('Alt', 'Alt ---', row=2)
        mpstate.console.set_status('AGL', 'AGL ---/---', row=2)
        mpstate.console.set_status('AirSpeed', 'AirSpeed --', row=2)
        mpstate.console.set_status('GPSSpeed', 'GPSSpeed --', row=2)
        mpstate.console.set_status('Thr', 'Thr ---', row=2)
        mpstate.console.set_status('Roll', 'Roll ---', row=2)
        mpstate.console.set_status('Pitch', 'Pitch ---', row=2)
        mpstate.console.set_status('Wind', 'Wind ---/---', row=2)
        mpstate.console.set_status('WP', 'WP --', row=3)
        mpstate.console.set_status('WPDist', 'Distance ---', row=3)
        mpstate.console.set_status('WPBearing', 'Bearing ---', row=3)
        mpstate.console.set_status('AltError', 'AltError --', row=3)
        mpstate.console.set_status('AspdError', 'AspdError --', row=3)
        mpstate.console.set_status('FlightTime', 'FlightTime --', row=3)
        mpstate.console.set_status('ETR', 'ETR --', row=3)

        mpstate.console.ElevationMap = mp_elevation.ElevationModel()

        # create the main menu
        self.menu = MPMenuTop([])
        self.add_menu(
            MPMenuSubMenu('MAVProxy',
                          items=[
                              MPMenuItem('Settings', 'Settings',
                                         'menuSettings'),
                              MPMenuItem('Map', 'Load Map',
                                         '# module load map')
                          ]))
Пример #7
0
 def __init__(self, filename):
     from MAVProxy.modules.mavproxy_map import mp_elevation
     f = open(filename)
     lines = f.readlines()
     f.close()
     self.positions = []
     self.columns = lines[0].rstrip().split(' ')
     self.colmap = {}
     self.time_offset = None
     self.ElevationMap = mp_elevation.ElevationModel()
     for i in range(len(self.columns)):
         self.colmap[self.columns[i]] = i
     for i in range(1, len(lines)):
         self._parse_line(lines[i].rstrip())
    def __init__(self, mpstate):
        super(TerrainModule, self).__init__(mpstate, "terrain", "terrain handling", public=False)

        self.ElevationModel = mp_elevation.ElevationModel()
        self.current_request = None
        self.sent_mask = 0
        self.last_send_time = time.time()
        self.requests_received = 0
        self.blocks_sent = 0
        self.check_lat = 0
        self.check_lon = 0
        self.add_command('terrain', self.cmd_terrain, "terrain control",
                         ["<status|check>",
                          'set (TERRAINSETTING)'])
        self.terrain_settings = mp_settings.MPSettings(
            [ ('debug', int, 0) ]
            )
        self.add_completion_function('(TERRAINSETTING)', self.terrain_settings.completion)
Пример #9
0
 def __init__(self, mpstate):
     super(CameraViewModule, self).__init__(mpstate, "cameraview")
     self.add_command('cameraview', self.cmd_cameraview, "camera view")
     self.roll = 0
     self.pitch = 0
     self.yaw = 0
     self.mount_roll = 0
     self.mount_pitch = 0
     self.mount_yaw = 0
     self.height = 0
     self.lat = 0
     self.lon = 0
     self.home_height = 0
     self.hdg = 0
     self.elevation_model = mp_elevation.ElevationModel()
     self.camera_params = CameraParams() # TODO how to get actual camera params
     self.view_settings = mp_settings.MPSettings(
         [ ('r', float, 0.5),
           ('g', float, 0.5),
           ('b', float, 1.0),
         ])
     self.update_col()
Пример #10
0
    def __init__(self, mpstate):
        super(MDlinkModule, self).__init__(mpstate,
                                           "mdlink",
                                           "GUI mdlink",
                                           public=True)
        self.in_air = False
        self.start_time = 0.0
        self.total_time = 0.0
        self.speed = 0
        self.max_link_num = 0
        mpstate.mdlink = wxconsole.MessageConsole(title='MDlink')

        #========================================================================
        self.MissionDirector_time_between_hbs = 1
        self.MissionDirector_time_of_last_hb = -100

        self.current_wp = 0
        self.wp_to_loiter_at = 3
        self.loiter_command_given = 0
        self.time_when_loiter_given = 0.0
        self.time_to_loiter_until_returning_home = 60.0
        self.return_home_command_given = 0
        #========================================================================

        # setup some default status information
        mpstate.mdlink.set_status('Mode', 'UNKNOWN', row=0, fg='blue')
        mpstate.mdlink.set_status('GPS', 'GPS: --', fg='red', row=0)
        mpstate.mdlink.set_status('Vcc', 'Vcc: --', fg='red', row=0)
        mpstate.mdlink.set_status('Radio', 'Radio: --', row=0)
        mpstate.mdlink.set_status('INS', 'INS', fg='grey', row=0)
        mpstate.mdlink.set_status('MAG', 'MAG', fg='grey', row=0)
        mpstate.mdlink.set_status('AS', 'AS', fg='grey', row=0)
        mpstate.mdlink.set_status('RNG', 'RNG', fg='grey', row=0)
        mpstate.mdlink.set_status('AHRS', 'AHRS', fg='grey', row=0)
        mpstate.mdlink.set_status('Heading', 'Hdg ---/---', row=2)
        mpstate.mdlink.set_status('Alt', 'Alt ---', row=2)
        mpstate.mdlink.set_status('AGL', 'AGL ---/---', row=2)
        mpstate.mdlink.set_status('AirSpeed', 'AirSpeed --', row=2)
        mpstate.mdlink.set_status('GPSSpeed', 'GPSSpeed --', row=2)
        mpstate.mdlink.set_status('Thr', 'Thr ---', row=2)
        mpstate.mdlink.set_status('Roll', 'Roll ---', row=2)
        mpstate.mdlink.set_status('Pitch', 'Pitch ---', row=2)
        mpstate.mdlink.set_status('Wind', 'Wind ---/---', row=2)
        mpstate.mdlink.set_status('WP', 'WP --', row=3)
        mpstate.mdlink.set_status('WPDist', 'Distance ---', row=3)
        mpstate.mdlink.set_status('WPBearing', 'Bearing ---', row=3)
        mpstate.mdlink.set_status('AltError', 'AltError --', row=3)
        mpstate.mdlink.set_status('AspdError', 'AspdError --', row=3)
        mpstate.mdlink.set_status('FlightTime', 'FlightTime --', row=3)
        mpstate.mdlink.set_status('ETR', 'ETR --', row=3)

        mpstate.mdlink.ElevationMap = mp_elevation.ElevationModel()

        # create the main menu
        self.menu = MPMenuTop([])
        self.add_menu(
            MPMenuSubMenu('MAVProxy',
                          items=[
                              MPMenuItem('Settings', 'Settings',
                                         'menuSettings'),
                              MPMenuItem('Map', 'Load Map',
                                         '# module load map')
                          ]))
Пример #11
0
    def __init__(self, mpstate):
        super(MapModule, self).__init__(mpstate,
                                        "map",
                                        "map display",
                                        public=True,
                                        multi_instance=True,
                                        multi_vehicle=True)
        cmdname = "map"
        if self.instance > 1:
            cmdname += "%u" % self.instance
        # lat/lon per system ID
        self.lat_lon = {}
        self.wp_change_time = 0
        self.fence_change_time = 0
        self.rally_change_time = 0
        self.have_simstate = False
        self.have_vehicle = {}
        self.move_wp = -1
        self.moving_wp = None
        self.moving_fencepoint = None
        self.moving_rally = None
        self.mission_list = None
        self.icon_counter = 0
        self.circle_counter = 0
        self.draw_line = None
        self.draw_callback = None
        self.have_global_position = False
        self.vehicle_type_by_sysid = {}
        self.vehicle_type_name = 'plane'
        self.ElevationMap = mp_elevation.ElevationModel()
        self.last_unload_check_time = time.time()
        self.unload_check_interval = 0.1  # seconds
        self.trajectory_layers = set()
        self.map_settings = mp_settings.MPSettings([
            ('showgpspos', int, 1), ('showgps2pos', int, 1),
            ('showsimpos', int, 0), ('showahrspos', int, 1),
            ('showahrs2pos', int, 0), ('showahrs3pos', int, 0),
            ('brightness', float, 1), ('rallycircle', bool, False),
            ('loitercircle', bool, False), ('showclicktime', int, 2),
            ('showdirection', bool, False)
        ])

        service = 'MicrosoftHyb'
        if 'MAP_SERVICE' in os.environ:
            service = os.environ['MAP_SERVICE']
        import platform
        from MAVProxy.modules.mavproxy_map import mp_slipmap
        title = "Map"
        if self.instance > 1:
            title += str(self.instance)
        self.map = mp_slipmap.MPSlipMap(service=service,
                                        elevation=True,
                                        title=title)
        if self.instance == 1:
            self.mpstate.map = self.map
            mpstate.map_functions = {'draw_lines': self.draw_lines}

        self.map.add_callback(functools.partial(self.map_callback))
        self.add_command(
            cmdname, self.cmd_map, "map control",
            ['icon', 'set (MAPSETTING)', 'zoom', 'center', 'follow', 'clear'])
        self.add_completion_function('(MAPSETTING)',
                                     self.map_settings.completion)

        self.default_popup = MPMenuSubMenu('Popup', items=[])
        self.add_menu(
            MPMenuItem('Fly To',
                       'Fly To',
                       '# guided ',
                       handler=MPMenuCallTextDialog(
                           title='Altitude (m)',
                           default=self.mpstate.settings.guidedalt)))
        self.add_menu(MPMenuItem('Set Home', 'Set Home', '# map sethomepos '))
        self.add_menu(
            MPMenuItem('Set Home (with height)', 'Set Home', '# map sethome '))
        self.add_menu(
            MPMenuItem('Set Origin', 'Set Origin', '# map setoriginpos '))
        self.add_menu(
            MPMenuItem('Set Origin (with height)', 'Set Origin',
                       '# map setorigin '))
        self.add_menu(
            MPMenuItem('Terrain Check', 'Terrain Check', '# terrain check'))
        self.add_menu(
            MPMenuItem('Show Position', 'Show Position', 'showPosition'))

        self._colour_for_wp_command = {
            # takeoff commands
            mavutil.mavlink.MAV_CMD_NAV_TAKEOFF: (255, 0, 0),
            mavutil.mavlink.MAV_CMD_NAV_TAKEOFF_LOCAL: (255, 0, 0),
            mavutil.mavlink.MAV_CMD_NAV_VTOL_TAKEOFF: (255, 0, 0),

            # land commands
            mavutil.mavlink.MAV_CMD_NAV_LAND_LOCAL: (255, 255, 0),
            mavutil.mavlink.MAV_CMD_NAV_LAND: (255, 255, 0),
            mavutil.mavlink.MAV_CMD_NAV_VTOL_LAND: (255, 255, 0),

            # waypoint commands
            mavutil.mavlink.MAV_CMD_NAV_WAYPOINT: (0, 255, 255),
            mavutil.mavlink.MAV_CMD_NAV_SPLINE_WAYPOINT: (64, 255, 64),

            # other commands
            mavutil.mavlink.MAV_CMD_DO_LAND_START: (255, 127, 0),
        }
        self._label_suffix_for_wp_command = {
            mavutil.mavlink.MAV_CMD_NAV_TAKEOFF: "TOff",
            mavutil.mavlink.MAV_CMD_DO_LAND_START: "DLS",
            mavutil.mavlink.MAV_CMD_NAV_SPLINE_WAYPOINT: "SW",
            mavutil.mavlink.MAV_CMD_NAV_VTOL_LAND: "VL",
        }
                      help="start latitude")
    parser.add_option("--lon",
                      type='float',
                      default=149.509165,
                      help="start longitude")
    parser.add_option("--database",
                      type='string',
                      default='srtm',
                      help="elevation database")
    parser.add_option("--debug", action='store_true', help="enabled debugging")
    parser.add_option("--step", type='float', default=0.001)
    parser.add_option("--numsteps", type='int', default=1000)

    (opts, args) = parser.parse_args()

    EleModel = mp_elevation.ElevationModel(opts.database, debug=opts.debug)

    lat = opts.lat
    lon = opts.lon

    xdata = []
    ydata = []

    for x in range(opts.numsteps):
        xdata.append(lon)
        alt = EleModel.GetElevation(lat, lon, timeout=10)
        ydata.append(alt)
        if alt is None:
            print("Tile not available")
            sys.exit(1)
        lon += opts.step
Пример #13
0
    def __init__(self, state, *args, **kwds):
        # begin wxGlade: MissionEditorFrame.__init__
        self.state = state
        kwds["style"] = wx.DEFAULT_FRAME_STYLE
        wx.Frame.__init__(self, *args, **kwds)
        self.label_sync_state = wx.StaticText(self,
                                              wx.ID_ANY,
                                              "UNSYNCED   \n",
                                              style=wx.ALIGN_CENTRE)
        self.label_wp_radius = wx.StaticText(self, wx.ID_ANY, "WP Radius")
        self.text_ctrl_wp_radius = wx.TextCtrl(self,
                                               wx.ID_ANY,
                                               "",
                                               style=wx.TE_PROCESS_ENTER
                                               | wx.TE_PROCESS_TAB)
        self.label_loiter_rad = wx.StaticText(self, wx.ID_ANY, "Loiter Radius")
        self.text_ctrl_loiter_radius = wx.TextCtrl(self,
                                                   wx.ID_ANY,
                                                   "",
                                                   style=wx.TE_PROCESS_ENTER
                                                   | wx.TE_PROCESS_TAB)
        self.checkbox_loiter_dir = wx.CheckBox(self, wx.ID_ANY, "CW")
        self.checkbox_agl = wx.CheckBox(self, wx.ID_ANY, "AGL")
        self.label_default_alt = wx.StaticText(self, wx.ID_ANY, "Default Alt")
        self.text_ctrl_wp_default_alt = wx.TextCtrl(self,
                                                    wx.ID_ANY,
                                                    "",
                                                    style=wx.TE_PROCESS_ENTER
                                                    | wx.TE_PROCESS_TAB)
        self.label_home_location = wx.StaticText(self, wx.ID_ANY,
                                                 "Home Location")
        self.label_home_lat = wx.StaticText(self, wx.ID_ANY, "Lat")
        self.label_home_lat_value = wx.StaticText(self, wx.ID_ANY, "0.0")
        self.label_home_lon = wx.StaticText(self, wx.ID_ANY, "Lon")
        self.label_home_lon_value = wx.StaticText(self, wx.ID_ANY, "0.0")
        self.label_home_alt = wx.StaticText(self, wx.ID_ANY, "Alt (abs)")
        self.label_home_alt_value = wx.StaticText(self, wx.ID_ANY, "0.0")
        self.button_read_wps = wx.Button(self, wx.ID_ANY, "Read WPs")
        self.button_write_wps = wx.Button(self, wx.ID_ANY, "Write WPs")
        self.button_load_wp_file = wx.Button(self, wx.ID_ANY, "Load WP File")
        self.button_save_wp_file = wx.Button(self, wx.ID_ANY, "Save WP File")
        self.grid_mission = wx.grid.Grid(self, wx.ID_ANY, size=(1, 1))
        self.button_add_wp = wx.Button(self, wx.ID_ANY, "Add Below")
        self.button_split = wx.Button(self, wx.ID_ANY, "Split")

        self.__set_properties()
        self.__do_layout()

        self.ElevationModel = mp_elevation.ElevationModel()

        self.Bind(wx.EVT_TEXT_ENTER, self.on_wp_radius_enter,
                  self.text_ctrl_wp_radius)
        self.Bind(wx.EVT_TEXT, self.on_wp_radius_changed,
                  self.text_ctrl_wp_radius)
        self.Bind(wx.EVT_TEXT_ENTER, self.on_loiter_rad_enter,
                  self.text_ctrl_loiter_radius)
        self.Bind(wx.EVT_TEXT, self.on_loiter_rad_change,
                  self.text_ctrl_loiter_radius)
        self.Bind(wx.EVT_CHECKBOX, self.on_loiter_dir_cb_change,
                  self.checkbox_loiter_dir)
        self.Bind(wx.EVT_TEXT_ENTER, self.on_wp_default_alt_enter,
                  self.text_ctrl_wp_default_alt)
        self.Bind(wx.EVT_TEXT, self.on_wp_default_alt_change,
                  self.text_ctrl_wp_default_alt)
        self.Bind(wx.EVT_BUTTON, self.read_wp_pushed, self.button_read_wps)
        self.Bind(wx.EVT_BUTTON, self.write_wp_pushed, self.button_write_wps)
        self.Bind(wx.EVT_BUTTON, self.load_wp_file_pushed,
                  self.button_load_wp_file)
        self.Bind(wx.EVT_BUTTON, self.save_wp_file_pushed,
                  self.button_save_wp_file)
        self.Bind(wx.grid.EVT_GRID_CMD_CELL_CHANGED,
                  self.on_mission_grid_cell_changed, self.grid_mission)
        self.Bind(wx.grid.EVT_GRID_CMD_CELL_LEFT_CLICK,
                  self.on_mission_grid_cell_left_click, self.grid_mission)
        self.Bind(wx.grid.EVT_GRID_CMD_SELECT_CELL,
                  self.on_mission_grid_cell_select, self.grid_mission)
        self.Bind(wx.EVT_BUTTON, self.add_wp_below_pushed, self.button_add_wp)
        self.Bind(wx.EVT_BUTTON, self.split_pushed, self.button_split)
        # end wxGlade

        #use a timer to facilitate event an event handlers for events
        #passed from another process.
        self.timer = wx.Timer(self)
        self.Bind(wx.EVT_TIMER, self.time_to_process_gui_events, self.timer)
        self.timer.Start(200)

        self.last_layout_send = time.time()
        self.Bind(wx.EVT_IDLE, self.on_idle)

        delete_br = button_renderer.ButtonRenderer("Delete", 70, 20)
        up_br = button_renderer.ButtonRenderer("+", 20, 20)
        down_br = button_renderer.ButtonRenderer("-", 1, 1)

        self.del_attr = wx.grid.GridCellAttr()
        self.del_attr.SetReadOnly(True)
        self.del_attr.SetRenderer(delete_br)

        self.up_attr = wx.grid.GridCellAttr()
        self.up_attr.SetReadOnly(True)
        self.up_attr.SetRenderer(up_br)

        self.down_attr = wx.grid.GridCellAttr()
        self.down_attr.SetReadOnly(True)
        self.down_attr.SetRenderer(down_br)
        self.read_only_attr = wx.grid.GridCellAttr()
        self.read_only_attr.SetReadOnly(True)

        self.grid_mission.SetColAttr(ME_DELETE_COL, self.del_attr)
        self.grid_mission.SetColAttr(ME_UP_COL, self.up_attr)
        self.grid_mission.SetColAttr(ME_DOWN_COL, self.down_attr)
        self.grid_mission.SetColAttr(ME_DIST_COL, self.read_only_attr)
        self.grid_mission.SetColAttr(ME_ANGLE_COL, self.read_only_attr)
        self.grid_mission.SetRowLabelSize(50)

        #remember what mission we opened/saved last
        self.last_mission_file_path = ""

        #remember last map click position
        self.last_map_click_pos = None
Пример #14
0
import socket, time, random, math

track_count = 0

# object types
DNFZ_types = {
    'Aircraft': 1,
    'Weather': 20000,
    'BirdMigrating': 30000,
    'BirdOfPrey': 40000
}

from MAVProxy.modules.mavproxy_map import mp_elevation

ElevationMap = mp_elevation.ElevationModel()

gen_settings = mp_settings.MPSettings([("port", int, 45454), ('debug', int, 0),
                                       ('home_lat', float, -27.298440),
                                       ('home_lon', float, 151.290775),
                                       ('region_width', float, 15000),
                                       ('num_aircraft', int, 5),
                                       ('num_bird_prey', int, 5),
                                       ('num_bird_migratory', int, 5),
                                       ('num_weather', int, 5),
                                       ('wgs84_to_AMSL', float, -41.2),
                                       ('stop', int, 0)])


class DNFZ:
    '''a dynamic no-fly zone object'''
Пример #15
0
                  type='float',
                  default=3,
                  help="maximum climb rate")
parser.add_option("--home", default=None, help="new home")

(opts, args) = parser.parse_args()

from pymavlink import mavutil, mavwp

if len(args) < 1:
    print("Usage: mavmission.py [options] <missionfile>")
    sys.exit(1)

parms = {}

EleModel = mp_elevation.ElevationModel()


def get_ground_alt(lat, lon):
    '''get highest ground altitide around a point'''
    global EleModel
    ground = EleModel.GetElevation(lat, lon)
    surrounds = []
    for bearing in range(0, 360, 45):
        surrounds.append((opts.lookahead, bearing))
    for (dist, bearing) in surrounds:
        (lat2, lon2) = cuav_util.gps_newpos(lat, lon, bearing, dist)
        el = EleModel.GetElevation(lat2, lon2)
        if el > ground:
            ground = el
    return ground
Пример #16
0
    def __init__(self, mpstate):
        super(ConsoleModule, self).__init__(mpstate,
                                            "console",
                                            "Raven console",
                                            public=True,
                                            multi_vehicle=True)
        self.in_air = False
        self.start_time = 0.0
        self.total_time = 0.0
        self.speed = 0
        self.max_link_num = 0
        self.last_sys_status_health = 0
        mpstate.console = wxconsole.MessageConsole(title='Raven Console')

        # setup some default status information
        mpstate.console.set_status('Mode', 'UNKNOWN', row=0, fg='blue')
        mpstate.console.set_status('SysID', '', row=0, fg='blue')
        mpstate.console.set_status('ARM', 'ARM', fg='grey', row=0)
        mpstate.console.set_status('GPS', 'GPS: --', fg='red', row=0)
        mpstate.console.set_status('Vcc', 'Vcc: --', fg='red', row=0)
        mpstate.console.set_status('Radio', 'Radio: --', row=0)
        mpstate.console.set_status('INS', 'INS', fg='grey', row=0)
        mpstate.console.set_status('MAG', 'MAG', fg='grey', row=0)
        mpstate.console.set_status('AS', 'AS', fg='grey', row=0)
        mpstate.console.set_status('RNG', 'RNG', fg='grey', row=0)
        mpstate.console.set_status('AHRS', 'AHRS', fg='grey', row=0)
        mpstate.console.set_status('EKF', 'EKF', fg='grey', row=0)
        mpstate.console.set_status('LOG', 'LOG', fg='grey', row=0)
        mpstate.console.set_status('Heading', 'Head ---/---', row=2)
        mpstate.console.set_status('Alt', 'Alt ---', row=2)
        mpstate.console.set_status('AGL', 'AGL ---/---', row=2)
        mpstate.console.set_status('AirSpeed', 'AirSpeed --', row=2)
        mpstate.console.set_status('GPSSpeed', 'GPSSpeed --', row=2)
        mpstate.console.set_status('Thr', 'Thr ---', row=2)
        mpstate.console.set_status('Roll', 'Roll ---', row=2)
        mpstate.console.set_status('Pitch', 'Pitch ---', row=2)
        mpstate.console.set_status('Wind', 'Wind ---/---', row=2)
        mpstate.console.set_status('WP', 'WP --', row=3)
        mpstate.console.set_status('WPDist', 'Distance ---', row=3)
        mpstate.console.set_status('WPBearing', 'Bearing ---', row=3)
        mpstate.console.set_status('AltError', 'AltError --', row=3)
        mpstate.console.set_status('AspdError', 'AspdError --', row=3)
        mpstate.console.set_status('FlightTime', 'FlightTime --', row=3)
        mpstate.console.set_status('ETR', 'ETR --', row=3)

        mpstate.console.ElevationMap = mp_elevation.ElevationModel()

        self.vehicle_list = []
        self.vehicle_menu = None
        self.vehicle_name_by_sysid = {}
        self.last_param_sysid_timestamp = None

        # create the main menu
        if mp_util.has_wxpython:
            self.menu = MPMenuTop([])
            self.arm_menu = MPMenuSubMenu(
                'Arm/Disarm',
                items=[
                    MPMenuItem('Arming', 'Arming', '# arm throttle'),
                    MPMenuItem('Disarming', 'Disarming', '# disarm')
                ])
            self.graph_menu = MPMenuSubMenu(
                'Add Graph',
                items=[
                    MPMenuItem('Ground and Air Speed', 'Ground and Air Speed',
                               '# graph VFR_HUD.groundspeed VFR_HUD.airspeed'),
                    MPMenuItem(
                        'Attitude/Roll and Pitch', 'Attitude/Roll and Pitch',
                        '# graph degrees(ATTITUDE.roll) degrees(ATTITUDE.pitch)'
                    ),
                    MPMenuItem('Altitude', 'Altitude', '# graph VFR_HUD.alt')
                ])
            self.add_menu(
                MPMenuSubMenu('Main Menu',
                              items=[
                                  self.arm_menu,
                                  MPMenuItem('Settings', 'Settings',
                                             'menuSettings'),
                                  MPMenuItem('Add Graph Module', 'Load Graph',
                                             '# module load graph'),
                                  MPMenuItem('Add Map Module', 'Load Map',
                                             '# module load map'),
                                  self.graph_menu,
                                  MPMenuItem('Prachute Release',
                                             'Load Parachute',
                                             '# parachute release'),
                                  MPMenuItem('Save Data', 'Save Data',
                                             '# param save data.csv')
                              ]))