Exemplo n.º 1
0
    def launch_browser(self, data):
        """
        data: AdhocMedias, which is a list of AdhocMedia objects

        Turns these medias into AdhocBrowsers and then publishes them
        """
        msg = AdhocBrowsers()
        for media in data.medias:
            url = add_url_params(self.url,
                                 src=media.url,
                                 leader=self.leader,
                                 autoplay=self.autoplay,
                                 show_controls=self.show_controls,
                                 rosbridge_port=self.ros_port,
                                 rosbridge_host=self.ros_host,
                                 syncRate=self.sync_rate,
                                 frameLatency=self.frame_latency,
                                 pingInterval=self.ping_interval,
                                 hardSyncDiff=self.hard_sync_diff,
                                 minPlaybackRate=self.min_playbackrate,
                                 maxPlaybackRate=self.max_playbackrate)
            url = url2pathname(url)
            rospy.logdebug('url for media: %s' % url)
            new_browser = AdhocBrowser()
            new_browser.id = 'adhoc_media_browser_%s' % self.viewport_name
            new_browser.geometry = media.geometry
            new_browser.url = url
            msg.browsers.append(new_browser)
            rospy.loginfo("New browser URL: %s" % url)

        self.publisher.publish(msg)
Exemplo n.º 2
0
    def build_state(self):
        """
        Calls state tracking service and handles all url grabbing
        """
        current_state = self.last_uscs_service().message
        try:
            current_state = json.loads(current_state)
        except:
            rospy.logerr("Error parsing last uscs message as json")
            return

        windows = current_state.get('windows', [])
        for window in windows:
            url = self.grab_url(window)
            if url is None:
                continue
            # adding cms_protocol and cms_port for the portal launcher
            # only needed on the kiosk
            if window.get('presentation_viewport', None) == 'kiosk':
                # default port and protocol
                protocol = 'http'
                port = '8088'
                if 'https' in url:
                    protocol = 'https'
                    port = '443'
                window['assets'] = [add_url_params(url, cms_protocol=protocol, cms_port=port)]

        current_state = self.handle_tactile(current_state)
        return current_state
Exemplo n.º 3
0
    def launch_browser(self, data):
        """
        data: AdhocMedias, which is a list of AdhocMedia objects

        Turns these medias into AdhocBrowsers and then publishes them
        """
        msg = AdhocBrowsers()
        for media in data.medias:
            url = add_url_params(
                self.url, src=media.url,
                leader=self.leader,
                autoplay=self.autoplay,
                show_controls=self.show_controls,
                rosbridge_port=self.ros_port,
                rosbridge_host=self.ros_host,
                syncRate=self.sync_rate,
                frameLatency=self.frame_latency,
                pingInterval=self.ping_interval,
                hardSyncDiff=self.hard_sync_diff,
                minPlaybackRate=self.min_playbackrate,
                maxPlaybackRate=self.max_playbackrate)
            url = url2pathname(url)
            rospy.logdebug('url for media: %s' % url)
            new_browser = AdhocBrowser()
            new_browser.id = 'adhoc_media_browser_%s' % self.viewport_name
            new_browser.geometry = media.geometry
            new_browser.url = url
            msg.browsers.append(new_browser)
            rospy.loginfo("New browser URL: %s" % url)

        self.publisher.publish(msg)
