Meta(Oculus)Quest のコントローラーの動きでロボットの手の動きを制御:ソースコード:robot_support.py

RobotSupport__init__初期化
get_last_errorエラーコード取得:今は、位置計算に失敗した時のみエラー
get_plane平面の式のパラメターを得る
__get_vectors_lengthベクトルの大きさを得る
__get_vectors_deff_dot二つのベクトルの差を取った後の内積・大きさを比べる時平方根を撮らないことで時間短縮
get_anglevec0を頂点とした3点の角度を得る
get_normal3点を頂点とする三角形の法線を得る
set_magnification操作者の腕の長さと、ロボットの腕の長さの比率から位置合わせの伸縮倍率を設定
check_floatfloatの値が等しいか、誤差を考慮して判断
check_float_axisfloatで表された軸が同じか判断
check_float_listfloatリストの値が全て同じか判断
tow_link_ik2リンク問題を解く
four_link_ik4リンク問題を解く
seven_link_ik7リンク問題を解く
get_shoulder_angles肩の軸角度と肘の位置から、x,y軸周りの回転角を得る
get_calibrated_quaternion座標系変換されたコントローラーのクォータニオンを入れるとキャリブレーションされた座標系変換されたコントローラーの位置情報からキャリブレーションされた位置情報を得る
get_calibrated_position座標系変換されたコントローラーの位置情報からキャリブレーションされた位置情報を得る
calibrate_hand_quaternionキャリブレーション用のクォータニオンを設定
calibrate_hand_positon位置をキャリブレーションする情報を設定
get_calibration_stage現在キャリブレーションのどの段階にあるのかを得る
set_calibration_stage現在キャリブレーションのどの段階にあるのかを設定する
__get_shoulder_positionすでに計算した肩の位置を取得
__calibrate_hand_positon_main位置のキャリブレーション情報を作成するためのメイン関数:calibrate_hand_positonから呼び出している
__get_2points_line2Dの2点からなる線の式のパラメータを取得
__get_2dline_crros_point2Dの2つの線分の交点を求める
set_hand_pos肩の位置を原点とする手の位置を求める
__get_xy_elbow_wrist_position2リンク問題で求めた肩と肘の角度を使って、xy平面上の肘の位置と肩の位置を求める。またその時の手首の軸角度も求める
__get_check_wrist_position肩2つの角度と肘関節の角度を用いで肘と手首の位置を求める。肩2つの角度と肘関節の角度を用いで肘と手首の位置を求める。
_get_wrist_angles手首の3軸の回転角を得る
__get_rotate_axis_and_angle任意軸周りの回転を複数のベクトルに対して行う
__check_vector_length基準ベクトルに近いベクトルがどちらかを判断
get_axis_points_angle任意軸に対してどれだけ回転したら始点を終点に最も近づけるかを返す。
get_three_points_angle基準軸を頂点に始点から終点までの角度を得る
get_angle_sine指定のベクトル回りの回転に対して、始点から終点まで指定の角度で回転させたとき角度の向きを整える。arccosでは角度も向きを得られないため
# robot_support.py
# copyright 2022- https://robot-creation-diary.com/
# 20230115 get_normal get_place でベクトルのリストを渡していたのを3つのベクトルを渡すように変更

import numpy as np
import quaternion
import time
if __name__ == '__main__':
    from axis_angle import AxisAngle as AxisAngle
    from serial_support import SerialSuppot as SerialSuppot
else:
    from hmdcontroller_sub.axis_angle import AxisAngle as AxisAngle
import copy
ERROR_NO_ERROR = 0
ERROR_ARCCOS_OVER_1 = 1


