Exemplo n.º 1
0
 def __init__(self, mpstate):
     super(FakeGPSModule, self).__init__(mpstate, "fakegps")
     self.last_send = time.time()
     self.FakeGPS_settings = mp_settings.MPSettings([
         ("nsats", int, 16), ("lat", float, -35.363261),
         ("lon", float, 149.165230), ("alt", float, 584.0),
         ("rate", float, 5)
     ])
     self.add_command('fakegps', self.cmd_FakeGPS, "fakegps control",
                      ["<status>", "set (FAKEGPSSETTING)"])
     self.add_completion_function('(FAKEGPSSETTING)',
                                  self.FakeGPS_settings.completion)
     if mp_util.has_wxpython:
         map = self.module('map')
         if map is not None:
             menu = MPMenuSubMenu(
                 'FakeGPS',
                 items=[
                     MPMenuItem('SetPos', 'SetPos', '# fakegps setpos'),
                     MPMenuItem(
                         'SetPos (with alt)',
                         'SetPosAlt',
                         '# fakegps setpos ',
                         handler=MPMenuCallTextDialog(
                             title='Altitude (m)',
                             default=self.mpstate.settings.guidedalt))
                 ])
             map.add_menu(menu)
Exemplo n.º 2
0
 def __init__(self, mpstate):
     super(NtripModule, self).__init__(mpstate,
                                       "ntrip",
                                       "ntrip",
                                       public=False)
     self.ntrip_settings = mp_settings.MPSettings([
         ('caster', str, None), ('port', int, 2101),
         ('username', str, 'IBS'), ('password', str, 'IBS'),
         ('mountpoint', str, None), ('logfile', str, None),
         ('sendalllinks', bool, False), ('sendmul', int, 1)
     ])
     self.add_command(
         'ntrip', self.cmd_ntrip, 'NTRIP control',
         ["<status>", "<start>", "<stop>", "set (NTRIPSETTING)"])
     self.add_completion_function('(NTRIPSETTING)',
                                  self.ntrip_settings.completion)
     self.pos = None
     self.pkt_count = 0
     self.last_pkt = None
     self.last_restart = None
     self.last_rate = None
     self.rate_total = 0
     self.ntrip = None
     self.start_pending = False
     self.rate = 0
     self.logfile = None
     self.id_counts = {}
     self.last_by_id = {}
Exemplo n.º 3
0
 def __init__(self, mpstate):
     from pymavlink import mavparm
     super(TrackerModule, self).__init__(mpstate, "tracker",
                                         "antenna tracker control module")
     self.connection = None
     self.tracker_param = mavparm.MAVParmDict()
     sysid = 2
     self.pstate = ParamState(self.tracker_param, self.logdir,
                              self.vehicle_name, 'tracker.parm', mpstate,
                              sysid)
     self.tracker_settings = mp_settings.MPSettings([
         ('port', str, "/dev/ttyUSB0"), ('baudrate', int, 57600),
         ('debug', int, 0)
     ])
     self.add_command(
         'tracker', self.cmd_tracker, "antenna tracker control module", [
             '<start|arm|disarm|level|mode|position|calpress|mode>',
             'set (TRACKERSETTING)',
             'param <set|show|fetch|help> (TRACKERPARAMETER)',
             'param (TRACKERSETTING)'
         ])
     self.add_completion_function('(TRACKERSETTING)',
                                  self.tracker_settings.completion)
     self.add_completion_function('(TRACKERPARAMETER)',
                                  self.complete_parameter)
