Skip to content

Algorithm Interface Configuration algo

For the RealMan robotic arm, there are tool interfaces such as forward and inverse kinematics and various pose parameter transformations.

Initialize algorithm dependency data __init__()

  • Method prototype:
python
__init__(self, arm_model: rm_robot_arm_model_e, force_type: rm_force_type_e):

Jump to typeList for details of rm_robot_arm_model_e and rm_force_type_e

  • Parameter description:
ParameterTypeDescription
arm_modelrm_robot_arm_model_eRobotic arm model.
force_typerm_force_type_eSensor type.
  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

arm_model = rm_robot_arm_model_e.RM_MODEL_RM_65_E  # RM_65 Robotic arm
force_type = rm_force_type_e.RM_MODEL_RM_B_E  # Standard version
# Initialize the robotic arm model and sensor type in the algorithm
algo_handle = Algo(arm_model, force_type)

Get the algorithm library version rm_algo_version()

  • Method prototype:
python
rm_algo_version(self) -> str:
  • Return value:
ParameterTypeDescription
-strAlgorithm library version number.
  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

arm_model = rm_robot_arm_model_e.RM_MODEL_RM_65_E  # RM_65 Robotic arm
force_type = rm_force_type_e.RM_MODEL_RM_B_E  # Standard version
# Initialize the robotic arm model and sensor type in the algorithm
algo_handle = Algo(arm_model, force_type)

# Get the robotic arm mounting angle used by the current algorithm
print(algo_handle.rm_algo_version())

Set the mounting angle rm_algo_set_angle()

  • Method prototype:
python
rm_algo_set_angle(self, x: float, y: float, z: float) -> None:
  • Parameter description:
ParameterTypeDescription
xfloatX-axis mounting angle, in °.
yfloatY-axis mounting angle, in °.
zfloatZ-axis mounting angle, in °.
  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

arm_model = rm_robot_arm_model_e.RM_MODEL_RM_65_E  # RM_65 Robotic arm
force_type = rm_force_type_e.RM_MODEL_RM_B_E  # Standard version
# Initialize the robotic arm model and sensor type in the algorithm
algo_handle = Algo(arm_model, force_type)

# Set the robotic arm mounting angle used by the current algorithm
algo_handle.rm_algo_set_angle(0,90,0)

Get the mounting angle rm_algo_get_angle()

  • Method prototype:
python
rm_algo_get_angle(self) -> tuple[float, float, float]:
  • Return value:
ParameterTypeDescription
xfloatX-axis mounting angle, in °.
yfloatY-axis mounting angle, in °.
zfloatZ-axis mounting angle, in °.
  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

arm_model = rm_robot_arm_model_e.RM_MODEL_RM_65_E  # RM_65 Robotic arm
force_type = rm_force_type_e.RM_MODEL_RM_B_E  # Standard version
# Initialize the robotic arm model and sensor type in the algorithm
algo_handle = Algo(arm_model, force_type)

# Get the robotic arm mounting angle used by the current algorithm
print(algo_handle.rm_algo_get_angle())

Set the work frame rm_algo_set_workframe()

  • Method prototype:
Python
rm_algo_set_workframe(self, frame: rm_frame_t) -> None:

Jump to rm_frame_t for details of the structure

  • Parameter description:
ParameterTypeDescription
framerm_frame_tFrame data.
  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

arm_model = rm_robot_arm_model_e.RM_MODEL_RM_65_E  # RM_65 Robotic arm
force_type = rm_force_type_e.RM_MODEL_RM_B_E  # Standard version
# Initialize the robotic arm model and sensor type in the algorithm
algo_handle = Algo(arm_model, force_type)

# Set the pose of the current work frame
frame = rm_frame_t("", [0.186350, 0.062099, 0.2, 3.141, 0, 1.569])
algo_handle.rm_algo_set_workframe(frame)

Get the current work frame rm_algo_get_curr_workframe()

  • Method prototype:
python
rm_algo_get_curr_workframe(self) -> dict[str, any]:
  • Parameter description:
ParameterTypeDescription
dict[str, any]rm_frame_tReturn the dictionary of the current work frame,
key: field name of rm_frame_t.

Jump to rm_frame_t for details of the structure

  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

arm_model = rm_robot_arm_model_e.RM_MODEL_RM_65_E  # RM_65 Robotic arm
force_type = rm_force_type_e.RM_MODEL_RM_B_E  # Standard version
# Initialize the robotic arm model and sensor type in the algorithm
algo_handle = Algo(arm_model, force_type)

# Set the pose of the current work frame
frame = rm_frame_t("", [0.186350, 0.062099, 0.2, 3.141, 0, 1.569])
algo_handle.rm_algo_set_workframe(frame)

# Get the pose of the current work frame
print(algo_handle.rm_algo_get_curr_workframe())

Set the tool frame rm_algo_set_toolframe()

  • Method prototype:
python
rm_algo_set_toolframe(self, frame: rm_frame_t) -> None:

Jump to rm_frame_t for details of the structure

  • Parameter description:
ParameterTypeDescription
framerm_frame_tFrame data.
  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

arm_model = rm_robot_arm_model_e.RM_MODEL_RM_65_E  # RM_65 Robotic arm
force_type = rm_force_type_e.RM_MODEL_RM_B_E  # Standard version
# Initialize the robotic arm model and sensor type in the algorithm
algo_handle = Algo(arm_model, force_type)

# Set the current tool frame
frame = rm_frame_t("", [0.186350, 0.062099, 0.2, 3.141, 0, 1.569], 5, 1, 1, 1)
algo_handle.rm_algo_set_toolframe(frame)

Get the current tool frame rm_algo_get_curr_toolframe()

  • Method prototype:
python
rm_algo_get_curr_toolframe(self) -> dict[str, any]:
  • Parameter description:
ParameterTypeDescription
dict[str, any]rm_frame_tReturn the dictionary of the current tool frame,
key: field name of rm_frame_t.

Jump to rm_frame_t for details of the structure

  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

arm_model = rm_robot_arm_model_e.RM_MODEL_RM_65_E  # RM_65 Robotic arm
force_type = rm_force_type_e.RM_MODEL_RM_B_E  # Standard version
# Initialize the robotic arm model and sensor type in the algorithm
algo_handle = Algo(arm_model, force_type)

# Set the current tool frame
frame = rm_frame_t("", [0.186350, 0.062099, 0.2, 3.141, 0, 1.569], 5, 1, 1, 1)
algo_handle.rm_algo_set_toolframe(frame)

# Get the current tool frame
print(algo_handle.rm_algo_get_curr_toolframe())

Set maximum joint limit rm_algo_set_joint_max_limit()

  • Method prototype:
python
rm_algo_set_joint_max_limit(self, joint_limit: list[float]) -> None:
  • Parameter description:
ParameterTypeDescription
joint_limitlist[float]Maximum joint limit array, in °.
  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

arm_model = rm_robot_arm_model_e.RM_MODEL_RM_65_E  # RM_65 Robotic arm
force_type = rm_force_type_e.RM_MODEL_RM_B_E  # Standard version
# Initialize the robotic arm model and sensor type in the algorithm
algo_handle = Algo(arm_model, force_type)

# Set the maximum joint limit used by the algorithm
joint_max_limit = [178.0, 130.0, 135.0, 178.0, 128.0, 180.0]
algo_handle.rm_algo_set_joint_max_limit(joint_max_limit)

Get maximum joint limit rm_algo_get_joint_max_limit()

  • Method prototype:
python
rm_algo_get_joint_max_limit(self) -> list[float]:
  • Parameter description:
ParameterTypeDescription
\list[float]Return the maximum joint limit array, in °.
  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

arm_model = rm_robot_arm_model_e.RM_MODEL_RM_65_E  # RM_65 Robotic arm
force_type = rm_force_type_e.RM_MODEL_RM_B_E  # Standard version
# Initialize the robotic arm model and sensor type in the algorithm
algo_handle = Algo(arm_model, force_type)

