예제 #1
0
 def poll(self):
     '''check for events, returning one event'''
     if self.out_queue.qsize() <= 0:
         return None
     evt = self.out_queue.get()
     while isinstance(evt, win_layout.WinLayout):
         win_layout.set_layout(evt, self.set_layout)
         if self.out_queue.qsize() == 0:
             return None
         evt = self.out_queue.get()
     return evt
예제 #2
0
 def get_event(self):
     '''return next event or None'''
     if self.event_queue.empty():
         return None
     evt = self.event_queue.get()
     while isinstance(evt, win_layout.WinLayout):
         win_layout.set_layout(evt, self.set_layout)
         if self.event_queue.empty():
             return None
         evt = self.event_queue.get()
     return evt
예제 #3
0
 def get_event(self):
     '''return next event or None'''
     if self.event_queue.qsize() == 0:
         return None
     evt = self.event_queue.get()
     while isinstance(evt, win_layout.WinLayout):
         win_layout.set_layout(evt, self.set_layout)
         if self.event_queue.qsize() == 0:
             return None
         evt = self.event_queue.get()
     return evt
예제 #4
0
 def poll(self):
     '''check for events, returning one event'''
     if self.out_queue.qsize() <= 0:
         return None
     evt = self.out_queue.get()
     while isinstance(evt, win_layout.WinLayout):
         win_layout.set_layout(evt, self.set_layout)
         if self.out_queue.qsize() == 0:
             return None
         evt = self.out_queue.get()
     return evt
예제 #5
0
 def watch_thread(self):
     '''watch for menu events from child'''
     from MAVProxy.modules.lib.mp_settings import MPSetting
     try:
         while True:
             msg = self.parent_pipe_recv.recv()
             if isinstance(msg, win_layout.WinLayout):
                 win_layout.set_layout(msg, self.set_layout)
             elif self.menu_callback is not None:
                 self.menu_callback(msg)
             time.sleep(0.1)
     except EOFError:
         pass
예제 #6
0
 def watch_thread(self):
     '''watch for menu events from child'''
     from MAVProxy.modules.lib.mp_settings import MPSetting
     try:
         while True:
             msg = self.parent_pipe_recv.recv()
             if isinstance(msg, win_layout.WinLayout):
                 win_layout.set_layout(msg, self.set_layout)
             elif self.menu_callback is not None:
                 self.menu_callback(msg)
             time.sleep(0.1)
     except EOFError:
         pass