Exemplo n.º 4
0
def main():
    rospy.init_node(NODE_NAME)

    viewports = str(rospy.get_param('~viewports'))
    viewports = [x.strip() for x in viewports.split(',')]
    geometry = util.combine_viewport_geometries(viewports)
    url = str(rospy.get_param('~url', DEFAULT_URL))
    field_of_view = float(rospy.get_param('~fov', DEFAULT_FOV))
    yaw_offset = float(rospy.get_param('~yaw_offset', 0))
    yaw_offsets = str(rospy.get_param('~yaw_offsets', yaw_offset))
    leader = str(rospy.get_param('~leader', 'false'))
    clock_addr = rospy.get_param('~clock_addr', 'ws://localhost:9091')
    depend_on_webserver = rospy.get_param('~depend_on_webserver', False)
    depend_on_rosbridge = rospy.get_param('~depend_on_rosbridge', False)
    rosbridge_host = rospy.get_param('~rosbridge_host', '127.0.0.1')
    rosbridge_port = rospy.get_param('~rosbridge_port', 9090)
    rosbridge_secure = rospy.get_param('~rosbridge_secure', 'false')
    kiosk = rospy.get_param('~kiosk', True)

    url = add_url_params(url,
                         hFov=field_of_view,
                         master=leader,
                         clockAddr=clock_addr,
                         yawOffsets=yaw_offsets,
                         rosbridgeHost=rosbridge_host,
                         rosbridgePort=rosbridge_port,
                         rosbridgeSecure=rosbridge_secure)

    host = discover_host_from_url(url)
    port = discover_port_from_url(url)
    timeout = rospy.get_param('/global_dependency_timeout', 15)

    check_www_dependency(depend_on_webserver, host, port, 'panovideo server', timeout)
    check_www_dependency(depend_on_webserver, rosbridge_host, rosbridge_port, 'rosbridge', timeout)

    x_available_or_raise(timeout)

    slug = "lg_panovideo__" + str(geometry).replace('\n', '_').replace(': ', '_')
    managed_browser = ManagedAdhocBrowser(url=url, geometry=geometry, slug=slug, kiosk=kiosk)

    # set initial state
    state = ApplicationState.STOPPED
    managed_browser.set_state(state)

    make_soft_relaunch_callback(managed_browser.handle_soft_relaunch, groups=['panovideo'])

    def handle_scene(scene):
        has_panovideo = has_activity(scene, 'panovideo')
        if has_panovideo:
            managed_browser.set_state(ApplicationState.VISIBLE)
        else:
            managed_browser.set_state(ApplicationState.STOPPED)

    on_new_scene(handle_scene)

    rospy.spin()
Exemplo n.º 5
0
    def handle_tactile(self, state):
        for window in state.get('windows', []):
            if window.get('activity', '') != 'browser':
                continue

            for i in range(len(window.get('assets', []))):
                if ('maps.google.com' in window['assets'][i] or "google.com/maps" in window['assets'][i]) and \
                        self.tactile_flag not in window['assets'][i]:
                    # add a param to be sure there is at least one param (HACK)
                    url = add_url_params(window['assets'][i], foo='bar')
                    url += '&%s' % self.tactile_flag
                    window['assets'][i] = url
                # adding cms_protocol and cms_port for the portal launcher
                # only needed on the kiosk
                #if window.get('presentation_viewport', None) == 'kiosk':
                #    window['assets'][i] = add_url_params(window['assets'][i], cms_protocol='https', cms_port='443')

        return state