# Get the maximum joint limit used by the algorithm
print(algo_handle.rm_algo_get_joint_max_limit())

Set minimum joint limit rm_algo_set_joint_min_limit()

  • Method prototype:
python
rm_algo_set_joint_min_limit(self, joint_limit: list[float]) -> None:
  • Parameter description:
ParameterTypeDescription
joint_limitlist[float]Minimum joint limit array, in °.
  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

arm_model = rm_robot_arm_model_e.RM_MODEL_RM_65_E  # RM_65 Robotic arm
force_type = rm_force_type_e.RM_MODEL_RM_B_E  # Standard version
# Initialize the robotic arm model and sensor type in the algorithm
algo_handle = Algo(arm_model, force_type)

# Set the minimum joint limit used by the algorithm
joint_min_limit = [-178.0, -130.0, -135.0, -178.0, -128.0, -180.0]
algo_handle.rm_algo_set_joint_min_limit(joint_min_limit)

Get minimum joint limit rm_algo_get_joint_min_limit()

  • Method prototype:
python
rm_algo_get_joint_min_limit(self) -> list[float]:
  • Parameter description:
ParameterTypeDescription
\list[float]Minimum joint limit array, in °.
  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

arm_model = rm_robot_arm_model_e.RM_MODEL_RM_65_E  # RM_65 Robotic arm
force_type = rm_force_type_e.RM_MODEL_RM_B_E  # Standard version
# Initialize the robotic arm model and sensor type in the algorithm
algo_handle = Algo(arm_model, force_type)

# Get the minimum joint limit used by the algorithm
print(algo_handle.rm_algo_get_joint_min_limit())

Set maximum joint speed rm_algo_set_joint_max_speed()

  • Method prototype:
python
rm_algo_set_joint_max_speed(self, joint_limit: list[float]) -> None:
  • Parameter description:
ParameterTypeDescription
joint_limitlist[float]Maximum speed, in RPM.
  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

arm_model = rm_robot_arm_model_e.RM_MODEL_RM_65_E  # RM_65 Robotic arm
force_type = rm_force_type_e.RM_MODEL_RM_B_E  # Standard version
# Initialize the robotic arm model and sensor type in the algorithm
algo_handle = Algo(arm_model, force_type)

# Set the maximum joint speed used by the algorithm
joint_max_speed = [30.0, 30.0, 37.5, 37.5, 37.5, 37.5]
algo_handle.rm_algo_set_joint_max_speed(joint_max_speed)

Get maximum joint speed rm_algo_get_joint_max_speed()

  • Method prototype:
python
rm_algo_get_joint_max_speed(self) -> list[float]:
  • Parameter description:
ParameterTypeDescription
list[float]floatSave the returned maximum speed, in RPM.
  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

arm_model = rm_robot_arm_model_e.RM_MODEL_RM_65_E  # RM_65 Robotic arm
force_type = rm_force_type_e.RM_MODEL_RM_B_E  # Standard version
# Initialize the robotic arm model and sensor type in the algorithm
algo_handle = Algo(arm_model, force_type)

# Get the minimum joint limit used by the algorithm
print(algo_handle.rm_algo_get_joint_max_speed())

Set maximum joint acceleration rm_algo_set_joint_max_acc()

  • Method prototype:
python
rm_algo_set_joint_max_acc(self, joint_limit: list[float]) -> None:
  • Parameter description:
ParameterTypeDescription
joint_limitfloatMaximum acceleration, in RPM/s.
  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

arm_model = rm_robot_arm_model_e.RM_MODEL_RM_65_E  # RM_65 Robotic arm
force_type = rm_force_type_e.RM_MODEL_RM_B_E  # Standard version
# Initialize the robotic arm model and sensor type in the algorithm
algo_handle = Algo(arm_model, force_type)

# Set the maximum joint acceleration used by the algorithm
joint_max_acc = [166.6666717529297, 166.6666717529297, 166.6666717529297, 166.6666717529297, 166.6666717529297, 166.6666717529297]
algo_handle.rm_algo_set_joint_max_acc(joint_max_acc)

