#!/usr/bin/env python
#################################################################################
# Copyright 2018 ROBOTIS CO., LTD.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
#     http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
#################################################################################

# Authors: Gilbert #

from __future__ import print_function
import rospy
import actionlib
import turtlebot3_example.msg
import sys

msg = """
patrol your TurtleBot3!
-----------------------
mode : s - Patrol to Square
       t - Patrol to Triangle
       c - Patrol to Circle

area : Square, Triangle mode - length of side (m)
       Circle mode - radius (m)

count - patrol count

If you want to close, insert 'x'
"""

class Client():
    def __init__(self):
        rospy.loginfo("wait for server")
        self.client()

    def getkey(self):
        mode, area, count = raw_input("| mode | area | count |\n").split()
        mode, area, count = [str(mode), float(area), int(count)]

        if mode == 's':
            mode = 1
        elif mode == 't':
            mode = 2
        elif mode == 'c':
            mode = 3
        elif mode == 'x':
            self.shutdown()
        else:
            rospy.loginfo("you select wrong mode")

        return mode, area, count

    def client(self):
        client = actionlib.SimpleActionClient('turtlebot3', turtlebot3_example.msg.Turtlebot3Action)

        mode, area, count = self.getkey()
        client.wait_for_server()
        goal = turtlebot3_example.msg.Turtlebot3Goal()
        goal.goal.x = mode
        goal.goal.y = area
        goal.goal.z = count
        client.send_goal(goal)
        rospy.loginfo("send to goal")
        client.wait_for_result()

        rospy.loginfo(client.get_result())

    def shutdown(self):
        rospy.sleep(1)

if __name__ == '__main__':
    rospy.init_node('turtlebot3_client')
    try:
        while not rospy.is_shutdown():
            print (msg)
            result = Client()
    except:
        print("program close.", file=sys.stderr)