Exemplo n.º 4
0
 def __init__(self, mpstate):
     super(ViconModule, self).__init__(mpstate,
                                       "vicon",
                                       "vicon",
                                       public=False)
     self.console.set_status('VPos', 'VPos -- -- --', row=5)
     self.console.set_status('VAtt', 'VAtt -- -- --', row=5)
     self.vicon_settings = mp_settings.MPSettings([
         ('host', str, "vicon"), ('origin_lat', float, -35.363261),
         ('origin_lon', float, 149.165230), ('origin_alt', float, 584.0),
         ('vision_rate', int, 14), ('vel_filter_hz', float, 30.0),
         ('gps_rate', int, 5), ('gps_nsats', float, 16),
         ('yaw_offset', float, 0.0)
     ])
     self.add_command('vicon', self.cmd_vicon, 'VICON control',
                      ["<start>", "<stop>", "set (VICONSETTING)"])
     self.add_completion_function('(VICONSETTING)',
                                  self.vicon_settings.completion)
     self.vicon = None
     self.thread = threading.Thread(target=self.thread_loop)
     self.thread.start()
     self.pos = None
     self.att = None
     self.frame_count = 0
     self.gps_count = 0
     self.vision_count = 0
     self.last_frame_count = 0
     self.vel_filter = LowPassFilter2p.LowPassFilter2p(200.0, 30.0)
     self.actual_frame_rate = 0.0
    def __init__(self, mpstate):
        """Initialise module.  We start poking the UAV for messages after this
        is called"""
        super(dataflash_logger,
              self).__init__(mpstate, "dataflash_logger",
                             "logging of mavlink dataflash messages")
        self.sender = None
        self.stopped = False
        self.time_last_start_packet_sent = 0
        self.time_last_stop_packet_sent = 0
        self.dataflash_dir = self._dataflash_dir(mpstate)
        self.download = 0
        self.prev_download = 0
        self.last_status_time = time.time()
        self.last_seqno = 0
        self.missing_blocks = {}
        self.acking_blocks = {}
        self.blocks_to_ack_and_nack = []
        self.missing_found = 0
        self.abandoned = 0
        self.dropped = 0
        self.armed = False

        self.log_settings = mp_settings.MPSettings([
            ('verbose', bool, False), ('rotate_on_disarm', bool, False),
            ('df_target_system', int, 0),
            ('df_target_component', int, mavutil.mavlink.MAV_COMP_ID_LOG)
        ])
        self.add_command(
            'dataflash_logger', self.cmd_dataflash_logger,
            "dataflash logging control",
            ['status', 'start', 'stop', 'rotate', 'set (LOGSETTING)'])
        self.add_completion_function('(LOGSETTING)',
                                     self.log_settings.completion)
Exemplo n.º 6
0
 def __init__(self, mpstate):
     super(EMUECUModule, self).__init__(mpstate,
                                        "emuecu",
                                        "emuecu",
                                        public=False)
     self.emuecu_settings = mp_settings.MPSettings([('port', int, 102)])
     self.add_command('emu', self.cmd_emu, 'EMUECU control',
                      ["<send>", "set (EMUECUSETTING)"])
     self.add_completion_function('(EMUECUSETTING)',
                                  self.emuecu_settings.completion)
Exemplo n.º 7
0
 def __init__(self, mpstate):
     super(SerialModule, self).__init__(mpstate, "serial",
                                        "serial control handling")
     self.add_command('serial', self.cmd_serial, 'remote serial control',
                      ['<lock|unlock|send>', 'set (SERIALSETTING)'])
     self.serial_settings = mp_settings.MPSettings([('port', int, 0),
                                                    ('baudrate', int,
                                                     57600),
                                                    ('timeout', int, 500)])
     self.add_completion_function('(SERIALSETTING)',
                                  self.serial_settings.completion)
     self.locked = False
Exemplo n.º 8
0
    def __init__(self, mpstate):
        """Initialise module"""
        super(generator, self).__init__(mpstate, "generator", "")

        self.generator_settings = mp_settings.MPSettings(
            [ ('verbose', bool, False),
          ])
        self.add_command('generator',
                         self.cmd_generator,
                         "generator module",
                         ['status','set (LOGSETTING)'])
        self.console_row = 6
        self.console.set_status('Generator', 'No generator messages', row=self.console_row)
Exemplo n.º 9
0
    def __init__(self, mpstate):
        """Initialise module"""
        super(message, self).__init__(mpstate, "message", "")
        self.status_callcount = 0
        self.boredom_interval = 10  # seconds
        self.last_bored = time.time()

        self.packets_mytarget = 0
        self.packets_othertarget = 0
        self.verbose = False

        self.message_settings = mp_settings.MPSettings([('verbose', bool,
                                                         False)])
        self.add_command('message', self.cmd_message, "message module", [])
Exemplo n.º 10
0
    def __init__(self, mpstate):
        """Initialise module"""
        super(system_time, self).__init__(mpstate, "system_time", "")
        self.last_sent = 0
        self.last_sent_ts1 = 0
        self.last_sent_timesync = 0
        self.module_load_time = time.time()

        self.system_time_settings = mp_settings.MPSettings([
            ('verbose', bool, False), ('interval_timesync', int, 10),
            ('interval', int, 10)
        ])
        self.add_command('system_time', self.cmd_system_time,
                         "system_time module", ['status', 'set (LOGSETTING)'])