Exemplo n.º 6
0
def main():
    rospy.init_node(NODE_NAME, anonymous=True)

    geometry = ManagedWindow.get_viewport_geometry()
    server_type = rospy.get_param('~server_type', 'streetview')
    url = str(rospy.get_param('~url', DEFAULT_URL))
    field_of_view = float(rospy.get_param('~fov', DEFAULT_FOV))
    pitch_offset = float(rospy.get_param('~pitch_offset', 0))
    show_links = str(rospy.get_param('~show_links', False)).lower()
    show_fps = str(rospy.get_param('~show_fps', False)).lower()
    show_attribution = str(rospy.get_param('~show_attribution', False)).lower()
    yaw_offset = float(rospy.get_param('~yaw_offset', 0))
    yaw_offsets = str(rospy.get_param('~yaw_offsets', yaw_offset))
    leader = str(rospy.get_param('~leader', 'false'))
    tilt = str(rospy.get_param('~tilt', 'false'))
    depend_on_webserver = rospy.get_param('~depend_on_webserver', False)
    depend_on_rosbridge = rospy.get_param('~depend_on_rosbridge', False)
    rosbridge_host = rospy.get_param('~rosbridge_host', '127.0.0.1')
    rosbridge_port = rospy.get_param('~rosbridge_port', 9090)
    rosbridge_secure = rospy.get_param('~rosbridge_secure', 'false')
    zoom = str(rospy.get_param('~zoom', 'false')).lower()
    initial_zoom = rospy.get_param('~initial_zoom', 3)
    kiosk = rospy.get_param('~kiosk', True)
    map_api_key = rospy.get_param('/google/maps_api_key', None)

    # put parameters into one big url
    url = add_url_params(url,
                         zoom=zoom,
                         initialZoom=initial_zoom,
                         fov=field_of_view,
                         pitchOffset=pitch_offset,
                         showLinks=show_links,
                         showFPS=show_fps,
                         showAttribution=show_attribution,
                         leader=leader,
                         yawOffset=yaw_offset,
                         yawOffsets=yaw_offsets,
                         tilt=tilt,
                         rosbridgeHost=rosbridge_host,
                         rosbridgePort=rosbridge_port,
                         rosbridgeSecure=rosbridge_secure)

    rospy.loginfo('Use Google maps API key: {}'.format(map_api_key))

    if map_api_key:
        url = add_url_params(url, map_api_key=map_api_key)

    # check if server is already there
    host = discover_host_from_url(url)
    port = discover_port_from_url(url)
    timeout = rospy.get_param('/global_dependency_timeout', 15)

    check_www_dependency(depend_on_webserver, host, port, 'streetview server', timeout)
    check_www_dependency(depend_on_webserver, rosbridge_host, rosbridge_port, 'rosbridge', timeout)

    x_available_or_raise(timeout)

    # create the managed browser
    slug = server_type + "__" + "_fov-" + str(field_of_view) + "__" + "_yaw-" + str(yaw_offset) + "__" + "_pitch-" + str(pitch_offset)
    managed_browser = ManagedAdhocBrowser(url=url, geometry=geometry, slug=slug, kiosk=kiosk)

    # set initial state
    state = ApplicationState.STOPPED
    managed_browser.set_state(state)

    def state_proxy(msg):
        if not msg.state == ApplicationState.VISIBLE:
            managed_browser.set_state(ApplicationState.HIDDEN)
        else:
            managed_browser.set_state(ApplicationState.VISIBLE)

    # listen to state messages
    rospy.Subscriber('/%s/state' % server_type, ApplicationState, state_proxy)
    make_soft_relaunch_callback(managed_browser.handle_soft_relaunch, groups=['streetview'])

    rospy.spin()