Get maximum joint acceleration rm_algo_get_joint_max_acc()

  • Method prototype:
python
rm_algo_get_joint_max_acc(self) -> list[float]:
  • Parameter description:
ParameterTypeDescription
list[]floatSave the returned maximum acceleration, in RPM/s.
  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

arm_model = rm_robot_arm_model_e.RM_MODEL_RM_65_E  # RM_65 Robotic arm
force_type = rm_force_type_e.RM_MODEL_RM_B_E  # Standard version
# Initialize the robotic arm model and sensor type in the algorithm
algo_handle = Algo(arm_model, force_type)

# Get the minimum joint limit used by the algorithm
print(algo_handle.rm_algo_get_joint_max_acc())

Set the inverse kinematics solution mode rm_algo_set_redundant_parameter_traversal_mode()

  • Method prototype:
python
rm_algo_set_redundant_parameter_traversal_mode(self, mode: bool) -> None:
  • Parameter description:
ParameterTypeDescription
modebool- true: traversal mode, redundant parameter traversal solution strategy. It is applicable to scenes where the current pose differs greatly from the required pose, such as MOVJ_P and pose editing, and it takes a long time. -false: single step mode, automatically adjusting the solution strategy of redundant parameters. It is applicable to scenes where the difference between the current pose and the required pose is very small and continuous cycle control is required, such as the pose solution of Cartesian space planning, and it takes a short time.
  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

arm_model = rm_robot_arm_model_e.RM_MODEL_RM_65_E  # RM_65 Robotic arm
force_type = rm_force_type_e.RM_MODEL_RM_B_E  # Standard version
# Initialize the robotic arm model and sensor type in the algorithm
algo_handle = Algo(arm_model, force_type)

# Set the inverse kinematics solution to traversal mode
algo_handle.rm_algo_set_redundant_parameter_traversal_mode(true)

Inverse kinematics function rm_algo_inverse_kinematics()

  • Method prototype:
python
rm_algo_inverse_kinematics(self, params: rm_inverse_kinematics_params_t) -> tuple[int, list[float]]:
  • Parameter description:
ParameterTypeDescription
paramsrm_inverse_kinematics_params_tInverse kinematics input parameter structure.

Jump to rm_inverse_kinematics_params_t for details of the structure

  • Return value: tuple[int,list[float]]: a tuple containing two elements.

    • int Inverse kinematics result:

      ParameterTypeDescription
      0intInverse kinematics succeeds.
      1intInverse kinematics fails.
      -1intThe previous joint angle input is NULL.
      -2intThe target pose quaternion is invalid.
    • list[float] : output joint angle, in °, length: degree of freedom of the robotic arm.

  • Usage demo

python
from Robotic_Arm.rm_robot_interface import *

arm_model = rm_robot_arm_model_e.RM_MODEL_RM_65_E  # RM_65 Robotic arm
force_type = rm_force_type_e.RM_MODEL_RM_B_E  # Standard version
# Initialize the robotic arm model and sensor type in the algorithm
algo_handle = Algo(arm_model, force_type)

# Perform the inverse kinematics from joint angles [0, 0, -90, 0, -90, 0] to target poses [0.186350, 0.062099, 0.200000, 3.141, 0, 1.569]. The target orientation is represented by the Euler angle.
params = rm_inverse_kinematics_params_t([0, 0, -90, 0, -90, 0], [0.186350, 0.062099, 0.200000, 3.141, 0, 1.569], 1)
q_out = algo_handle.rm_algo_inverse_kinematics(params)
print(q_out)

Forward kinematics algorithm rm_algo_forward_kinematics()

  • Method prototype:
python
rm_algo_forward_kinematics(self, joint: list[float], flag: int = 1) -> list[float]:
  • Parameter description:
ParameterTypeDescription
jointlist[float]Joint angle, in °.
flagintOrientation representation, default: Euler angle. - 0: return the pose list [x, y, z, w, x, y, z] with the orientation represented by the quaternion, - 1: return the pose list [x, y, z, rx, ry, rz] with the orientation represented by the Euler angle.
  • Return value:

list[float]: obtained target pose list.

  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

arm_model = rm_robot_arm_model_e.RM_MODEL_RM_65_E  # RM_65 Robotic arm
force_type = rm_force_type_e.RM_MODEL_RM_B_E  # Standard version
# Initialize the robotic arm model and sensor type in the algorithm
algo_handle = Algo(arm_model, force_type)

# Perform the forward kinematics of joint angles [0, 0, -90, 0, -90, 0], and return the pose, with the orientation represented by the Euler angle
pose = algo_handle.rm_algo_forward_kinematics([0, 0, -90, 0, -90, 0])
print(pose)

Euler angle to quaternion rm_algo_euler2quaternion()

  • Method prototype:
python
rm_algo_euler2quaternion(self, eul: list[float]) -> list[float]:
  • Parameter description:
ParameterTypeDescription
eullist[float]Euler angle list [rx, ry, rz], in rad.
  • Return value:

list[float]: quaternion list [w, x, y, z]

  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

arm_model = rm_robot_arm_model_e.RM_MODEL_RM_65_E  # RM_65 Robotic arm
force_type = rm_force_type_e.RM_MODEL_RM_B_E  # Standard version
# Initialize the robotic arm model and sensor type in the algorithm
algo_handle = Algo(arm_model, force_type)

# Convert the Euler angle [-0.259256, -0.170727, 0.35621] into the quaternion
print(algo_handle.rm_algo_euler2quaternion([-0.259256, -0.170727, 0.35621]))

Quaternion to Euler angle rm_algo_quaternion2euler()

  • Method prototype:
python
rm_algo_quaternion2euler(self, quat: list[float]) -> list[float]:
  • Parameter description:
ParameterTypeDescription
quatlist[float]Quaternion list [w, x, y, z].
  • Return value:

list[float]: Euler angle list [rx, ry, rz], in rad.

  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

arm_model = rm_robot_arm_model_e.RM_MODEL_RM_65_E  # RM_65 Robotic arm
force_type = rm_force_type_e.RM_MODEL_RM_B_E  # Standard version
# Initialize the robotic arm model and sensor type in the algorithm
algo_handle = Algo(arm_model, force_type)

# Convert the quaternion (0, 0, 0, 1) into the Euler angle
print(algo_handle.rm_algo_quaternion2euler([0,0,0,1]))

Euler angle to rotation matrix rm_algo_euler2matrix()

  • Method prototype:
python
rm_algo_euler2matrix(self, eu: list[float]) -> rm_matrix_t:

Jump to rm_matrix_t for details of the structure

  • Parameter description:
ParameterTypeDescription
eulist[float]Euler angle list [rx, ry, rz], in rad.
  • Return value:

rm_matrix_t: rotation matrix.

  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

arm_model = rm_robot_arm_model_e.RM_MODEL_RM_65_E  # RM_65 Robotic arm
force_type = rm_force_type_e.RM_MODEL_RM_B_E  # Standard version
# Initialize the robotic arm model and sensor type in the algorithm
algo_handle = Algo(arm_model, force_type)

# Convert the Euler angle (3.14, 0, 0) into the rotation matrix
mat = algo_handle.rm_algo_euler2matrix([3.14, 0, 0])

Pose to rotation matrix rm_algo_pos2matrix()

  • Method prototype:
python
rm_algo_pos2matrix(self, pose: list[float]) -> rm_matrix_t:
  • Parameter description:
ParameterTypeDescription
poselist[float]Position and orientation list [x, y, z, rx, ry, rz].
  • Return value:

rm_matrix_t: rotation matrix.

  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

arm_model = rm_robot_arm_model_e.RM_MODEL_RM_65_E  # RM_65 Robotic arm
force_type = rm_force_type_e.RM_MODEL_RM_B_E  # Standard version
# Initialize the robotic arm model and sensor type in the algorithm
algo_handle = Algo(arm_model, force_type)

