Exemplo n.º 1
0
    def halt(self):
        # 全てのロボットの制御を切る
        for robot_id in range(self._ID_NUM):
            control_target = ControlTarget()
            control_target.robot_id = robot_id
            control_target.control_enable = False

            self._pubs_control_target[robot_id].publish(control_target)

        # ビジー状態を解除して、halt後に動けるようにする
        self._is_busy = False
Exemplo n.º 2
0
    def halt(self):
        # 全てのロボットの速度を0にする
        for robot_id in range(self._ID_NUM):
            control_target = ControlTarget()
            control_target.robot_id = robot_id
            control_target.control_enable = True
            control_target.goal_velocity = Pose2D(0, 0, 0)

            self._pubs_control_target[robot_id].publish(control_target)

        # ビジー状態を解除して、halt後に動けるようにする
        self._is_busy = False
Exemplo n.º 3
0
    def _publish_line_positions(self, move_forward=True):
        START_X = 1.0
        MARGIN = 0.6
        TARGET_Y = 1.0
        THETA = math.pi * 0.5

        # 横一直線の目標位置を送信する
        for robot_id in range(self._ID_NUM):
            control_target = ControlTarget()
            control_target.robot_id = robot_id
            control_target.control_enable = True

            # ゴール位置を生成
            pose = Pose2D()
            pose.x = START_X + MARGIN * robot_id
            pose.y = TARGET_Y

            if move_forward is False:
                pose.y *= -1.0

            pose.theta = THETA
            control_target.path.append(pose)

            # ゴール地点での速度
            control_target.goal_velocity = Pose2D(0.0, 0.0, 0.0)

            # キック威力 0.0 ~ 1.0
            control_target.kick_power = 0.0
            control_target.chip_enable = False
            control_target.dribble_power = 0.0

            self._pubs_control_target[robot_id].publish(control_target)
Exemplo n.º 4
0
    def __init__(self):
        self._ID_NUM = 16

        self._is_busy = False
        self._move_forward = True

        self._is_arrived = []
        self._control_target = []

        self._pubs_control_target = []
        self._subs_is_arrived = []

        self.last_time = rospy.Time.now()

        color = 'blue'
        for robot_id in range(self._ID_NUM):
            self._is_arrived.append(False)
            self._control_target.append(ControlTarget())

            # 末尾に16進数の文字列をつける
            topic_id = hex(robot_id)[2:]

            topic_name = 'consai2_game/control_target_' + color + '_' + topic_id
            pub_control_target = rospy.Publisher(topic_name,
                                                 ControlTarget,
                                                 queue_size=1)
            self._pubs_control_target.append(pub_control_target)

            topic_name = 'consai2_control/is_arrived_' + color + '_' + topic_id
            sub_is_arrived = rospy.Subscriber(topic_name,
                                              Bool,
                                              self._callback_is_arrived,
                                              queue_size=1,
                                              callback_args=robot_id)
            self._subs_is_arrived.append(sub_is_arrived)
Exemplo n.º 5
0
    def update(self):
        Observer.update_ball_is_moving(self._ball_info)
        Observer.update_role_is_exist(self._roledecision._rolestocker._role_is_exist)

        self._roledecision.set_disappeared([i.disappeared for i in self._robot_info['our']])
        if tool.is_in_defense_area(self._ball_info.pose, 'our') is False \
               and Observer.ball_is_moving() is False:
            # ボールが自チームディフェンスエリア外にあり
            # ボールが動いていないとき、アタッカーの交代を考える
            self._roledecision.check_ball_dist([i.pose for i in self._robot_info['our']], self._ball_info)
        self._roledecision.event_observer()
        defense_num = self._roledecision._rolestocker._defense_num

        self._obstacle_avoidance.update_obstacles(self._ball_info, self._robot_info)
        for our_info in self._robot_info['our']:
            robot_id = our_info.robot_id
            target = ControlTarget()
            # ロールの更新
            self._robot_node[robot_id]._my_role = self._roledecision._rolestocker._my_role[robot_id]
            if our_info.disappeared:
                # ロボットが消えていたら停止
                target = self._robot_node[robot_id].get_sleep()
            else:
                # ロボットの状態を更新
                self._robot_node[robot_id].set_state(
                        our_info.pose, our_info.velocity)
                # 目標位置を生成
                target = self._robot_node[robot_id].get_action(
                        self._decoded_referee,
                        self._obstacle_avoidance,
                        self._ball_info,
                        self._robot_info,
                        defense_num)

            self._pubs_control_target[robot_id].publish(target)