Exemplo n.º 11
0
 def __init__(self, mpstate):
     super(FollowTestModule, self).__init__(mpstate, "followtest",
                                            "followtest module")
     self.add_command('followtest', self.cmd_followtest,
                      "followtest control", ['set (FOLLOWSETTING)'])
     self.follow_settings = mp_settings.MPSettings([
         ("radius", float, 100.0), ("altitude", float, 50.0),
         ("speed", float, 10.0), ("type", str, 'guided'),
         ("vehicle_throttle", float, 0.5), ("disable_msg", bool, False)
     ])
     self.add_completion_function('(FOLLOWSETTING)',
                                  self.follow_settings.completion)
     self.target_pos = None
     self.last_update = 0
     self.circle_dist = 0
Exemplo n.º 12
0
    def __init__(self, mpstate):
        """Initialise module"""
        super(example, self).__init__(mpstate, "example", "")
        self.status_callcount = 0
        self.boredom_interval = 10  # seconds
        self.last_bored = time.time()

        self.packets_mytarget = 0
        self.packets_othertarget = 0

        self.example_settings = mp_settings.MPSettings([
            ('verbose', bool, False),
        ])
        self.add_command('example', self.cmd_example, "example module",
                         ['status', 'set (LOGSETTING)'])
Exemplo n.º 13
0
 def __init__(self, mpstate):
     super(NSHModule, self).__init__(mpstate, "nsh", "remote nsh shell")
     self.add_command('nsh', self.cmd_nsh,
                      'nsh shell control',
                      ['<start|stop>',
                       'set (SERIALSETTING)'])
     self.serial_settings = mp_settings.MPSettings(
         [ ('port', int, mavutil.mavlink.SERIAL_CONTROL_DEV_SHELL),
           ('baudrate', int, 57600)
           ]
         )
     self.add_completion_function('(SERIALSETTING)', self.serial_settings.completion)
     self.last_packet = time.time()
     self.last_check = time.time()
     self.started = False
Exemplo n.º 14
0
    def __init__(self, mpstate, multi_vehicle=True):
        """Initialise module"""
        super(proximity, self).__init__(mpstate, "proximity", "")

        self.proximity_settings = mp_settings.MPSettings([
            ('verbose', bool, False),
        ])
        self.add_command('proximity', self.cmd_proximity, "proximity module", [
            'set (PROXIMITYSETTING)',
        ])

        self.heading_for_vehicle = {}
        self.have_global_position = False

        # lat/lon per system ID
        self.lat_lon_for_vehicle = {}
Exemplo n.º 15
0
 def __init__(self, mpstate):
     super(SetPosModule, self).__init__(mpstate,
                                        "SetPos",
                                        "SetPos",
                                        public=False)
     self.add_command('setpos', self.cmd_setpos, "set local pos")
     self.add_command('hop', self.cmd_hop, "hop position")
     self.hop = None
     self.hop_stage = 0
     self.hop_last_time = time.time()
     self.hop_settings = mp_settings.MPSettings([
         ('height', float, 0.7), ('takeoff_delay', float, 4.0),
         ('move_delay', float, 4.0)
     ])
     self.add_command('hop', self.cmd_hop, 'HOP control',
                      ["set (HOPSETTING)"])
     self.add_completion_function('(HOPSETTING)',
                                  self.hop_settings.completion)
Exemplo n.º 16
0
    def __init__(self, mpstate):
        """Initialise OSD module"""
        super(osd, self).__init__(mpstate, "osd", "")

        self.request_id = 1
        self.osd_settings = mp_settings.MPSettings(
            [ ('verbose', bool, False),
          ])
        self.add_command('osd', self.cmd_osd, "OSD module", ['param-set', 'param-show', 'set (OSDSETTING)'])
        self.type_map = {
            mavutil.mavlink.OSD_PARAM_NONE : "NONE",
            mavutil.mavlink.OSD_PARAM_SERIAL_PROTOCOL : "SERIAL_PROTOCOL",
            mavutil.mavlink.OSD_PARAM_SERVO_FUNCTION : "SERVO_FUNCTION",
            mavutil.mavlink.OSD_PARAM_AUX_FUNCTION : "AUX_FUNCTION",
            mavutil.mavlink.OSD_PARAM_FLIGHT_MODE : "FLIGHT_MODE",
            mavutil.mavlink.OSD_PARAM_FAILSAFE_ACTION : "FAILSAFE_ACTION",
            mavutil.mavlink.OSD_PARAM_FAILSAFE_ACTION_1 : "FAILSAFE_ACTION_1",
            mavutil.mavlink.OSD_PARAM_FAILSAFE_ACTION_2 : "FAILSAFE_ACTION_2" }
        self.invtype_map = { v : k for k, v in self.type_map.items()}