예제 #7
0
    def run(self):
        while not self.time_to_quit:
            queue_access_start_time = time.time()
            self.event_queue_lock.acquire()
            request_read_after_processing_queue = False
            while self.event_queue.qsize() > 0 and (
                    time.time() - queue_access_start_time) < 0.6:
                event = self.event_queue.get()

                if isinstance(event, win_layout.WinLayout):
                    win_layout.set_layout(event, self.mp_misseditor.set_layout)
                else:
                    event_type = event.get_type()

                    if event_type == me_event.MEE_READ_WPS:
                        self.module('wp').cmd_wp(['list'])
                        #list the rally points while I'm add it:
                        #TODO: DON'T KNOW WHY THIS DOESN'T WORK
                        #self.module('rally').cmd_rally(['list'])

                        #means I'm doing a read & don't know how many wps to expect:
                        self.mp_misseditor.num_wps_expected = -1
                        self.wps_received = {}

                    elif event_type == me_event.MEE_TIME_TO_QUIT:
                        self.time_to_quit = True

                    elif event_type == me_event.MEE_GET_WP_RAD:
                        wp_radius = self.module('param').mav_param.get(
                            'WP_RADIUS')
                        if (wp_radius is None):
                            continue
                        self.mp_misseditor.gui_event_queue_lock.acquire()
                        self.mp_misseditor.gui_event_queue.put(
                            MissionEditorEvent(me_event.MEGE_SET_WP_RAD,
                                               wp_rad=wp_radius))
                        self.mp_misseditor.gui_event_queue_lock.release()

                    elif event_type == me_event.MEE_SET_WP_RAD:
                        self.mp_misseditor.param_set('WP_RADIUS',
                                                     event.get_arg("rad"))

                    elif event_type == me_event.MEE_GET_LOIT_RAD:
                        loiter_radius = self.module('param').mav_param.get(
                            'WP_LOITER_RAD')
                        if (loiter_radius is None):
                            continue
                        self.mp_misseditor.gui_event_queue_lock.acquire()
                        self.mp_misseditor.gui_event_queue.put(
                            MissionEditorEvent(me_event.MEGE_SET_LOIT_RAD,
                                               loit_rad=loiter_radius))
                        self.mp_misseditor.gui_event_queue_lock.release()

                    elif event_type == me_event.MEE_SET_LOIT_RAD:
                        loit_rad = event.get_arg("rad")
                        if (loit_rad is None):
                            continue

                        self.mp_misseditor.param_set('WP_LOITER_RAD', loit_rad)

                        #need to redraw rally points
                        # Don't understand why this rally refresh isn't lagging...
                        # likely same reason why "timeout setting WP_LOITER_RAD"
                        #comes back:
                        #TODO: fix timeout issue
                        self.module('rally').set_last_change(time.time())

                    elif event_type == me_event.MEE_GET_WP_DEFAULT_ALT:
                        self.mp_misseditor.gui_event_queue_lock.acquire()
                        self.mp_misseditor.gui_event_queue.put(
                            MissionEditorEvent(
                                me_event.MEGE_SET_WP_DEFAULT_ALT,
                                def_wp_alt=self.mp_misseditor.mpstate.settings.
                                wpalt))
                        self.mp_misseditor.gui_event_queue_lock.release()
                    elif event_type == me_event.MEE_SET_WP_DEFAULT_ALT:
                        self.mp_misseditor.mpstate.settings.command(
                            ["wpalt", event.get_arg("alt")])

                    elif event_type == me_event.MEE_WRITE_WPS:
                        self.module('wp').wploader.clear()
                        self.master().waypoint_count_send(
                            event.get_arg("count"))
                        self.mp_misseditor.num_wps_expected = event.get_arg(
                            "count")
                        self.mp_misseditor.wps_received = {}
                    elif event_type == me_event.MEE_WRITE_WP_NUM:
                        w = mavutil.mavlink.MAVLink_mission_item_message(
                            self.mp_misseditor.mpstate.settings.target_system,
                            self.mp_misseditor.
                            mpstate.settings.target_component,
                            event.get_arg("num"), int(event.get_arg("frame")),
                            event.get_arg("cmd_id"), 0, 1, event.get_arg("p1"),
                            event.get_arg("p2"), event.get_arg("p3"),
                            event.get_arg("p4"), event.get_arg("lat"),
                            event.get_arg("lon"), event.get_arg("alt"))

                        self.module('wp').wploader.add(w)
                        wsend = self.module('wp').wploader.wp(w.seq)
                        if self.mp_misseditor.mpstate.settings.wp_use_mission_int:
                            wsend = self.module('wp').wp_to_mission_item_int(w)
                        self.master().mav.send(wsend)

                        #tell the wp module to expect some waypoints
                        self.module('wp').loading_waypoints = True

                    elif event_type == me_event.MEE_LOAD_WP_FILE:
                        self.module('wp').cmd_wp(
                            ['load', event.get_arg("path")])
                        #Wait for the other thread to finish loading waypoints.
                        #don't let this loop run forever in case we have a lousy
                        #link to the plane
                        i = 0
                        while (i < 10 and self.module('wp').loading_waypoints):
                            time.sleep(1)
                            i = i + 1

                            #don't modify queue while in the middile of processing it:
                            request_read_after_processing_queue = True

                    elif event_type == me_event.MEE_SAVE_WP_FILE:
                        self.module('wp').cmd_wp(
                            ['save', event.get_arg("path")])

            self.event_queue_lock.release()

            #if event processing operations require a mission referesh in GUI
            #(e.g., after a load or a verified-completed write):
            if (request_read_after_processing_queue):
                self.event_queue_lock.acquire()
                self.event_queue.put(MissionEditorEvent(me_event.MEE_READ_WPS))
                self.event_queue_lock.release()

            #periodically re-request WPs that were never received:
            #DON'T NEED TO! -- wp module already doing this

            time.sleep(0.2)