class RobotSupport():

    def __init__(self):

        self.hand_zero = np.array([0, 0, 0, 0])
        self.hand_pos = np.array([0, 0, 0, 0])
        self.hand_quat = np.quaternion(1.0, 0, 0, 0)
        self.hand_plane = [0, 0, 0, 0]  # abcd
        self.shoulder_pos = [0, 0, 0]
        self.hand_calibration_y_angle = 0
        self.arm_length1 = 125
        self.arm_length2 = 75
        self.magnification = 1
        self.handposition_calibrate_aa = AxisAngle()
        self.calibration_stage = 0

        self.calibration_shoulder = [0, 0, 0]
        self.cal_pos1 = [0, 0, 0]  # caliblation position 1
        self.cal_pos2 = [0, 0, 0]  # caliblation position 1
        self.calibration_head_positoin = [0, 0, 0]
        self.calibratoin_quaternion_aa = AxisAngle([1.0, 0, 0, 0])
        self.debug_on = False

        self.__pre_wrist_axis_angles = [0, 0, 0]  # 手首計算に使う。一回前の各軸の角度。
        self.last_error = ERROR_NO_ERROR

    def get_last_error(self):
        return self.last_error

    def get_plane(self, vec1, vec2, vec3):
        """
        平面の式のパラメターを得る
        """
        xy = np.array(vec2)-np.array(vec1)
        xz = np.array(vec3)-np.array(vec1)
        c = np.cross(xy, xz)
        result = np.array([c[0], c[1], c[2],
                           (vec1[0] * c[0]
                           + vec1[1] * c[1]
                           + vec1[2] * c[2]) * -1])
        return result

    def __get_vectors_length(self, vec1, vec2):
        """
        ベクトルの大きさを得る
        """
        return np.sqrt(np.dot(np.array(vec1) - np.array(vec2),
                       np.array(vec1)-np.array(vec2)))

    def __get_vectors_deff_dot(self, vec1, vec2):
        """
        二つのベクトルの差を取った後の内積・大きさを比べる時平方根を撮らないことで時間短縮
        """
        return np.dot(np.array(vec1) - np.array(vec2),
                      np.array(vec1) - np.array(vec2))

    def get_angle(self, vec0, vec1, vec2):
        """
        vec0を頂点とした3点の角度を得る
        """
        v01 = np.array(vec1) - np.array(vec0)
        v02 = np.array(vec2) - np.array(vec0)
        vd = np.dot(v01, v02)
        vd /= np.linalg.norm(v01) * np.linalg.norm(v02)
        return np.arccos(vd)

    def get_normal(self, vec1, vec2, vec3):
        """
        3点を頂点とする三角形の法線を得る
        """
        xy = np.array(vec2)-np.array(vec1)
        xz = np.array(vec3)-np.array(vec1)
        cross = np.cross(xy, xz)
        if self.check_float(0, np.sqrt(np.dot(cross, cross))):
            pass
        normal = cross/np.sqrt(np.dot(cross, cross))

        # 法線は最も軸成分が大きい軸が正になるように整える。
        if np.fabs(normal[1]) < np.fabs(normal[0]) and\
           np.fabs(normal[2]) < np.fabs(normal[0]):
            if normal[0] < 0:
                normal *= -1
        elif np.fabs(normal[0]) < np.fabs(normal[1]) and\
                np.fabs(normal[2]) < np.fabs(normal[1]):
            if normal[1] < 0:
                normal *= -1
        elif np.fabs(normal[1]) < np.fabs(normal[2]) and\
                np.fabs(normal[0]) < np.fabs(normal[2]):
            # z軸はマイナス方向をメインとする。
            if normal[2] < 0:
                normal *= -1

        return normal

    def set_magnification(self, vec):
        """
        操作者の腕の長さと、ロボットの腕の長さの比率から位置合わせの伸縮倍率を設定
        """
        self.magnification = (self.arm_length1 + self.arm_length2) /\
            np.sqrt(np.dot(np.array(vec), np.array(vec)))

    def check_float(self, n1, n2):
        """
        floatの値が等しいか、誤差を考慮して判断
        """
        if ((n1 - 0.000001 < n2) and (n2 < n1 + 0.000001)):
            return True
        return False

    def check_float_axis(self, a1, a2):
        """
        floatで表された軸が同じか判断
        """
        if (self.check_float(a1[0], a2[0]) and
                self.check_float(a1[2], a2[2]) and
                self.check_float(a1[2], a2[2])):
            return True
        return False

    def check_float_list(self, l1, l2):
        """
        floatリストの値が全て同じか判断
        """
        if (len(l1) == len(l2)):
            count = 0
            for d1, d2 in zip(l1, l2):
                if (self.check_float(d1, d2)):
                    count += 1
            if len(l1) == count:
                return True
        return False

    def tow_link_ik(self, goal):
        """
        2リンク問題を解く
        """
        # 反時計回りが正 クウォータニオンの計算が時計回りが正なので出力反転
        # 2リンク問題を解く
        if 1 < np.fabs((goal[0] * goal[0] +
                        goal[1] * goal[1] +
                        self.arm_length1 * self.arm_length1 -
                        self.arm_length2 * self.arm_length2) /
                       (2 * self.arm_length1 *
                        np.sqrt(goal[0] * goal[0] +
                                goal[1] * goal[1]))):
            print("error: arccos over 1")
            self.last_error = ERROR_ARCCOS_OVER_1
            return None, None
        self.last_error = ERROR_NO_ERROR

        acos_buf = np.arccos((goal[0] * goal[0] +
                              goal[1] * goal[1] +
                              self.arm_length1 * self.arm_length1 -
                              self.arm_length2 * self.arm_length2) /
                             (2 * self.arm_length1 *
                              np.sqrt(goal[0] * goal[0] +
                                      goal[1] * goal[1])))
        atan_buf = np.arctan2(goal[1], goal[0])

        # 小さいほうを使う 0<acos なので -のほうを使う
        angle1 = -acos_buf + atan_buf
        angle2 = np.arctan2(goal[1]-self.arm_length1*np.sin(angle1),
                            goal[0]-self.arm_length1*np.cos(angle1)) - angle1

        return angle1, angle2

    def four_link_ik(self, goal_vec):
        """
        4リンク問題を解く
        肩から手首までの四リンクの逆運動学を解く
        """
        # 肩、ひじ、手首が上面図で一直線上になるように位置決めする。
        # 手首の位置で、y軸周りの回転を取得

        vec_buf = copy.deepcopy(goal_vec)
        vec_buf[1] = 0
        # print("goal_vec",goal_vec)
        yangle = self.get_axis_points_angle([0, 1, 0], [1, 0, 0], vec_buf)
        yaa = AxisAngle([0, 1, 0], -yangle)
        goal_buf = yaa.get_rotate_vector(goal_vec)
        # 2リンク問題を解く
        angle1, angle2 = self.tow_link_ik([goal_buf[0], goal_buf[1]])
        if angle1 is None and angle2 is None:
            return None, None, None, None, None
        # 2リンク問題を解く終了
        # 2リンクの結果で肘と手首の位置を計算最終的な肘と手首の位置を求める。
        elbow_position, wrist_position, wristaa =\
            self.__get_xy_elbow_wrist_position(angle1, angle2)
        # zy平面にしたときのyの分だけ回転する。
        iyaa = AxisAngle([0, 1, 0], yangle)
        elbow_position = iyaa.get_rotate_vector(elbow_position)
        wrist_position = iyaa.get_rotate_vector(wrist_position)
        # 肩の回転角を取得
        shoulder_normal = self.get_normal([0, 0, 0],
                                          [0, 0, -1],
                                          elbow_position)
        shoulder_angle = self.get_angle([0, 0, 0], [0, 0, -1], elbow_position)
        # 肩の回転角から肘の位置を計算
        shoulder_aa1 = AxisAngle(shoulder_normal, shoulder_angle)
        posi1 = shoulder_aa1.get_rotate_vector([0, 0, -self.arm_length1])
        shoulder_angle = self.get_angle_sine(shoulder_normal,
                                             shoulder_angle,
                                             posi1,
                                             elbow_position)
        shoulder_aa = AxisAngle(shoulder_normal, shoulder_angle)
        # 各ロボットのモータ間接に合わせて回転角を変換
        # 肩を2軸の回転角として取得

        shoulder_xangle, shoulder_yangle =\
            self.get_shoulder_angles(elbow_position, shoulder_aa)
        # 肩2つの角度と肘関節の角度を用いで肘と手首の位置を求める。手首の位置がずれている場合腕回りの回転を求める。

        elbow_position2, wrist_position2, wrist_aa2 =\
            self.__get_check_wrist_position(shoulder_xangle,
                                            shoulder_yangle,
                                            angle2)
        arm_angle = self.get_axis_points_angle(elbow_position2,
                                               wrist_position2,
                                               wrist_position)
        arm_angle = self.get_angle_sine(elbow_position2,
                                        arm_angle,
                                        wrist_position2,
                                        wrist_position)

        arm_aa = AxisAngle(elbow_position2, arm_angle)
        wrist_aa2 += arm_aa
        # 肩上下回転, 肩片脇開閉、 腕回転 肘関節 手首回転角
        return shoulder_xangle, shoulder_yangle, arm_angle, angle2, wrist_aa2

    def seven_link_ik(self, position, quat):
        """
        7リンク問題を解く
        """
        # 位置や角度をキャリブレーション
        if isinstance(quat, quaternion.quaternion):
            quat = quat
        else:
            quat = quaternion.quaternion(quat[0], quat[1], quat[2], quat[3])
        goal_vec = self.get_calibrated_position(position)
        goal_quat = self.get_calibrated_quaternion(quat)
        # 手首までの4リンク問題を解く
        shoulder_up_down, shoulder_open_close, arm_roteta, elbow, wristaa =\
            self.four_link_ik(goal_vec)
        if shoulder_up_down is None:
            # arccoss over 1 の時
            result = np.array([np.NaN,
                               np.NaN,
                               np.NaN,
                               np.NaN,
                               np.NaN,
                               np.NaN,
                               np.NaN])
            return result

        goalaa = AxisAngle(goal_quat)

        wrist_angles = self._get_wrist_angles(wristaa, goalaa)
        result = np.array([shoulder_up_down,
                           shoulder_open_close,
                           arm_roteta,
                           elbow])
        result = np.hstack([result, wrist_angles])

        return result

    def get_shoulder_angles(self, elbow_position, shoulder_aa):
        """
        肩の軸角度と肘の位置から、x,y軸周りの回転角を得る
        """
        # 肩の回転角と同じ姿勢になる角度を得る。
        xa = np.array([1, 0, 0])
        ya = np.array([0, 1, 0])
        za = np.array([0, 0, -1])

        yaa = AxisAngle(ya, 0)
        yaa += shoulder_aa
        xaa = AxisAngle(xa, 0)
        xaa += shoulder_aa

        # 現在のAxixsAngleで回転させる
        elbow_position2 = copy.deepcopy(elbow_position)

        # x軸周りの回転を調べその後 x軸を回転させた後のz軸での回転角を調べる
        elbow_position2[0] = 0
        xangle = self.get_axis_points_angle([1, 0, 0],
                                            [0, 0, -1],
                                            elbow_position2)
        # x回転後の軸周りの回転をさせる
        xaa = AxisAngle([1, 0, 0], xangle)
        elbow_position2 = copy.deepcopy(elbow_position)
        ya2 = xaa.get_rotate_vector(ya)
        za2 = xaa.get_rotate_vector(za)

        yangle = self.get_axis_points_angle(ya2, za2, elbow_position2)
        # 以下デバッグ処理
        # xaa = AxisAngle([1, 0, 0], xangle)
        yaa = AxisAngle(ya2, yangle)
        elbow_position2 = [0, 0, -self.arm_length1]
        elbow_position2 = xaa.get_rotate_vector(elbow_position2)
        elbow_position2 = yaa.get_rotate_vector(elbow_position2)
        # -------------------------------------------
        # 出力は準運動学
        return xangle, yangle

    def get_calibrated_quaternion(self, quat):
        """
        座標系変換されたコントローラーのクォータニオンを入れるとキャリブレーションされたクォータニオンを得る
        """
        return self.calibratoin_quaternion_aa.get_rotate_quaternion(quat)

    def get_calibrated_position(self, position):
        """
        座標系変換されたコントローラーの位置情報からキャリブレーションされた位置情報を得る
        """
        position_buf = position - self.__get_shoulder_position()
        rpos = self.handposition_calibrate_aa.get_rotate_vector(position_buf)
        rpos2 = self.calibratoin_quaternion_aa.get_rotate_vector(position_buf)
        rpos *= self.magnification
        rpos2 *= self.magnification
        # 腕の長さを超える位置にならないようにする
        if (self.arm_length1 + self.arm_length2 < np.sqrt(np.dot(rpos, rpos))):
            rpos *= ((self.arm_length1 + self.arm_length2) /
                     np.sqrt(np.dot(rpos, rpos))) - 0.00001
        return rpos

    def calibrate_hand_quaternion(self, quat):
        """
        キャリブレーション用のクォータニオンを設定
        """
        self.calibratoin_quaternion_aa =\
            AxisAngle([1.0, 0, 0, 0]) - AxisAngle(quat)

    def calibrate_hand_positon(self, head_position, pos1, pos2):
        """
        位置をキャリブレーションする情報を設定
        """
        if 0 == self.calibration_stage:
            if pos1 is not None:
                self.cal_pos1 = pos1
                self.calibration_stage += 1

        if 1 == self.calibration_stage:
            if pos2 is not None:
                self.cal_pos2 = pos2
                self.calibration_head_positoin = head_position
                if head_position is not None:
                    self.__calibrate_hand_positon_main(head_position,
                                                       self.cal_pos1,
                                                       self.cal_pos2)
                self.calibration_stage += 1

    def get_calibration_stage(self):
        """
        現在キャリブレーションのどの段階にあるのかを得る
        """
        return self.calibration_stage

    def set_calibration_stage(self, stage):
        """
        現在キャリブレーションのどの段階にあるのかを設定する
        """
        self.calibration_stage = stage

    def __get_shoulder_position(self):
        """
        すでに計算した肩の位置を取得
        """
        return self.shoulder_pos

    def __calibrate_hand_positon_main(self, head_position, pos1, pos2):
        """
        位置のキャリブレーション情報を作成するためのメイン関数:calibrate_hand_positonから呼び出している
        """
        # pos1手を前に伸ばした時の位置
        # pos2肘を90度まげて脇につけた時の位置
        # 腕の長さを求める
        # len1 = pos1[1] - pos2[1] #上腕
        # len2 = np.sqrt( (pos2[0] - head_position[0]) *
        #                 (pos2[0] - head_position[0]) \
        #               + (pos2[2] - head_position[2]) *
        #                 (pos2[2] - head_position[2]))
        # arm_len = (len1 + len2)
        # うでのラインと頭の位置の垂線の交点から、肩の位置を求める

        arm_line = self.__get_2points_line([pos1[0], pos1[2]],
                                           [pos2[0], pos2[2]])

        self.shoulder_pos = self.__get_2dline_crros_point(arm_line,
                                                          [head_position[0],
                                                           head_position[2]],
                                                          [pos1[0], pos1[2]])
        self.shoulder_pos.append(self.shoulder_pos[1])
        self.shoulder_pos[1] = pos1[1]
        self.shoulder_pos = np.array(self.shoulder_pos)

        pos1 = np.array(pos1)
        pos2 = np.array(pos2)

        # 肩の位置を中心にpos1がz-1に重なる回転角を得る。
        pos1_buf1 = pos1 - self.shoulder_pos

        angle1 = self.get_axis_points_angle([0, 1, 0], pos1_buf1, [0, 0, -1])
        rotateaa1 = AxisAngle([0, 1, 0], angle1)
        pos1_buf2 = rotateaa1.get_rotate_vector(pos1_buf1)

        angle2 = self.get_axis_points_angle([1, 0, 0], pos1_buf2, [0, 0, -1])
        rotateaa2 = AxisAngle([1, 0, 0], angle2)

        self.handposition_calibrate_aa = rotateaa1 + rotateaa2
        self.magnification = np.fabs(self.arm_length1 + self.arm_length2) /\
            np.sqrt(np.dot(pos1-self.shoulder_pos, pos1-self.shoulder_pos))
        # 肩を原点としたときpos1が z軸と重なればよい
        # x,z軸周りについては考える必要なし

    def __get_2points_line(self, point1, point2):
        """
        2Dの2点からなる線の式のパラメータを取得
        """
        if self.check_float((point2[0] - point1[0]), 0):
            return [None, None]
        else:
            a = (point2[1] - point1[1])/(point2[0] - point1[0])
            b = -a * point1[0] + point1[1]
            return [a, b]

    def __get_2dline_crros_point(self, line, point, linepoint):
        """
        2Dの2つの線分の交点を求める
        """
        if line[0] is None:
            return [linepoint[0], point[1]]
        else:
            x = (line[0]*(point[1] - line[1]) + point[0]) /\
                (line[0]*line[0] + 1)
            y = line[0]*x + line[1]
            return [x, y]

    def set_hand_pos(self, pos):
        """
        肩の位置を原点とする手の位置を求める
        """
        self.hand_pos = [pos[0] - self.shoulder_pos[0],
                         pos[1] - self.shoulder_pos[0],
                         pos[2] - self.shoulder_pos[2]]
        yaa = AxisAngle([0, 1, 0], self.hand_calibration_y_angle)
        self.hand_pos = yaa.get_rotate_vector(self.hand_pos)

    def __get_xy_elbow_wrist_position(self, angle1, angle2):
        """
        2リンク問題で求めた肩と肘の角度を使って、xy平面上の肘の位置と肩の位置を求める。またその時の手首の軸角度も求める
        """
        # クウォータニオン
        wristaa = AxisAngle(np.quaternion(1, 0, 0, 0))
        elbow_position = [self.arm_length1, 0, 0]
        wrist_position = [self.arm_length2, 0, 0]

        saa = AxisAngle([0, 0, 1], angle1)
        wristaa += saa
        # 仮想手首の位置、肘周りの回転軸を得るのに使う
        elbow_position = saa.get_rotate_vector(elbow_position)
        wrist_position = saa.get_rotate_vector(wrist_position)

        # 肘周りの回転
        elbowaa = AxisAngle([0, 0, 1], angle2)
        wristaa += elbowaa
        wrist_position = elbowaa.get_rotate_vector(wrist_position)
        wrist_position += elbow_position
        return elbow_position, wrist_position, wristaa

    def __get_check_wrist_position(self, shoulder_updown_angle,
                                   shoulder_openclose_angle, elbow_angle):
        """
        肩2つの角度と肘関節の角度を用いで肘と手首の位置を求める。
        """
        elbow_position = [0, 0, -self.arm_length1]
        wrist_position = [0, 0, -self.arm_length2]
        exbow_axis = [1, 0, 0]
        ya = [0, 1, 0]
        wristaa = AxisAngle(np.quaternion(1, 0, 0, 0))
        shoulder_ud_aa = AxisAngle([1, 0, 0], shoulder_updown_angle)

        # 以下位置と回転オブジェクトを連鎖的に計算
        elbow_position = shoulder_ud_aa.get_rotate_vector(elbow_position)
        wrist_position = shoulder_ud_aa.get_rotate_vector(wrist_position)
        exbow_axis = shoulder_ud_aa.get_rotate_vector(exbow_axis)
        ya = shoulder_ud_aa.get_rotate_vector(ya)
        wristaa += shoulder_ud_aa

        shoulder_oc_aa = AxisAngle(ya, shoulder_openclose_angle)
        elbow_position = shoulder_oc_aa.get_rotate_vector(elbow_position)
        wrist_position = shoulder_oc_aa.get_rotate_vector(wrist_position)
        exbow_axis = shoulder_oc_aa.get_rotate_vector(exbow_axis)
        wristaa += shoulder_oc_aa

        elbow_aa = AxisAngle(exbow_axis, elbow_angle)
        wrist_position = elbow_aa.get_rotate_vector(wrist_position)
        wrist_position += elbow_position
        wristaa += elbow_aa
        return elbow_position, wrist_position, wristaa

    def _get_wrist_angles(self, wrist_axis_angle, goal_axis_angles):
        """
        手首の3軸の回転角を得る

        axis_angleを
        a1,a2,a3,の軸(ベクトル)回りの回転で表すときの各軸周りの角度を求める。
        """
        xa = np.array([1, 0, 0])
        ya = np.array([0, 1, 0])
        za = np.array([0, 0, -1])
        iza = np.array([0, 0, -1])
        postures = [np.array([1, 0, 0]),
                    np.array([0, 1, 0]),
                    np.array([0, 0, -1])]

        axis_list = [xa, ya, iza]
        oder_axis_index_list = [0, 0, 0]
        # 現在のクウォータニオンで回転させる
        goal_xa_vec = goal_axis_angles.get_rotate_vector(xa)
        goal_ya_vec = goal_axis_angles.get_rotate_vector(ya)
        goal_za_vec = goal_axis_angles.get_rotate_vector(za)
        goal_vec_list = [goal_xa_vec, goal_ya_vec, goal_za_vec]
        result_angle_list = [0, 0, 0]
        for i in range(3):
            axis_list[i] = wrist_axis_angle.get_rotate_vector(axis_list[i])
            postures[i] = wrist_axis_angle.get_rotate_vector(postures[i])

        # 回転軸順番決定手順
        # y軸を合わせるためにx軸z軸周りの回転を行う。
        # 前回の回転角から変位量の少ないほうを優先して最初の回転軸とする。
        # 2回目の回転は、操作対象べく鳥でないほうを軸ベクトルにして操作対象ベクトルを合わせる。
        # 3回目の回転は。残りの軸を回転軸にする。最初の軸を操作対象ベクトルにする。
        # ------------------------------------------------------------
        # y軸を合わせるためにx軸z軸周りの回転を行う。
        # 前回の回転角から変位量の少ないほうを優先して最初の回転軸とする。

        angle_y_1 = self.get_axis_points_angle(axis_list[1],
                                               postures[2],
                                               goal_vec_list[2])
        angle_y_2 = self.get_three_points_angle([0, 0, 0],
                                                postures[1],
                                                goal_vec_list[1])
        angle_x_1 = self.get_axis_points_angle(axis_list[0],
                                               postures[2],
                                               goal_vec_list[2])
        angle_x_2 = self.get_three_points_angle([0, 0, 0],
                                                postures[0],
                                                goal_vec_list[0])

        if (np.fabs(angle_x_1) + np.fabs(angle_x_2) <
                np.fabs(angle_y_1) + np.fabs(angle_y_2)):
            rotation_axis_index = 0
            sub_vec_index = 1
            goal_index = 2
            oder_axis_index_list[0] = rotation_axis_index
            self.debug_on = True

            (result_angle_list[rotation_axis_index],
             axis_list[goal_index],
             axis_list[sub_vec_index],
             postures) = self.__get_rotate_axis_and_angle(
                    axis_list[rotation_axis_index],
                    postures[goal_index],
                    goal_vec_list[goal_index],
                    axis_list[goal_index],
                    axis_list[sub_vec_index],
                    postures,
                    np.pi * 0.5)
            self.debug_on = False
            rotation_axis_index = 1
            goal_index = 2
            sub_vec_index = oder_axis_index_list[0]
            oder_axis_index_list[1] = rotation_axis_index

            (result_angle_list[rotation_axis_index],
             axis_list[goal_index],
             axis_list[sub_vec_index],
             postures) = self.__get_rotate_axis_and_angle(
                axis_list[rotation_axis_index],
                postures[goal_index],
                goal_vec_list[goal_index],
                axis_list[goal_index],
                None,
                postures,
                np.pi)
            oder_axis_index_list[1] = rotation_axis_index
        else:
            rotation_axis_index = 1
            goal_index = 2
            sub_vec_index = 0
            oder_axis_index_list[0] = rotation_axis_index

            # axis_list[sub_vec_index] にNoneが渡されるので一時退避
            sub_vec = axis_list[sub_vec_index]

            (result_angle_list[rotation_axis_index],
             axis_list[goal_index],
             axis_list[sub_vec_index],
             postures) = self.__get_rotate_axis_and_angle(
                axis_list[rotation_axis_index],
                postures[goal_index],
                goal_vec_list[goal_index],
                axis_list[goal_index],
                None,
                postures,
                np.pi)
            oder_axis_index_list[0] = rotation_axis_index
            axis_list[sub_vec_index] = sub_vec

            rotation_axis_index = 0
            goal_index = 2
            sub_vec_index = oder_axis_index_list[0]
            oder_axis_index_list[1] = rotation_axis_index

            (result_angle_list[rotation_axis_index],
             axis_list[goal_index],
             axis_list[sub_vec_index],
             postures) = self.__get_rotate_axis_and_angle(
                axis_list[rotation_axis_index],
                postures[goal_index],
                goal_vec_list[goal_index],
                axis_list[goal_index],
                axis_list[sub_vec_index],
                postures,
                np.pi * 0.5)

        # ここまで2回転目
        # 3回目の回転は。残りの軸を回転軸にする。最初の軸を操作対象ベクトルにする。

        rotation_axis_index = 2
        sub_vec_index = 0
        goal_index = 1
        if (1 == rotation_axis_index):
            # y軸の時180まで許す
            (result_angle_list[rotation_axis_index],
             axis_list[goal_index],
             axis_list[sub_vec_index],
             postures) = self.__get_rotate_axis_and_angle(
                axis_list[rotation_axis_index],
                postures[goal_index],
                goal_vec_list[goal_index],
                axis_list[goal_index],
                None, postures,
                np.pi)
            oder_axis_index_list[2] = rotation_axis_index
        else:
            (result_angle_list[rotation_axis_index],
             axis_list[goal_index],
             axis_list[sub_vec_index],
             postures) = self.__get_rotate_axis_and_angle(
                axis_list[rotation_axis_index],
                postures[goal_index],
                goal_vec_list[goal_index],
                None,
                None,
                postures,
                np.pi * 0.5)
            oder_axis_index_list[2] = rotation_axis_index
        self.__pre_wrist_axis_angles = copy.deepcopy(result_angle_list)
        return result_angle_list

    def __get_rotate_axis_and_angle(self,
                                    rotate_axis,
                                    start_posture,
                                    goal_posture,
                                    a1,
                                    a2,
                                    postures,
                                    limit_angle):
        """
        任意軸周りの回転を複数のベクトルに対して行う
        回転軸、回転の起点となるベクトル、回転させる残りのベクトル。回転目標のベクトル、回転角の上限の絶対値
        角度と、回転軸以外が回転した後の軸のベクトルを返す
        """
        angle = self.get_axis_points_angle(rotate_axis,
                                           start_posture,
                                           goal_posture)

        if (limit_angle < np.fabs(angle)):
            if 0 < angle:
                angle = limit_angle
            else:
                angle = - limit_angle

        a1aa = AxisAngle(rotate_axis, angle)
        # x軸を回転させたときの y, z軸のベクトルを取得する
        ra1 = a1
        ra2 = a2
        if not isinstance(a1, type(None)):
            ra1 = a1aa.get_rotate_vector(a1)

        if not isinstance(a2, type(None)):
            ra2 = a1aa.get_rotate_vector(a2)

        for i in range(3):
            postures[i] = a1aa.get_rotate_vector(postures[i])
        # za_buf,ya_bufはデバッグ用終わったら消すこと

        return angle, ra1, ra2, postures

    def __check_vector_length(self, base, check1, check2):
        """
        基準ベクトルに近いベクトルがどちらかを判断
        base がcheck1とcheck2のどちらのベクトルに近いか。
        1と遠い場合True
        2と遠い場合False
        """

        deff1 = np.array(check1) - np.array(base)
        deff2 = np.array(check2) - np.array(base)
        if np.dot(deff2, deff2) < np.dot(deff1, deff1):
            return True
        else:
            return False

    def get_axis_points_angle(self, axis, start_point, end_point):
        """
        任意軸に対してどれだけ回転したら始点を終点に最も近づけるかを返す。
        """
        # 軸周りの2点の角度
        # 軸を z軸に合わせ2店の角度を返す。
        if (self.check_float_axis(axis, start_point) or
                self.check_float_axis(axis, end_point)):
            # 回転軸と開始地点または終了地点が同じとき0
            return 0
        base_axis = [0, 0, 1]
        normal = self.get_normal([0, 0, 0], axis, base_axis)
        angle = self.get_three_points_angle([0, 0, 0], axis, base_axis)
        aa = AxisAngle(normal, angle)

        if np.isnan(normal[0]):
            start_point_rotated = copy.deepcopy(start_point)
            end_point_rotated = copy.deepcopy(end_point)
        else:
            start_point_rotated = aa.get_rotate_vector(start_point)
            end_point_rotated = aa.get_rotate_vector(end_point)
        # 基準軸によって0にする軸を変える
        # ジンバルロック状態の時は0度とする。
        if (np.fabs(self.get_three_points_angle(
                        [0, 0, 0],
                        [0, 0, 1],
                        start_point_rotated) * 180 / np.pi) < 10 or
                170 < np.fabs(
                        self.get_three_points_angle([0, 0, 0],
                                                    [0, 0, 1],
                                                    start_point_rotated) *
                        180 / np.pi)):
            return 0
        if (np.fabs(self.get_three_points_angle(
                        [0, 0, 0],
                        [0, 0, 1],
                        end_point_rotated) * 180 / np.pi) < 10 or
                170 < np.fabs(self.get_three_points_angle(
                    [0, 0, 0],
                    [0, 0, 1],
                    end_point_rotated) * 180/np.pi)):
            return 0
        start_point_rotated[2] = 0
        end_point_rotated[2] = 0
        angle = self.get_three_points_angle(
                        [0, 0, 0],
                        start_point_rotated,
                        end_point_rotated)
        return self.get_angle_sine(axis, angle, start_point, end_point)

    def get_three_points_angle(self, base_point, start_point, end_point):
        """
        基準軸を頂点に始点から終点までの角度を得る
        """
        normal = self.get_normal(base_point, start_point, end_point)

        # 法線は最も軸成分が大きい軸が正になるように整える。

        angle = self.get_angle(base_point, start_point, end_point)
        angle = self.get_angle_sine(normal, angle, start_point, end_point)
        return angle

    def get_angle_sine(self, normal, angle, start_point, end_point):
        """
        指定のベクトル回りの回転に対して、始点から終点まで指定の角度で回転させたとき角度の向きを整える。arccosでは角度も向きを得られないため
        """
        # 回転角の向きを決定
        aa = AxisAngle(normal, angle)
        end_buf1 = aa.get_rotate_vector(start_point) - np.array(end_point)
        aa = AxisAngle(normal, -angle)
        end_buf2 = aa.get_rotate_vector(start_point) - np.array(end_point)
        if (np.dot(end_buf2, end_buf2) < np.dot(end_buf1, end_buf1)):
            angle *= -1
        return angle