Exemplo n.º 6
0
    def update(self):
        for our_info in self._robot_info['our']:
            robot_id = our_info.robot_id
            target = ControlTarget()
            if our_info.disappeared:
                # ロボットが消えていたら停止
                target = self._robot_node[robot_id].get_sleep()

                # ボールとの距離を初期化
                self._dist_to_ball[robot_id] = self._FAR_DISTANCE

            else:
                # アタッカー情報をセット
                self._robot_node[robot_id].set_attacker(
                    self._i_am_attacker(robot_id, our_info.pose))

                # ロボットの状態を更新
                self._robot_node[robot_id].set_state(our_info.pose,
                                                     our_info.velocity)
                # 目標位置を生成
                # target = self._robot_node[robot_id].get_action(
                # self._decoded_referee,
                # self._ball_info)
                target = self._robot_node[robot_id].get_action(
                    self._decoded_referee, self._ball_info, self._robot_info)

            self._pubs_control_target[robot_id].publish(target)
Exemplo n.º 7
0
def velocity_control_example(target_id, publisher):
    control_target = ControlTarget()

    # ロボットID
    control_target.robot_id = target_id
    # キック・ドリブルをFalse
    control_target.kick_power = 0.0
    control_target.chip_enable = False
    control_target.dribble_power = 0.0

    # Trueで走行開始
    control_target.control_enable = True

    STOP_TIME = 2.0
    MOVE_TIME = 2.0

    publish_velocity(control_target, Pose2D(0, 0, 0), publisher, "Stop:",
                     STOP_TIME)

    publish_velocity(control_target, Pose2D(1, 0, 0), publisher, "Move:",
                     MOVE_TIME)
    publish_velocity(control_target, Pose2D(0, 0, 0), publisher, "Stop:",
                     STOP_TIME)

    publish_velocity(control_target, Pose2D(-1, 0, 0), publisher, "Move:",
                     MOVE_TIME)
    publish_velocity(control_target, Pose2D(0, 0, 0), publisher, "Stop:",
                     STOP_TIME)

    publish_velocity(control_target, Pose2D(0, 1, 0), publisher, "Move:",
                     MOVE_TIME)
    publish_velocity(control_target, Pose2D(0, 0, 0), publisher, "Stop:",
                     STOP_TIME)

    publish_velocity(control_target, Pose2D(0, -1, 0), publisher, "Move:",
                     MOVE_TIME)
    publish_velocity(control_target, Pose2D(0, 0, 0), publisher, "Stop:",
                     STOP_TIME)

    publish_velocity(control_target, Pose2D(0, 0, math.pi), publisher, "Move:",
                     MOVE_TIME)
    publish_velocity(control_target, Pose2D(0, 0, 0), publisher, "Stop:",
                     STOP_TIME)

    publish_velocity(control_target, Pose2D(0, 0, -math.pi), publisher,
                     "Move:", MOVE_TIME)
    publish_velocity(control_target, Pose2D(0, 0, 0), publisher, "Stop:",
                     STOP_TIME)

    control_target.control_enable = False
    publish_velocity(control_target, Pose2D(0, 0, 0), publisher, "Finish:",
                     STOP_TIME)
Exemplo n.º 8
0
    def __init__(self, robot_id):

        self._MY_ID = robot_id

        self._control_target = ControlTarget()
        self._control_target.robot_id = robot_id
        self._control_target.control_enable = False

        self._my_pose = Pose2D()
        self._my_velocity = Pose2D()

        self._is_attacker = False
        self._is_goalie = False