예제 #8
0
    def idle_task(self):
        '''run on idle'''
        # send updated HB stats to GUI every 1 sec
        if self.needHBupdate_timer.trigger():
            self.gui.updateHB(self.vehicleLastHB)

        # do we need to update the GUI?
        if self.needGUIupdate_timer.trigger() and self.needGUIupdate:
            self.gui.updateLayout(self.vehicleListing)
            self.needGUIupdate = False

        # do we need to get any vehicle follow sysid params?
        # only send param requests 1 per 0.1sec, to avoid link flooding
        if self.requestParams_timer.trigger() and len(self.vehParamsToGet) > 0:
            (sysid, compid) = self.vehParamsToGet.pop(0)
            self.mpstate.foreach_mav(sysid, compid, lambda mav: mav.param_request_read_send(
                sysid, compid, parmString("FOLL_SYSID"), -1))

        if self.RerequestParams_timer.trigger():
            # If any in vehicleListing are missing their FOLL_SYSID, re-request
            for veh in self.vehicleListing:
                if veh[2] == 0:
                    self.vehParamsToGet.append(((veh[0], veh[1])))

        # execute any commands from GUI via parent_pipe
        if self.gui.parent_pipe.poll():
            (cmd, sysid, compid) = self.gui.parent_pipe.recv()
            if isinstance(cmd, win_layout.WinLayout):
                win_layout.set_layout(cmd, self.set_layout)
            if cmd == "arm":
                self.mpstate.foreach_mav(sysid, compid, lambda mav: mav.command_long_send(
                    # self.master.mav.command_long_send(
                    sysid,  # target_system
                    compid,
                    mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,  # command
                    0,  # confirmation
                    1,  # param1 (1 to indicate arm)
                    0,  # param2  (all other params meaningless)
                    0,  # param3
                    0,  # param4
                    0,  # param5
                    0,  # param6
                    0))  # param7
            elif cmd == "disarm":
                self.mpstate.foreach_mav(sysid, compid, lambda mav: mav.command_long_send(
                    sysid,  # target_system
                    compid,
                    mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,  # command
                    0,  # confirmation
                    0,  # param1 (1 to indicate arm)
                    0,  # param2  (all other params meaningless)
                    0,  # param3
                    0,  # param4
                    0,  # param5
                    0,  # param6
                    0))  # param7
            elif cmd == "takeoff":
                self.mpstate.foreach_mav(sysid, compid, lambda mav: mav.command_long_send(
                    sysid,  # target_system
                    compid,  # target_component
                    mavutil.mavlink.MAV_CMD_NAV_TAKEOFF,  # command
                    0,  # confirmation
                    0,  # param1
                    0,  # param2
                    0,  # param3
                    0,  # param4
                    0,  # param5
                    0,  # param6
                    self.swarm_settings.takeoffalt))  # param7
            elif cmd in ["FOLLOW", "RTL", "AUTO", "GUIDED"]:
                mode_mapping = self.master.mode_mapping()
                self.mpstate.foreach_mav(sysid, compid, lambda mav: mav.command_long_send(sysid,
                                                                                          compid,
                                                                                          mavutil.mavlink.MAV_CMD_DO_SET_MODE,
                                                                                          0,
                                                                                          mavutil.mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED,
                                                                                          mode_mapping[cmd],
                                                                                          0,
                                                                                          0,
                                                                                          0,
                                                                                          0,
                                                                                          0))
            elif cmd == "kill":
                self.mpstate.foreach_mav(sysid, compid, lambda mav: mav.command_long_send(
                    sysid,  # target_system
                    compid,
                    mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,  # command
                    0,  # confirmation
                    0,  # param1 (0 to indicate disarm)
                    21196,  # param2 (indicates force disarm)
                    0,  # param3
                    0,  # param4
                    0,  # param5
                    0,  # param6
                    0))  # param7
            elif cmd == 'getoffsets':
                # time.sleep(0.1)
                for parm in self.parmsToShow:
                    self.mpstate.foreach_mav(sysid, compid, lambda mav: mav.param_request_read_send(
                        sysid, compid, parmString(parm), -1))
            elif cmd == 'resetLayout':
                self.vehicleListing = []
                self.vehicleLastHB = {}
                self.needGUIupdate = True
                # self.gui.updateLayout(self.vehicleListing)
            elif cmd == 'getparams':
                for (sysid, compid, foll_sysid, veh_type) in self.vehicleListing:
                    # time.sleep(0.1)
                    for parm in self.parmsToShow:
                        self.mpstate.foreach_mav(sysid, compid, lambda mav: mav.param_request_read_send(
                            sysid, compid, parmString(parm), -1))