if __name__ == '__main__':

    rsr = RobotSupport()
    rsl = RobotSupport()
    st_time = time.time()

    rsr.calibrate_hand_positon(
        [0.05710649490356445, 0.09122085571289062, 0.13544045388698578],
        [0.23312297463417053, -0.2683688998222351, -0.23034866154193878], None)

    rsl.calibrate_hand_positon(
        [0.05710649490356445, 0.09122085571289062, 0.13544045388698578],
        [-0.1262214630842209, -0.2702094316482544, -0.2580428421497345], None)

    rsl.calibrate_hand_positon(
        [0.05381555110216141, 0.06848493218421936, 0.02566489577293396], None,
        [-0.14960207045078278, -0.4632076025009155, -0.04568114131689072])

    rsl.calibrate_hand_quaternion([0.9791911840438843, -0.19468680024147034,
                                   -0.05687325820326805, -0.00686476519331336])

    rsr.calibrate_hand_positon(
        [0.05368240550160408, 0.06860034167766571, 0.0245894193649292], None,
        [0.15052443742752075, -0.4402616024017334, -0.014723729342222214])
    rsr.calibrate_hand_quaternion(
            [0.9898318648338318, -0.13527309894561768,
             -0.010736760683357716, -0.042647942900657654])

    serial_support = SerialSuppot("com4", 115200)

    print("1------")
    print("r------")
    r_nparray = rsr.seven_link_ik(
        [0.1519170105457306, -0.43505826592445374, -0.01406487450003624],
        [0.9951089024543762, -0.08291225880384445,
         -0.016847092658281326, -0.05098998174071312])
    print("l------")
    l_nparray = rsl.seven_link_ik(
        [-0.15276679396629333, -0.4549545645713806, -0.045161791145801544],
        [0.9939320087432861, -0.09892606735229492,
         -0.04765178635716438, -0.006485961843281984])

    print(
        "r_nparray, l_nparray",
        r_nparray * 180 / np.pi,
        l_nparray * 180 / np.pi)
    serial_support.debug_on = True
    serial_support.move_servo(
                    l_nparray,
                    (1 * 120.0 + 100.0) * np.pi / 180,
                    r_nparray,
                    (0.3 * 120.0 + 100.0) * np.pi / 180)
    serial_support.debug_on = True