Exemplo n.º 17
0
    def __init__(self, mpstate):
        super(AsterixModule, self).__init__(mpstate, "asterix",
                                            "asterix SDPS data support")
        self.threat_vehicles = {}
        self.active_threat_ids = [
        ]  # holds all threat ids the vehicle is evading

        self.add_command('asterix', self.cmd_asterix, "asterix control",
                         ["<start|stop>", "set (ASTERIXSETTING)"])

        # filter_dist is distance in metres
        self.asterix_settings = mp_settings.MPSettings([
            ("port", int, 45454),
            ('debug', int, 0),
            ('filter_dist_xy', int, 1000),
            ('filter_dist_z', int, 250),
            ('filter_time', int, 20),
            ('wgs84_to_AMSL', float, -41.2),
            ('filter_use_vehicle2', bool, True),
        ])
        self.add_completion_function('(ASTERIXSETTING)',
                                     self.asterix_settings.completion)
        self.sock = None
        self.tracks = {}
        self.start_listener()

        # storage for vehicle positions, used for filtering
        self.vehicle_pos = None
        self.vehicle2_pos = None

        self.adsb_packets_sent = 0
        self.adsb_packets_not_sent = 0
        self.adsb_byterate = 0  # actually bytes...
        self.adsb_byterate_update_timestamp = 0
        self.adsb_last_packets_sent = 0
        if self.logdir is not None:
            logpath = os.path.join(self.logdir, 'asterix.log')
        else:
            logpath = 'asterix.log'
        self.logfile = open(logpath, 'wb')
        self.pkt_count = 0
        self.console.set_status('ASTX', 'ASTX --/--', row=6)
Exemplo n.º 18
0
    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),
                                                        ('enable', int, 1)])
        self.add_completion_function('(TERRAINSETTING)',
                                     self.terrain_settings.completion)
Exemplo n.º 19
0
    def __init__(self, mpstate):
        super(UcenterModule, self).__init__(mpstate, "ucenter",
                                            "ucenter forwarding")

        self.add_command('ucenter', self.cmd_ucenter, "ucenter control",
                         ["<start|stop|restart>", "set (UCENTERSETTING)"])

        self.ucenter_settings = mp_settings.MPSettings([("port", int, 2001),
                                                        ('devnum', int, 2),
                                                        ('baudrate', int,
                                                         115200),
                                                        ('delay', float, 0.01),
                                                        ('debug', int, 0)])
        self.add_completion_function('(UCENTERSETTING)',
                                     self.ucenter_settings.completion)
        self.listen_sock = None
        self.sock = None
        self.last_write = time.time()
        self.last_baudrate = 0
        self.last_devnum = -1
Exemplo n.º 20
0
    def __init__(self, mpstate):
        super(ADSBModule, self).__init__(mpstate, "adsb", "ADS-B data support", public = True)
        self.threat_vehicles = {}
        self.active_threat_ids = []  # holds all threat ids the vehicle is evading

        self.add_command('adsb', self.cmd_ADSB, "adsb control",
                         ["<status>", "set (ADSBSETTING)"])

        self.ADSB_settings = mp_settings.MPSettings([("timeout", int, 5),  # seconds
                                                     ("threat_radius", int, 200),  # meters
                                                     ("show_threat_radius", bool, False),
                                                     # threat_radius_clear = threat_radius*threat_radius_clear_multiplier
                                                     ("threat_radius_clear_multiplier", int, 2),
                                                     ("show_threat_radius_clear", bool, False)])
        self.add_completion_function('(ADSBSETTING)',
                                     self.ADSB_settings.completion)
        
        self.threat_detection_timer = mavutil.periodic_event(2)
        self.threat_timeout_timer = mavutil.periodic_event(2)
        self.tnow = self.get_time()