Exemplo n.º 9
0
def path_example(target_id, publisher):
    # 制御目標値を生成
    control_target = ControlTarget()

    # ロボットID
    control_target.robot_id = target_id
    # Trueで走行開始
    control_target.control_enable = True

    # 経由位置1
    pose = Pose2D()
    pose.x = 1.0  # meter
    pose.y = 1.0  # meter
    pose.theta = 0.0  # radians
    control_target.path.append(pose)

    # 経由位置2
    pose = Pose2D()
    pose.x = -1.0  # meter
    pose.y = 1.0  # meter
    pose.theta = 0.0  # radians
    control_target.path.append(pose)

    # 経由位置3
    pose = Pose2D()
    pose.x = -1.0  # meter
    pose.y = -1.0  # meter
    pose.theta = 0.0  # radians
    control_target.path.append(pose)

    # ゴール位置
    pose = Pose2D()
    pose.x = 0.0  # meter
    pose.y = 0.0  # meter
    pose.theta = 0.0  # radians
    control_target.path.append(pose)

    # ゴール地点での速度
    goal_velocity = Pose2D(0.0, 0.0, 0.0)
    control_target.goal_velocity = goal_velocity

    # キック威力 0.0 ~ 1.0
    control_target.kick_power = 0.0
    control_target.chip_enable = False
    control_target.dribble_power = 0.0

    publisher.publish(control_target)
Exemplo n.º 10
0
    def __init__(self):
        QUEUE_SIZE = 10
        self._COLORS = ['blue', 'yellow']

        self._MAX_VELOCITY = 4.0  # m/s
        self._MAX_ANGLE_VELOCITY = 2.0 * math.pi  # rad/s
        self._MAX_ACCELERATION = 1.0 / 60.0  # m/s^2 / frame
        self._MAX_ANGLE_ACCELERATION = 1.0 * math.pi / 60.0  # rad/s^2 / frame
        self._POSE_P_GAIN = 1.0
        self._ARRIVED_THRESH = 0.1  # meters 目標位置に到着したかどうかのしきい値
        self._APPROACH_THRESH = 0.5  # meters 経由位置に近づいたかどうかのしきい値

        self._MAX_ID = rospy.get_param('consai2_description/max_id', 15)

        # フィールド座標系の制御速度
        # PID制御のため、前回の制御速度を保存する
        self._control_velocity = {'blue': [], 'yellow': []}
        for color in self._COLORS:
            for robot_id in range(self._MAX_ID + 1):
                self._control_velocity[color].append(Pose2D())

        # 経路追従のためのインデックス
        self._path_index = {'blue': [], 'yellow': []}

        self._robot_info = {'blue': [], 'yellow': []}
        self._subs_robot_info = {'blue': [], 'yellow': []}

        self._control_target = {'blue': [], 'yellow': []}
        self._subs_control_target = {'blue': [], 'yellow': []}

        self._pubs_is_arrived = {'blue': [], 'yellow': []}

        for color in self._COLORS:
            for robot_id in range(self._MAX_ID + 1):
                self._robot_info[color].append(RobotInfo())
                self._control_target[color].append(ControlTarget())
                self._path_index[color].append(0)

                # 末尾に16進数の文字列をつける
                topic_id = hex(robot_id)[2:]

                topic_name = 'vision_wrapper/robot_info_' + color + '_' + topic_id
                sub_robot_info = rospy.Subscriber(topic_name,
                                                  RobotInfo,
                                                  self._callback_robot_info,
                                                  queue_size=QUEUE_SIZE,
                                                  callback_args=color)
                self._subs_robot_info[color].append(sub_robot_info)

                topic_name = 'consai2_game/control_target_' + color + '_' + topic_id
                sub_control_target = rospy.Subscriber(
                    topic_name,
                    ControlTarget,
                    self._callback_control_target,
                    queue_size=QUEUE_SIZE,
                    callback_args=color)
                self._subs_control_target[color].append(sub_control_target)

                topic_name = 'consai2_control/is_arrived_' + color + '_' + topic_id
                pub_is_arrived = rospy.Publisher(topic_name,
                                                 Bool,
                                                 queue_size=QUEUE_SIZE)
                self._pubs_is_arrived[color].append(pub_is_arrived)

        self._pub_commands = rospy.Publisher('consai2_control/robot_commands',
                                             RobotCommands,
                                             queue_size=QUEUE_SIZE)