Exemplo n.º 7
0
def main():
    rospy.init_node(NODE_NAME)

    geometry = ManagedWindow.get_viewport_geometry()

    url = rospy.get_param('~url', None)
    url_base = rospy.get_param('~url_base', 'http://lg-head/ros_touchscreens/ts/')
    command_line_args = rospy.get_param('~command_line_args', '')
    extra_logging = rospy.get_param('~extra_logging', False)

    # TODO (wz) director_host and director_port should be global

    director_host = rospy.get_param('~director_host', '42-a')
    director_port = rospy.get_param('~director_port', 8060)

    rosbridge_secure = rospy.get_param('~rosbridge_secure', 0)
    director_secure = rospy.get_param('~director_secure', 0)

    rosbridge_host = rospy.get_param('~rosbridge_host', '127.0.0.1')
    rosbridge_port = rospy.get_param('~rosbridge_port', 9090)
    ts_name = rospy.get_param('~ts_name', 'default')

    depend_on_rosbridge = rospy.get_param('~depend_on_rosbridge', False)
    depend_on_director = rospy.get_param('~depend_on_director', False)
    global_dependency_timeout = rospy.get_param('/global_dependency_timeout', 15)

    check_www_dependency(depend_on_rosbridge, rosbridge_host, rosbridge_port, 'rosbridge', global_dependency_timeout)
    check_www_dependency(depend_on_director, director_host, director_port, 'director', global_dependency_timeout)

    x_available_or_raise(global_dependency_timeout)

    if url:
        rospy.loginfo("got prepared full url: %s" % url)
    else:
        url = url_base + ts_name + "/"

        url = add_url_params(url,
                             director_host=director_host,
                             director_port=director_port,
                             director_secure=director_secure,
                             rosbridge_secure=rosbridge_secure,
                             rosbridge_host=rosbridge_host,
                             rosbridge_port=rosbridge_port)

        url = url2pathname(url)
        rospy.loginfo("assembled a url: %s" % url)

    scale_factor = rospy.get_param('~force_device_scale_factor', 1)
    debug_port = rospy.get_param('~debug_port', None)
    user_agent = rospy.get_param(
        '~user_agent', 'Mozilla/5.0(iPad; U; CPU iPhone OS 3_2 like Mac OS X; '
        'en-us AppleWebKit/531.21.10 (KHTML, like Gecko) ' +
        'Version/4.0.4 Mobile/7B314 Safari/531.21.10'
    )
    log_level = rospy.get_param('/logging/level', 0)

    browser = ManagedBrowser(
        geometry=geometry,
        url=url,
        log_level=log_level,
        command_line_args=command_line_args,
        log_stderr=extra_logging,
        force_device_scale_factor=scale_factor,
        remote_debugging_port=debug_port,
        user_agent=user_agent
    )

    browser.set_state(ApplicationState.VISIBLE)
    make_soft_relaunch_callback(browser.handle_soft_relaunch, groups=['touchscreen'])

    def handle_debug_sock_msg(msg):
        browser.send_debug_sock_msg(msg.data)

    rospy.Subscriber('{}/debug'.format(rospy.get_name()), String, handle_debug_sock_msg)

    rospy.spin()
Exemplo n.º 8
0
def main():
    rospy.init_node(NODE_NAME, anonymous=True)

    geometry = ManagedWindow.get_viewport_geometry()
    server_type = rospy.get_param('~server_type', 'streetview')
    url = str(rospy.get_param('~url', DEFAULT_URL))
    field_of_view = float(rospy.get_param('~fov', DEFAULT_FOV))
    pitch_offset = float(rospy.get_param('~pitch_offset', 0))
    show_links = str(rospy.get_param('~show_links', False)).lower()
    show_fps = str(rospy.get_param('~show_fps', False)).lower()
    show_attribution = str(rospy.get_param('~show_attribution', False)).lower()
    yaw_offset = float(rospy.get_param('~yaw_offset', 0))
    yaw_offsets = str(rospy.get_param('~yaw_offsets', yaw_offset))
    leader = str(rospy.get_param('~leader', 'false'))
    tilt = str(rospy.get_param('~tilt', 'false'))
    depend_on_webserver = rospy.get_param('~depend_on_webserver', False)
    depend_on_rosbridge = rospy.get_param('~depend_on_rosbridge', False)
    rosbridge_host = rospy.get_param('~rosbridge_host', '127.0.0.1')
    rosbridge_port = rospy.get_param('~rosbridge_port', 9090)
    rosbridge_secure = rospy.get_param('~rosbridge_secure', 'false')
    zoom = str(rospy.get_param('~zoom', 'false')).lower()
    initial_zoom = rospy.get_param('~initial_zoom', 3)
    kiosk = rospy.get_param('~kiosk', True)
    map_api_key = rospy.get_param('~map_api_key', None)

    # put parameters into one big url
    url = add_url_params(url,
                         zoom=zoom,
                         initialZoom=initial_zoom,
                         fov=field_of_view,
                         pitchOffset=pitch_offset,
                         showLinks=show_links,
                         showFPS=show_fps,
                         showAttribution=show_attribution,
                         leader=leader,
                         yawOffset=yaw_offset,
                         yawOffsets=yaw_offsets,
                         tilt=tilt,
                         rosbridgeHost=rosbridge_host,
                         rosbridgePort=rosbridge_port,
                         rosbridgeSecure=rosbridge_secure)

    rospy.loginfo('Use Google maps API key: {}'.format(map_api_key))

    if map_api_key:
        url = add_url_params(url, map_api_key=map_api_key)

    # check if server is already there
    host = discover_host_from_url(url)
    port = discover_port_from_url(url)
    timeout = rospy.get_param('/global_dependency_timeout', 15)

    check_www_dependency(depend_on_webserver, host, port, 'streetview server', timeout)
    check_www_dependency(depend_on_webserver, rosbridge_host, rosbridge_port, 'rosbridge', timeout)

    x_available_or_raise(timeout)

    # create the managed browser
    slug = server_type + "__" + "_fov-" + str(field_of_view) + "__" + "_yaw-" + str(yaw_offset) + "__" + "_pitch-" + str(pitch_offset)
    managed_browser = ManagedAdhocBrowser(url=url, geometry=geometry, slug=slug, kiosk=kiosk)

    # set initial state
    state = ApplicationState.STOPPED
    managed_browser.set_state(state)

    def state_proxy(msg):
        if not msg.state == ApplicationState.VISIBLE:
            managed_browser.set_state(ApplicationState.HIDDEN)
        else:
            managed_browser.set_state(ApplicationState.VISIBLE)

    # listen to state messages
    rospy.Subscriber('/%s/state' % server_type, ApplicationState, state_proxy)
    make_soft_relaunch_callback(managed_browser.handle_soft_relaunch, groups=['streetview'])

    rospy.spin()