Exemplo n.º 21
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()
Exemplo n.º 22
0
 def __init__(self, mpstate):
     super(RCModule, self).__init__(mpstate,
                                    "rc",
                                    "rc command handling",
                                    public=True)
     self.count = 18
     self.override = [0] * self.count
     self.last_override = [0] * self.count
     self.override_counter = 0
     x = "|".join(str(x) for x in range(1, (self.count + 1)))
     self.add_command('rc', self.cmd_rc, "RC input control",
                      ['<%s|all>' % x])
     self.add_command('switch', self.cmd_switch,
                      "flight mode switch control", ['<0|1|2|3|4|5|6>'])
     self.rc_settings = mp_settings.MPSettings([('override_hz', float, 5.0)
                                                ])
     if self.sitl_output:
         self.rc_settings.override_hz = 20.0
     self.add_completion_function('(RCSETTING)',
                                  self.rc_settings.completion)
     self.override_period = mavutil.periodic_event(
         self.rc_settings.override_hz)
Exemplo n.º 23
0
    def __init__(self, mpstate):
        super(UserAlertsModule, self).__init__(mpstate,
                                               "useralerts",
                                               public=True)

        self.url = "https://firmware.ardupilot.org/useralerts/manifest.json"
        self.testurl = "https://firmware.ardupilot.org/useralerts/examplemanifest.json"

        # The useTest setting allows the user to query the example database
        # instead of the real database
        # The filterBoard setting determines whether User Alerts are filtered
        # by the hardwareLimited field.
        self.alerts_settings = mp_settings.MPSettings([
            ('useTest', bool, False), ('filterBoard', bool, True)
        ])
        self.add_completion_function('(ALERTSETTING)',
                                     self.alerts_settings.completion)

        self.add_command('useralerts', self.cmd_check, "Check User Alerts",
                         ["check", "set (ALERTSETTING)"])

        self.board = None
        self.version = None
Exemplo n.º 24
0
 def __init__(self, mpstate):
     super(FTPModule, self).__init__(mpstate, "ftp", public=True)
     self.add_command('ftp', self.cmd_ftp, "file transfer", [
         "<list|get|rm|rmdir|rename|mkdir|crc|cancel|status>",
         "set (FTPSETTING)", "put (FILENAME) (FILENAME)"
     ])
     self.ftp_settings = mp_settings.MPSettings([
         ('debug', int, 0), ('pkt_loss_tx', int, 0),
         ('pkt_loss_rx', int, 0), ('max_backlog', int, 5),
         ('burst_read_size', int, 110), ('retry_time', float, 0.5)
     ])
     self.add_completion_function('(FTPSETTING)',
                                  self.ftp_settings.completion)
     self.seq = 0
     self.session = 0
     self.network = 0
     self.last_op = None
     self.fh = None
     self.filename = None
     self.callback = None
     self.total_size = 0
     self.read_gaps = []
     self.read_gap_times = {}
     self.last_gap_send = None
     self.read_retries = 0
     self.duplicates = 0
     self.last_read = None
     self.last_burst_read = None
     self.op_start = None
     self.dir_offset = 0
     self.write_wait = False
     self.last_op_time = time.time()
     self.rtt = 0.5
     self.reached_eof = False
     self.backlog = 0
     self.burst_size = self.ftp_settings.burst_read_size
Exemplo n.º 25
0
 def __init__(self, mpstate):
     super(GasHeliModule, self).__init__(mpstate, "gas_heli", "Gas Heli", public=False)
     self.console.set_status('IGN', 'IGN', row=4)
     self.console.set_status('THR', 'THR', row=4)
     self.console.set_status('RPM', 'RPM: 0', row=4)
     self.add_command('gasheli', self.cmd_gasheli,
                      'gas helicopter control',
                      ['<start|stop>',
                       'set (GASHELISETTINGS)'])
     self.gasheli_settings = mp_settings.MPSettings(
         [ ('ignition_chan', int, 0),
           ('ignition_disable_time', float, 0.5),
           ('ignition_stop_time', float, 3),
           ('starter_chan', int, 0),
           ('starter_time', float, 3.0),
           ('starter_pwm_on', int, 2000),
           ('starter_pwm_off', int, 1000),
           ]
         )
     self.add_completion_function('(GASHELISETTINGS)', self.gasheli_settings.completion)
     self.starting_motor = False
     self.stopping_motor = False
     self.motor_t1 = None
     self.old_override = 0
Exemplo n.º 26
0
DNFZ_types = {
    'Aircraft': 1,
    'Weather': 20000,
    'BirdMigrating': 30000,
    'BirdOfPrey': 40000
}

from 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'''
    def __init__(self, DNFZ_type):
        if not DNFZ_type in DNFZ_types:
            raise ('Bad DNFZ type %s' % DNFZ_type)
        self.DNFZ_type = DNFZ_type
        self.pkt = {
            'category': 0,
            'I010': {
Exemplo n.º 27
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 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",
        }