Exemplo n.º 1
0
 def __web_connect(self, u, wantPipe):
     self.web_disconnect() # Drop any old connections
     try:
         self.web = WebClient(u)
         self.web.connect(lambda msg: self.handle_webmavlink(msg), wantPipe = wantPipe)
         self.is_controlling = wantPipe
         print("Connected to server")
     except:
         print("Error, can not connect to server")
         self.web = None
Exemplo n.º 2
0
def test_login_info():
    log.debug('Running web test')
    logging.basicConfig(level=logging.DEBUG)

    def __handleRxMavlink(msg):
        log.debug("MavRx: %s" % msg)

    user = LoginInfo()
    user.loginName = "test-bob-py"
    user.password = "******"
    user.email = "*****@*****.**"
    user.vehicleId = 'a8098c1a-f86e-11da-bd1a-00112444be1e'  # FIXME - store in prefs

    web_client = WebClient(user)
    web_client.connect(__handleRxMavlink)
Exemplo n.º 3
0
class APIModule(mp_module.MPModule):
    def __init__(self, mpstate):
        super(APIModule, self).__init__(mpstate, "api")

        self.add_command('api', self.cmd_api, "API commands", [ "<list>", "<start> (FILENAME)", "<stop> [THREAD_NUM]" ])
        self.add_command('web', self.cmd_web, "API web connections", [ "<track> (USERNAME) (PASSWORD) (VEHICLEID)",
            "<control> (USERNAME) (PASSWORD) (VEHICLEID)", "<disconnect>" ])
        self.api = MPAPIConnection(self)
        self.vehicle = self.api.get_vehicles()[0]
        self.lat = None
        self.lon = None
        self.alt = None

        self.vx = None
        self.vy = None
        self.vz = None

        self.airspeed = None
        self.groundspeed = None

        self.pitch = None
        self.yaw = None
        self.roll = None
        self.pitchspeed = None
        self.yawspeed = None
        self.rollspeed = None

        self.mount_pitch = None
        self.mount_yaw = None
        self.mount_roll = None

        self.voltage = None
        self.current = None
        self.level = None

        self.rc_readback = {}

        self.last_waypoint = 0

        self.eph = None
        self.epv = None
        self.satellites_visible = None
        self.fix_type = None  # FIXME support multiple GPSs per vehicle - possibly by using componentId

        self.rngfnd_distance = None
        self.rngfnd_voltage = None

        self.next_thread_num = 0  # Monotonically increasing
        self.threads = {}  # A map from int ID to thread object

        self.web = None
        self.web_interface = 0
        self.web_serverid = None

        self.local_path = os.path.dirname(os.getcwd())
        print("DroneAPI loaded")

    def fix_targets(self, message):
        """Set correct target IDs for our vehicle"""
        settings = self.mpstate.settings
        if hasattr(message, 'target_system'):
            message.target_system = settings.target_system
        if hasattr(message, 'target_component'):
            message.target_component = settings.target_component

    def __on_change(self, *args):
        for a in args:
            self.vehicle.notify_observers(a)

    def unload(self):
        """We ask any api threads to exit"""
        for t in self.threads.values():
            t.kill()
        for t in self.threads.values():
            t.join(5)
            if t.is_alive():
                print("WARNING: Timed out waiting for %s to exit." % t)

    def mavlink_packet(self, m):
        typ = m.get_type()
        if typ == 'GLOBAL_POSITION_INT':
            (self.lat, self.lon) = (m.lat / 1.0e7, m.lon / 1.0e7)
            (self.vx, self.vy, self.vz) = (m.vx / 100.0, m.vy / 100.0, m.vz / 100.0)
            self.__on_change('location', 'velocity')
        elif typ == 'GPS_RAW':
            pass # better to just use global position int
            # (self.lat, self.lon) = (m.lat, m.lon)
            # self.__on_change('location')
        elif typ == 'GPS_RAW_INT':
            # (self.lat, self.lon) = (m.lat / 1.0e7, m.lon / 1.0e7)
            self.eph = m.eph
            self.epv = m.epv
            self.satellites_visible = m.satellites_visible
            self.fix_type = m.fix_type
            self.__on_change('gps_0')
        elif typ == "VFR_HUD":
            self.heading = m.heading
            self.alt = m.alt
            self.airspeed = m.airspeed
            self.groundspeed = m.groundspeed
            self.__on_change('location', 'airspeed', 'groundspeed')
        elif typ == "ATTITUDE":
            self.pitch = m.pitch
            self.yaw = m.yaw
            self.roll = m.roll
            self.pitchspeed = m.pitchspeed
            self.yawspeed = m.yawspeed
            self.rollspeed = m.rollspeed
            self.__on_change('attitude')
        elif typ == "SYS_STATUS":
            self.voltage = m.voltage_battery
            self.current = m.current_battery
            self.level = m.battery_remaining
            self.__on_change('battery')
        elif typ == "HEARTBEAT":
            self.__on_change('mode', 'armed')
        elif typ in ["WAYPOINT_CURRENT", "MISSION_CURRENT"]:
            self.last_waypoint = m.seq
        elif typ == "RC_CHANNELS_RAW":
            def set(chnum, v):
                '''Private utility for handling rc channel messages'''
                # use port to allow ch nums greater than 8
                self.rc_readback[str(m.port * 8 + chnum)] = v

            set(1, m.chan1_raw)
            set(2, m.chan2_raw)
            set(3, m.chan3_raw)
            set(4, m.chan4_raw)
            set(5, m.chan5_raw)
            set(6, m.chan6_raw)
            set(7, m.chan7_raw)
            set(8, m.chan8_raw)
        elif typ == "MOUNT_STATUS":
            self.mount_pitch = m.pointing_a / 100
            self.mount_roll = m.pointing_b / 100
            self.mount_yaw = m.pointing_c / 100
            self.__on_change('mount')
        elif typ == "RANGEFINDER":
            self.rngfnd_distance = m.distance
            self.rngfnd_voltage = m.voltage
            self.__on_change('rangefinder')


        if (self.vehicle is not None) and hasattr(self.vehicle, 'mavrx_callback'):
            self.vehicle.mavrx_callback(m)

        self.send_to_server(m)

    def send_to_server(self, m):
        if (self.web is not None):
            sysid = m.get_srcSystem()
            if sysid != self.web_serverid: # Never return packets that arrived from the server
                try:
                    #logger.debug("send to web: " + str(m))
                    self.web.filterMavlink(self.web_interface, m.get_msgbuf())
                except IOError:
                    print("Lost connection to server")
                    # self.web.close()
                    self.web = None
            else:
                #logger.debug("ignore to: " + str(m))
                pass

    def thread_remove(self, t):
        if t.thread_num in self.threads.keys():
            del self.threads[t.thread_num]

    def thread_add(self, t):
        self.threads[t.thread_num] = t

    def cmd_list(self):
        print("API Threads:")
        for t in self.threads.values():
            print("  " + str(t))

    def cmd_kill(self, n):
        if self.threads[n].isAlive():
            self.threads[n].kill()

    def get_connection(self):
        return self.api

    def handle_webmavlink(self, msg):
        #print "got msg", msg
        #for m in msg: print "#", hex(ord(m))
        decoded = self.master.mav.decode(msg)
        self.web_serverid = decoded.get_srcSystem()
        #logger.debug("from server: %s (sys=%d, comp=%d, seq=%d)" % (decoded, decoded.get_srcSystem(), decoded.get_srcComponent(), decoded.get_seq()))

        mav = self.master.mav
        # FIXME - mavproxy is slaming in its own sysid - until I fix the generator for mavlinkv10.py to add a sendRaw()
        # instead of the following we send using private state of the mav connection
        #mav.send(decoded)
        mav.file.write(msg)

        if not self.is_controlling:
            # The server wants to send a packet to the vehicle
            mav.total_packets_sent += 1
            mav.total_bytes_sent += len(msg)
            if mav.send_callback:
                mav.send_callback(decoded, *mav.send_callback_args, **mav.send_callback_kwargs)
        else:
            # Pretend that this packet from the server just arrived over a local interface
            mav.total_packets_received += 1
            if mav.callback:
                mav.callback(decoded, *mav.callback_args, **mav.callback_kwargs)

    def web_track(self, username, password, vehicleid):
        """Start uploading live flight data to web service"""
        u = LoginInfo()
        u.loginName = username
        u.password = password
        u.vehicleId = vehicleid

        self.__web_connect(u, False)

    def web_control(self, username, password, vehicleid):
        """Start controlling a vehicle through the web service"""
        u = LoginInfo()
        u.loginName = username
        u.password = password
        u.vehicleId = vehicleid
        # FIXME - this is a super nasty we we find packets the local mavproxy wants to send to server
        # talk with Tridge and construct a better mechanism.  (Possibly make a new 'mav' binding?)
        self.master.mav.set_send_callback(lambda m, master: self.send_to_server(m), self.master)
        self.__web_connect(u, True)

    def web_disconnect(self):
        if self.web is not None:
            self.web.close()
            self.web = None
            print("Disconnected from server")

    def __web_connect(self, u, wantPipe):
        self.web_disconnect() # Drop any old connections
        try:
            self.web = WebClient(u)
            self.web.connect(lambda msg: self.handle_webmavlink(msg), wantPipe = wantPipe)
            self.is_controlling = wantPipe
            print("Connected to server")
        except:
            print("Error, can not connect to server")
            self.web = None

    def cmd_api(self, args):
        if len(args) < 1:
            print("usage: api <list|start|stop> [filename or threadnum]")
            return

        if args[0] == "list":
            self.cmd_list()
        elif args[0] == "stop":
            if len(args) > 2:
                print("usage: api stop [thread-num]")
                return
            elif len(args) > 1:
                self.cmd_kill(int(args[1]))
            elif len(self.threads) > 1:
                # Just kill the youngest
                self.cmd_kill(max(self.threads.keys))
        elif args[0] == "start":
            if len(args) < 2:
                print("usage: api start <filename> [arguments]")
                return

            g = {
                "local_connect" : self.get_connection,
                "local_path": os.path.dirname(os.path.abspath(args[1])), # The path to the executable script dir (so scripts can construct relative paths)
                "local_arguments": args[2:]
            }

            APIThread(self, lambda: execfile(args[1], g), args[1])
        else:
            print("Invalid api subcommand")

    def cmd_web(self, args):
        if len(args) < 1:
            print("usage: web <track|control|disconnect> ...")
            return

        if args[0] == "track":
            self.web_track(args[1], args[2], args[3])
        elif args[0] == "control":
            self.web_control(args[1], args[2], args[3])
        elif args[0] == "disconnect":
            self.web_disconnect()
        else:
            print("Invalid web subcommand")
Exemplo n.º 4
0
from droneapi.lib.WebClient import *
import logging

print "Running web test"
logging.basicConfig(level=logging.DEBUG)

def __handleRxMavlink(msg):
    print "MavRx: ", msg

u = LoginInfo()
u.loginName = "test-bob-py"
u.password = "******"
u.email = "*****@*****.**"
u.vehicleId = 'a8098c1a-f86e-11da-bd1a-00112444be1e' # FIXME - store in prefs

w = WebClient(u)
w.connect(__handleRxMavlink)
Exemplo n.º 5
0
from droneapi.lib.WebClient import *
import logging

print "Running web test"
logging.basicConfig(level=logging.DEBUG)


def __handleRxMavlink(msg):
    print "MavRx: ", msg


u = LoginInfo()
u.loginName = "test-bob-py"
u.password = "******"
u.email = "*****@*****.**"
u.vehicleId = 'a8098c1a-f86e-11da-bd1a-00112444be1e'  # FIXME - store in prefs

w = WebClient(u)
w.connect(__handleRxMavlink)