Exemplo n.º 11
0
    def __init__(self):

        self._MAX_ID = rospy.get_param('consai2_description/max_id')
        # 直接操縦かcontrol経由の操縦かを決める
        self._DIRECT = rospy.get_param('~direct')
        # /consai2_examples/launch/joystick_example.launch でキー割り当てを変更する
        self._BUTTON_SHUTDOWN_1 = rospy.get_param('~button_shutdown_1')
        self._BUTTON_SHUTDOWN_2 = rospy.get_param('~button_shutdown_2')

        self._BUTTON_MOVE_ENABLE = rospy.get_param('~button_move_enable')
        self._AXIS_VEL_SURGE = rospy.get_param('~axis_vel_surge')
        self._AXIS_VEL_SWAY = rospy.get_param('~axis_vel_sway')
        self._AXIS_VEL_ANGULAR = rospy.get_param('~axis_vel_angular')

        self._BUTTON_KICK_ENABLE = rospy.get_param('~button_kick_enable')
        self._BUTTON_KICK_STRAIGHT = rospy.get_param('~button_kick_straight')
        self._BUTTON_KICK_CHIP = rospy.get_param('~button_kick_chip')
        self._AXIS_KICK_POWER = rospy.get_param('~axis_kick_power')

        self._BUTTON_DRIBBLE_ENABLE = rospy.get_param('~button_dribble_enable')
        self._AXIS_DRIBBLE_POWER = rospy.get_param('~axis_dribble_power')

        self._BUTTON_ID_ENABLE = rospy.get_param('~button_id_enable')
        self._AXIS_ID_CHANGE = rospy.get_param('~axis_id_change')

        self._BUTTON_COLOR_ENABLE = rospy.get_param('~button_color_enable')
        self._AXIS_COLOR_CHANGE = rospy.get_param('~axis_color_change')

        self._BUTTON_ALL_ID_1 = rospy.get_param('~button_all_id_1')
        self._BUTTON_ALL_ID_2 = rospy.get_param('~button_all_id_2')
        self._BUTTON_ALL_ID_3 = rospy.get_param('~button_all_id_3')
        self._BUTTON_ALL_ID_4 = rospy.get_param('~button_all_id_4')

        # indirect control用の定数
        self._BUTTON_PATH_ENABLE = rospy.get_param('~button_path_enable')
        self._BUTTON_ADD_POSE = rospy.get_param('~button_add_pose')
        self._BUTTON_DELETE_PATH = rospy.get_param('~button_delete_path')
        self._BUTTON_SEND_TARGET = rospy.get_param('~button_send_target')

        self._MAX_VEL_SURGE = 1.0
        self._MAX_VEL_SWAY = 1.0
        self._MAX_VEL_ANGULAR = math.pi

        self._MAX_KICK_POWER = 1.0  # DO NOT EDIT
        self._KICK_POWER_CONTROL = 0.1

        self._MAX_DRIBBLE_POWER = 1.0  # DO NOT EDIT
        self._DRIBBLE_POWER_CONTROL = 0.1

        self._indirect_control_enable = True

        # direct control用のパラメータ
        self._kick_power = 0.5
        self._dribble_power = 0.5
        self._robot_id = 0
        self._is_yellow = False
        self._all_member = False

        self._pub_commands = rospy.Publisher('consai2_control/robot_commands',
                                             RobotCommands,
                                             queue_size=1)

        self._joy_msg = None
        self._sub_joy = rospy.Subscriber('joy',
                                         Joy,
                                         self._callback_joy,
                                         queue_size=1)

        self._pub_joy_target = rospy.Publisher('consai2_examples/joy_target',
                                               ControlTarget,
                                               queue_size=1)
        self._joy_target = ControlTarget()
        self._joy_target.path.append(Pose2D())  # スタート位置をセット