# Convert the pose into the rotation matrix
mat = algo_handle.rm_algo_pos2matrix([-0.177347, 0.438112, -0.215102, 2.09078, 0.942362, 2.39144])

Rotation matrix to pose rm_algo_matrix2pos()

  • Method prototype:
python
rm_algo_matrix2pos(self, matrix: rm_matrix_t, flag: int = 1) -> list[float]:

Jump to rm_matrix_t for details of the structure

  • Parameter description:
ParameterTypeDescription
matrixrm_matrix_tRotation matrix.
flagintOrientation representation, default: Euler angle. - 0: return the pose list [x, y, z, w, x, y, z] with the orientation represented by the quaternion, - 1: return the pose list [x, y, z, rx, ry, rz] with the orientation represented by the Euler angle.
  • Return value:

list[float]: obtained target pose.

  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

arm_model = rm_robot_arm_model_e.RM_MODEL_RM_65_E  # RM_65 Robotic arm
force_type = rm_force_type_e.RM_MODEL_RM_B_E  # Standard version
# Initialize the robotic arm model and sensor type in the algorithm
algo_handle = Algo(arm_model, force_type)

# Convert the rotation matrix into the pose
data = [1.0, 0.0, 0.0, 10.0],[0.0, 1.0, 0.0, 20.0],[0.0, 0.0, 1.0, 30.0],[0.0, 0.0, 0.0, 1.0]
mat = rm_matrix_t(4,4,data)

print(algo_handle.rm_algo_matrix2pos(mat))

Base frame to work frame rm_algo_base2workframe()

  • Method prototype:
python
rm_algo_base2workframe(self, matrix: rm_matrix_t, pose_in_base: rm_pose_t, flag: int = 1) -> list[float]:
  • Parameter description:
ParameterTypeDescription
matrixrm_matrix_tMatrix of the work frame in the base frame.
pose_in_baserm_pose_tPose of the end frame in the base frame.
flagintOrientation representation, default: Euler angle. - 0: return the pose list [x, y, z, w, x, y, z] with the orientation represented by the quaternion, - 1: return the pose list [x, y, z, rx, ry, rz] with the orientation represented by the Euler angle.

Jump to rm_matrix_t and rm_pose_t for details of the structure

  • Return value:

list[float]: pose of the base frame in the work frame.

  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

arm_model = rm_robot_arm_model_e.RM_MODEL_RM_65_E  # RM_65 Robotic arm
force_type = rm_force_type_e.RM_MODEL_RM_B_E  # Standard version
# Initialize the robotic arm model and sensor type in the algorithm
algo_handle = Algo(arm_model, force_type)

# Convert the base frame into the work frame, where work_matrix is the matrix of the work frame in the base frame, and end_pose is the pose of the end frame in the base frame
work_matrix = algo_handle.rm_algo_pos2matrix([-0.177347, 0.438112, -0.215102, 2.09078, 0.942362, 2.39144])
end_pose =  rm_pose_t()
end_pose.position = rm_position_t(0.186350, 0.062099, 0.2)
end_pose.euler = rm_euler_t(3.141, 0, 1.569)
print(algo_handle.rm_algo_base2workframe(work_matrix, end_pose))

Work frame to base framerm_algo_workframe2base()

  • Method prototype:
python
rm_algo_workframe2base(self, matrix: rm_matrix_t, pose_in_work: rm_pose_t, flag: int = 1) -> list[float]:

Jump to rm_matrix_t and rm_pose_t for details of the structure

  • Parameter description:
ParameterTypeDescription
matrixrm_matrix_tMatrix of the end frame in the work frame.
pose_in_workrm_pose_tPose of the end frame in the work frame.
flagintOrientation representation, default: Euler angle. - 0: return the pose list [x, y, z, w, x, y, z] with the orientation represented by the quaternion, - 1: return the pose list [x, y, z, rx, ry, rz] with the orientation represented by the Euler angle.
  • Return value:

list[float]: pose of the work frame in the base frame.

  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

