#!/usr/bin/env python
#
# License: BSD
#   https://raw.github.com/robotics-in-concert/rocon_multimaster/license/LICENSE
#

##############################################################################
# Imports
##############################################################################

import sys
import argparse
import itertools
import rospy
import rocon_gateway
import rocon_gateway_utils
import rocon_console.console as console

##############################################################################
# Functions
##############################################################################


def parse_arguments():
    parser = argparse.ArgumentParser(description='Prettifies remote gateway info')
    args = parser.parse_args()
    return args

##############################################################################
# Main
##############################################################################

if __name__ == '__main__':

    rospy.init_node('pull', anonymous=True)
    args = parse_arguments()
    gateway_namespace = None
    gateway_info = None

    try:
        gateway_namespace = rocon_gateway_utils.resolve_local_gateway()
        gateway = rocon_gateway_utils.resolve_gateway_info(gateway_namespace)
    except rocon_gateway.GatewayError, e:
        console.error(str(e))
        sys.exit(1)
    console.pretty_print("Gateway\n", console.bold)
    print("  Namespace   : %s" % gateway_namespace)
    print("  Name        : %s" % rocon_gateway_utils.gateway_basename(gateway.name))
    print("  Hash Name   : %s" % gateway.name)
    print("  Namespace   : %s" % gateway_namespace)
    print("  Ip/Hostname : %s" % gateway.ip)
    print("  Connected   : %s" % gateway.connected)
    if gateway.hub_names:
        max_len = 0
        max_width = max([len(hub) for hub in gateway.hub_names])
        print("  Hubs        : %-*s [%s]" % (max_width, gateway.hub_names[0], gateway.hub_uris[0]))
        for hub, uri in itertools.izip(gateway.hub_names[1:], gateway.hub_uris[1:]):
            print("              : %-*s [%s]" % (max_width, hub, uri))
    print("  Firewall    : %s" % gateway.firewall)

    print("  Public Watchlist")
    if len(gateway.public_watchlist) == 0:
        print("       : -")
    for rule in gateway.public_watchlist:
        print("       : "),
        console.pretty_print(rule.name, console.green)
        print("-"),
        console.pretty_print(rule.type, console.cyan)
        print("-"),
        console.pretty_print(rule.node + "\n", console.yellow)

    print("  Public Interface")
    if len(gateway.public_interface) == 0:
        print("       : -")
    for rule in gateway.public_interface:
        print("       : "),
        console.pretty_print(rule.name, console.green)
        print("-"),
        console.pretty_print(rule.type, console.cyan)
        print("-"),
        console.pretty_print(rule.node + "\n", console.yellow)

    print("  Flip Watchlist")
    if len(gateway.flip_watchlist) == 0:
        print("       : -")
    for remote_rule in gateway.flip_watchlist:
        if remote_rule.rule.node == 'None':
            remote_rule.rule.node = '.*'
        print("       : "),
        console.pretty_print(remote_rule.gateway, console.red)
        print("-"),
        console.pretty_print(remote_rule.rule.name, console.green)
        print("-"),
        console.pretty_print(remote_rule.rule.type, console.cyan)
        print("-"),
        console.pretty_print(remote_rule.rule.node + "\n", console.yellow)

    print("  Flipped Connections")
    if len(gateway.flipped_connections) == 0:
        print("       : -")
    for remote_rule in gateway.flipped_connections:
        print("       : "),
        console.pretty_print(remote_rule.remote_rule.gateway, console.red)
        print("-"),
        console.pretty_print(remote_rule.remote_rule.rule.name, console.green)
        print("-"),
        console.pretty_print(remote_rule.remote_rule.rule.type, console.cyan)
        print("-"),
        console.pretty_print(remote_rule.remote_rule.rule.node, console.yellow)
        print(" [" + remote_rule.status + "]")

    print("  Flipped in Connections")
    if len(gateway.flipped_in_connections) == 0:
        print("       : -")
    for remote_rule in gateway.flipped_in_connections:
        print("       : "),
        console.pretty_print(remote_rule.gateway, console.red)
        print("-"),
        console.pretty_print(remote_rule.rule.name, console.green)
        print("-"),
        console.pretty_print(remote_rule.rule.type, console.cyan)
        print("-"),
        console.pretty_print(remote_rule.rule.node + "\n", console.yellow)

    print("  Pull Watchlist")
    if len(gateway.pull_watchlist) == 0:
        print("       : -")
    for remote_rule in gateway.pull_watchlist:
        if remote_rule.rule.node == 'None':
            remote_rule.rule.node = '.*'
        print("       : "),
        console.pretty_print(remote_rule.gateway, console.red)
        print("-"),
        console.pretty_print(remote_rule.rule.name, console.green)
        print("-"),
        console.pretty_print(remote_rule.rule.type, console.cyan)
        print("-"),
        console.pretty_print(remote_rule.rule.node + "\n", console.yellow)

    print("  Pulled Connections")
    if len(gateway.pulled_connections) == 0:
        print("       : -")
    for remote_rule in gateway.pulled_connections:
        print("       : "),
        console.pretty_print(remote_rule.gateway, console.red)
        print("-"),
        console.pretty_print(remote_rule.rule.name, console.green)
        print("-"),
        console.pretty_print(remote_rule.rule.type, console.cyan)
        print("-"),
        console.pretty_print(remote_rule.rule.node + "\n", console.yellow)