Exemplo n.º 12
0
    def _indirect_control_update(self):
        # Controller経由でロボットを操縦する

        MOVE_GAIN = 0.04  # meters
        MOVE_GAIN_ANGLE = 0.04 * math.pi  # radians

        control_enable = True

        # メッセージを取得してない場合は抜ける
        if self._joy_msg is None:
            return

        color_or_id_changed = False
        current_joy_pose = self._joy_target.path[-1]

        # シャットダウン
        if self._joy_msg.buttons[self._BUTTON_SHUTDOWN_1] and\
                self._joy_msg.buttons[self._BUTTON_SHUTDOWN_2]:
            rospy.signal_shutdown('finish')
            return

        # チームカラーの変更
        if self._joy_msg.buttons[self._BUTTON_COLOR_ENABLE]:
            # カラー変更直後は操縦を停止する
            self._indirect_control_enable = False

            if math.fabs(self._joy_msg.axes[self._AXIS_COLOR_CHANGE]) > 0:
                self._is_yellow = not self._is_yellow
                print 'is_yellow: ' + str(self._is_yellow)
                color_or_id_changed = True
                # キーが離れるまでループ
                while self._joy_msg.axes[self._AXIS_COLOR_CHANGE] != 0:
                    pass

        # IDの変更
        if self._joy_msg.buttons[self._BUTTON_ID_ENABLE]:
            # ID変更直後は操縦を停止する
            self._indirect_control_enable = False

            if math.fabs(self._joy_msg.axes[self._AXIS_ID_CHANGE]) > 0:
                # 十字キーの入力に合わせて、IDを増減させる
                self._robot_id += int(self._joy_msg.axes[self._AXIS_ID_CHANGE])

                if self._robot_id > self._MAX_ID:
                    self._robot_id = self._MAX_ID
                if self._robot_id < 0:
                    self._robot_id = 0
                print 'robot_id:' + str(self._robot_id)
                color_or_id_changed = True
                # キーが離れるまでループ
                while self._joy_msg.axes[self._AXIS_ID_CHANGE] != 0:
                    pass

        # poseの更新
        if self._joy_msg.buttons[self._BUTTON_MOVE_ENABLE]:
            # 操縦を許可する
            self._indirect_control_enable = True

            if math.fabs(self._joy_msg.axes[self._AXIS_VEL_SWAY]):
                # joystickの仕様により符号を反転している
                gain = MOVE_GAIN * self._joy_msg.axes[self._AXIS_VEL_SWAY]
                current_joy_pose.x += math.copysign(
                    gain, -self._joy_msg.axes[self._AXIS_VEL_SWAY])

            if math.fabs(self._joy_msg.axes[self._AXIS_VEL_SURGE]):
                gain = MOVE_GAIN * self._joy_msg.axes[self._AXIS_VEL_SURGE]
                current_joy_pose.y += math.copysign(
                    gain, self._joy_msg.axes[self._AXIS_VEL_SURGE])

            if math.fabs(self._joy_msg.axes[self._AXIS_VEL_ANGULAR]):
                gain = MOVE_GAIN_ANGLE * self._joy_msg.axes[
                    self._AXIS_VEL_ANGULAR]
                current_joy_pose.theta += math.copysign(
                    gain, self._joy_msg.axes[self._AXIS_VEL_ANGULAR])

                current_joy_pose.theta = angle_normalize(
                    current_joy_pose.theta)

        # パスの末尾にセット
        self._joy_target.path[-1] = current_joy_pose

        # Pathの操作
        if self._joy_msg.buttons[self._BUTTON_PATH_ENABLE]:
            # 操縦を許可する
            self._indirect_control_enable = True

            # Poseの追加
            if self._joy_msg.buttons[self._BUTTON_ADD_POSE]:
                self._joy_target.path.append(copy.deepcopy(current_joy_pose))
                print 'add pose' + str(len(self._joy_target.path))
                # キーが離れるまでループ
                while self._joy_msg.buttons[self._BUTTON_ADD_POSE] != 0:
                    pass

            # Pathの初期化
            if self._joy_msg.buttons[self._BUTTON_DELETE_PATH]:
                self._joy_target.path = []
                self._joy_target.path.append(Pose2D())
                print 'delete  path'
                # キーが離れるまでループ
                while self._joy_msg.buttons[self._BUTTON_DELETE_PATH] != 0:
                    pass

            # ControlTargetの送信
            if self._joy_msg.buttons[self._BUTTON_SEND_TARGET]:
                self._joy_target.robot_id = self._robot_id
                self._joy_target.control_enable = True

                color = 'blue'
                if self._is_yellow:
                    color = 'yellow'

                # 末尾に16進数の文字列をつける
                topic_id = hex(self._robot_id)[2:]
                topic_name = 'consai2_game/control_target_' + color + '_' + topic_id
                pub_control_target = rospy.Publisher(topic_name,
                                                     ControlTarget,
                                                     queue_size=1)

                pub_control_target.publish(self._joy_target)
                # self._pub_control_target.publish(self._joy_target)
                print 'send target'

        # Color, ID変更ボタンを押すことで操縦を停止できる
        if self._indirect_control_enable is False:
            stop_target = ControlTarget()
            stop_target.robot_id = self._robot_id
            stop_target.control_enable = False

            color = 'blue'
            if self._is_yellow:
                color = 'yellow'

            # 末尾に16進数の文字列をつける
            topic_id = hex(self._robot_id)[2:]
            topic_name = 'consai2_game/control_target_' + color + '_' + topic_id
            pub_control_target = rospy.Publisher(topic_name,
                                                 ControlTarget,
                                                 queue_size=1)

            pub_control_target.publish()

        self._pub_joy_target.publish(self._joy_target)