arm_model = rm_robot_arm_model_e.RM_MODEL_RM_65_E  # RM_65 Robotic arm
force_type = rm_force_type_e.RM_MODEL_RM_B_E  # Standard version
# Initialize the robotic arm model and sensor type in the algorithm
algo_handle = Algo(arm_model, force_type)

# Convert the work frame into the base frame, where work_matrix is the matrix of the end frame in the work frame, and end_pose is the pose of the end frame in the work frame
work_matrix = algo_handle.rm_algo_pos2matrix([-0.177347, 0.438112, -0.215102, 2.09078, 0.942362, 2.39144])
end_pose =  rm_pose_t()
end_pose.position = rm_position_t(0.186350, 0.062099, 0.2)
end_pose.euler = rm_euler_t(3.141, 0, 1.569)
print(algo_handle.rm_algo_workframe2base(work_matrix, end_pose))

End pose to tool pose rm_algo_end2tool()

  • Method prototype:
python
rm_algo_end2tool(self, eu_end: rm_pose_t, flag: int = 1) -> list[float]:

Jump to rm_pose_t for details of the structure

  • Parameter description:
ParameterTypeDescription
eu_endrm_pose_tEnd pose based on world frame and default tool frame.
flagintOrientation representation, default: Euler angle. - 0: return the pose list [x, y, z, w, x, y, z] with the orientation represented by the quaternion, - 1: return the pose list [x, y, z, rx, ry, rz] with the orientation represented by the Euler angle.

list[float]: end pose based on work frame and tool frame.

  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

arm_model = rm_robot_arm_model_e.RM_MODEL_RM_65_E  # RM_65 Robotic arm
force_type = rm_force_type_e.RM_MODEL_RM_B_E  # Standard version
# Initialize the robotic arm model and sensor type in the algorithm
algo_handle = Algo(arm_model, force_type)

# Convert the end pose into the tool pose
eu_end = rm_pose_t()
eu_end.position = rm_position_t(-0.259256, -0.170727, 0.35621)
eu_end.euler = rm_euler_t(3.14, 0, 0)
print(algo_handle.rm_algo_end2tool(eu_end))

Tool pose to end pose rm_algo_tool2end()

  • Method prototype:
python
rm_algo_tool2end(self, eu_tool: rm_pose_t, flag: int = 1) -> list[float]:

Jump to rm_pose_t for details of the structure

  • Parameter description:
ParameterTypeDescription
eu_toolrm_pose_tEnd pose based on work frame and tool frame.
flagintOrientation representation, default: Euler angle. - 0: return the pose list [x, y, z, w, x, y, z] with the orientation represented by the quaternion, - 1: return the pose list [x, y, z, rx, ry, rz] with the orientation represented by the Euler angle.

list[float]: end pose based on world frame and default tool frame.

  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

arm_model = rm_robot_arm_model_e.RM_MODEL_RM_65_E  # RM_65 Robotic arm
force_type = rm_force_type_e.RM_MODEL_RM_B_E  # Standard version
# Initialize the robotic arm model and sensor type in the algorithm
algo_handle = Algo(arm_model, force_type)

# Convert the end pose into the tool pose
eu_tool = rm_pose_t()
eu_tool.position = rm_position_t(-0.259256, -0.170727, 0.35621)
eu_tool.euler = rm_euler_t(3.14, 0, 0)
print(algo_handle.rm_algo_tool2end(eu_tool))

Compute the pose in rotational movement rm_algo_RotateMove()

  • Method prototype:
python
rm_algo_RotateMove(self, curr_joint: list[float], rotate_axis: int, rotate_angle: float, choose_axis: rm_pose_t, flag: int = 1) -> list[float]:

Jump to rm_pose_t for details of the structure

  • Parameter description:
ParameterTypeDescription
curr_jointlist[float]Current joint angle, in °.
rotate_axisintRotation axis, 1: X-axis, 2: Y-axis, 3: Z-axis.
rotate_anglefloatRotation angle, in °.
choose_axisrm_pose_tSpecify the frame for computation.
flagintOrientation representation, default: Euler angle. - 0: return the pose list [x, y, z, w, x, y, z] with the orientation represented by the quaternion, - 1: return the pose list [x, y, z, rx, ry, rz] with the orientation represented by the Euler angle.
  • Return value:

list[float]: target pose.

  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

arm_model = rm_robot_arm_model_e.RM_MODEL_RM_65_E  # RM_65 Robotic arm
force_type = rm_force_type_e.RM_MODEL_RM_B_E  # Standard version
# Initialize the robotic arm model and sensor type in the algorithm
algo_handle = Algo(arm_model, force_type)

# Compute the rotation of 5° around the X-axis of the pose frame based on the current angle. The returned pose is represented by the Euler angle
current_joint = [0, 0, -60, 0, 60, 0]
pose = rm_pose_t()
pose.position = rm_position_t(-0.259256, -0.170727, 0.35621)
pose.euler = rm_euler_t(3.14, 0, 0)
print(algo_handle.rm_algo_RotateMove(current_joint, 1, 5, pose))

Compute the pose in movement along the tool frame rm_algo_cartesian_tool()

  • Method prototype:
python
rm_algo_cartesian_tool(self, curr_joint: list[float], move_lengthx: float, move_lengthy: float, move_lengthz: float, flag: int = 1) -> list[float]:
  • Parameter description:
ParameterTypeDescription
curr_jointlist[float]Current joint angle, in °.
move_lengthxfloatMovement length along the X-axis, in m.
move_lengthyfloatMovement length along the Y-axis, in m.
move_lengthzfloatMovement length along the Z-axis, in m.
flagintOrientation representation, default: Euler angle. - 0: return the pose list [x, y, z, w, x, y, z] with the orientation represented by the quaternion, - 1: return the pose list [x, y, z, rx, ry, rz] with the orientation represented by the Euler angle.
  • Return value:

list[float]: target pose.

  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

arm_model = rm_robot_arm_model_e.RM_MODEL_RM_65_E  # RM_65 Robotic arm
force_type = rm_force_type_e.RM_MODEL_RM_B_E  # Standard version
# Initialize the robotic arm model and sensor type in the algorithm
algo_handle = Algo(arm_model, force_type)

# Compute the motion pose along the tool frame based on the current angle
current_joint = [0, 0, -60, 0, 60, 0]
algo_handle.rm_algo_cartesian_tool(current_joint, 0.01, 0, 0.01)

Compute the pose after Pos and Rot have a displacement and rotation angle along a frame rm_algo_PoseMove()`

  • Method prototype:
python
rm_algo_PoseMove(self, poseCurrent: list[float], deltaPosAndRot: list[float], frameMode: int) -> list[float]
  • Parameter description:
ParameterTypeDescription
poseCurrentlist[float]Current pose (represented by the Euler angle)
deltaPosAndRotlist[float]Position and rotation array, where position in m and rotation in °
frameModeintFrame mode selection, 0: work (any frame is available), 1: tool
  • Return value:

list[float]: pose after translation and rotation

  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

arm_model = rm_robot_arm_model_e.RM_MODEL_RM_65_E  # RM_65 Robotic arm
force_type = rm_force_type_e.RM_MODEL_RM_B_E  # Standard version
# Initialize the robotic arm model and sensor type in the algorithm
algo_handle = Algo(arm_model, force_type)

# Set the current tool frame
frame = rm_frame_t("", [0.01, 0.01, 0.01, 0.5, 0.5, 0.5], 1, 0, 0, 0)
algo_handle.rm_algo_set_toolframe(frame)

# Current pose
current_joint = [0,-30,90,30,90,0]
poseCurrent = algo_handle.rm_algo_forward_kinematics(current_joint)
print("current pose:", poseCurrent)

# Compute the pose after a change
deltaPosAndRot = [0.01,0.01,0.01,20,20,20]
afterPosAndRot = algo_handle.rm_algo_PoseMove(poseCurrent, deltaPosAndRot,1)
print("pose after translation and rotation:", afterPosAndRot)