Exemplo n.º 9
0
def main():
    rospy.init_node(NODE_NAME)

    viewports = str(rospy.get_param('~viewports'))
    viewports = [x.strip() for x in viewports.split(',')]
    geometry = util.combine_viewport_geometries(viewports)
    url = str(rospy.get_param('~url', DEFAULT_URL))
    field_of_view = float(rospy.get_param('~fov', DEFAULT_FOV))
    yaw_offset = float(rospy.get_param('~yaw_offset', 0))
    yaw_offsets = str(rospy.get_param('~yaw_offsets', yaw_offset))
    leader = str(rospy.get_param('~leader', 'false'))
    clock_addr = rospy.get_param('~clock_addr', 'ws://localhost:9091')
    depend_on_webserver = rospy.get_param('~depend_on_webserver', False)
    depend_on_rosbridge = rospy.get_param('~depend_on_rosbridge', False)
    rosbridge_host = rospy.get_param('~rosbridge_host', '127.0.0.1')
    rosbridge_port = rospy.get_param('~rosbridge_port', 9090)
    rosbridge_secure = rospy.get_param('~rosbridge_secure', 'false')
    kiosk = rospy.get_param('~kiosk', True)

    url = add_url_params(url,
                         hFov=field_of_view,
                         master=leader,
                         clockAddr=clock_addr,
                         yawOffsets=yaw_offsets,
                         rosbridgeHost=rosbridge_host,
                         rosbridgePort=rosbridge_port,
                         rosbridgeSecure=rosbridge_secure)

    host = discover_host_from_url(url)
    port = discover_port_from_url(url)
    timeout = rospy.get_param('/global_dependency_timeout', 15)

    check_www_dependency(depend_on_webserver, host, port, 'panovideo server',
                         timeout)
    check_www_dependency(depend_on_webserver, rosbridge_host, rosbridge_port,
                         'rosbridge', timeout)

    x_available_or_raise(timeout)

    slug = "lg_panovideo__" + str(geometry).replace('\n', '_').replace(
        ': ', '_')
    managed_browser = ManagedAdhocBrowser(url=url,
                                          geometry=geometry,
                                          slug=slug,
                                          kiosk=kiosk)

    # set initial state
    state = ApplicationState.STOPPED
    managed_browser.set_state(state)

    make_soft_relaunch_callback(managed_browser.handle_soft_relaunch,
                                groups=['panovideo'])

    def handle_scene(scene):
        has_panovideo = has_activity(scene, 'panovideo')
        if has_panovideo:
            managed_browser.set_state(ApplicationState.VISIBLE)
        else:
            managed_browser.set_state(ApplicationState.STOPPED)

    on_new_scene(handle_scene)

    rospy.spin()