Exemplo n.º 13
0
    def __init__(self, parent=None):
        super(PaintWidget, self).__init__(parent)

        self._WHITE_LINE_THICKNESS = 2  # 白線の太さ
        self._ZOOM_RATE = 0.1  # 拡大縮小率
        self._SCALE_LIMIT = 0.2  # 縮小率の限界値
        self._ALPHA_DETECTED = 255  # 検出できたロボット・ボールの透明度
        self._ALPHA_NOT_DETECTED = 127  # 検出できなかったロボット・ボールの透明度
        self._COLOR_BALL = QColor(Qt.red)
        self._COLOR_ROBOT = {
            'blue': QColor(Qt.cyan),
            'yellow': QColor(Qt.yellow)
        }
        self._ID_POS = (0.15, 0.15)  # IDを描画するロボット中心からの位置
        self._FLAG_POS = (0.15, 0)  # control_targetのフラグを描画するロボット中心からの位置

        # Replace
        self._REPLACE_CLICK_POS_THRESHOLD = 0.1
        self._REPLACE_CLICK_VEL_ANGLE_THRESHOLD = self._REPLACE_CLICK_POS_THRESHOLD + 0.1
        self._REPLACE_BALL_VELOCITY_GAIN = 3.0
        self._REPLACE_MAX_BALL_VELOCITY = 8.0

        self._BALL_RADIUS = rospy.get_param('consai2_description/ball_radius',
                                            0.0215)
        self._ROBOT_RADIUS = rospy.get_param(
            'consai2_description/robot_radius', 0.09)
        self._MAX_ID = rospy.get_param('consai2_description/max_id', 15)
        self._SIDE = rospy.get_param('consai2_description/our_side', 'left')

        # チームサイドの反転
        self._invert_side = False
        if self._SIDE != 'left':
            self._invert_side = True

        # GUIパラメータ
        self._trans = QPointF(0.0, 0.0)  # x, y方向の移動
        self._mouse_trans = QPointF(0.0, 0.0)  # マウス操作による移動
        self._scale = QPointF(1.0, 1.0)  # 拡大, 縮小
        self._do_rotate_view = False  # 90度回転判定
        self._view_height = self.height()  # 描画サイズ(縦)
        self._view_width = self.width()  # 描画サイズ(横)
        self._scale_field_to_view = 1.0  # フィールドから描画領域に縮小するスケール
        self._click_point = QPointF(0.0, 0.0)  # マウスでクリックした描画座標
        self._current_mouse_pos = QPointF(0.0, 0.0)  # マウスカーソル位置
        self._replace_func = None
        self._replace_id = 0
        self._replace_is_yellow = False
        self._do_replacement = False
        self._replacement_target = {
            'ball_pos': False,
            'ball_vel': False,
            'robot_pos': False,
            'robot_angle': False
        }

        # フィールド形状
        # raw_vision_geometryの値で更新される
        self._field_length = 9.0
        self._field_width = 6.0
        self._field_goal_width = 1.0
        self._field_goal_depth = 0.2
        self._field_boundary_width = 0.3
        self._field_lines = []
        self._field_arcs = []

        # ジョイスティック情報
        self._joy_target = ControlTarget()

        # ロボット・ボール情報
        self._ball_info = BallInfo()
        self._robot_info = {'blue': [], 'yellow': []}

        # レフェリー情報
        self._decoded_referee = None

        # Publisher
        self._pub_replace = rospy.Publisher('sim_sender/replacements',
                                            Replacements,
                                            queue_size=1)

        # Subscribers
        self._sub_decoded_referee = rospy.Subscriber(
            'referee_wrapper/decoded_referee',
            DecodedReferee,
            self._callback_referee,
            queue_size=1)

        self._sub_geometry = rospy.Subscriber(
            'vision_receiver/raw_vision_geometry',
            VisionGeometry,
            self._callback_geometry,
            queue_size=1)

        self._sub_ball_info = rospy.Subscriber('vision_wrapper/ball_info',
                                               BallInfo,
                                               self._callback_ball_info,
                                               queue_size=1)

        self._sub_joy_target = rospy.Subscriber('consai2_examples/joy_target',
                                                ControlTarget,
                                                self._callback_joy_target,
                                                queue_size=1)

        self._subs_robot_info = {'blue': [], 'yellow': []}

        self._control_targets = {'blue': [], 'yellow': []}
        self._subs_control_target = {'blue': [], 'yellow': []}

        for robot_id in range(self._MAX_ID + 1):
            self._robot_info['blue'].append(RobotInfo())
            self._robot_info['yellow'].append(RobotInfo())
            self._control_targets['blue'].append(ControlTarget())
            self._control_targets['yellow'].append(ControlTarget())

            # 末尾に16進数の文字列をつける
            topic_id = hex(robot_id)[2:]
            topic_name = 'vision_wrapper/robot_info_blue_' + topic_id
            self._subs_robot_info['blue'].append(
                rospy.Subscriber(topic_name,
                                 RobotInfo,
                                 self._callback_blue_info,
                                 callback_args=robot_id))

            topic_name = 'vision_wrapper/robot_info_yellow_' + topic_id
            self._subs_robot_info['yellow'].append(
                rospy.Subscriber(topic_name,
                                 RobotInfo,
                                 self._callback_yellow_info,
                                 callback_args=robot_id))

            topic_name = 'consai2_game/control_target_blue_' + topic_id
            self._subs_control_target['blue'].append(
                rospy.Subscriber(topic_name,
                                 ControlTarget,
                                 self._callback_blue_target,
                                 callback_args=robot_id))

            topic_name = 'consai2_game/control_target_blue_' + topic_id
            self._subs_control_target['blue'].append(
                rospy.Subscriber(topic_name,
                                 ControlTarget,
                                 self._callback_blue_target,
                                 callback_args=robot_id))

            topic_name = 'consai2_game/control_target_yellow_' + topic_id
            self._subs_control_target['yellow'].append(
                rospy.Subscriber(topic_name,
                                 ControlTarget,
                                 self._callback_yellow_target,
                                 callback_args=robot_id))

        # Configs
        # This function enables mouse tracking without pressing mouse button
        self.setMouseTracking(True)