lebai sdk  1.4.4
lebai c++ sdk with swig to support sereval languages.
Functions
机器人.

机器人计算相关的接口. More...

Functions

KinematicsForwardResp lebai::l_master::Robot::get_forward_kin (const std::vector< double > &joint_positions)
 根据机械臂关节位置计算机器人末端位姿(位置的运动学正解). More...
 
KinematicsForwardResp lebai::l_master::Robot::kinematics_forward (const std::vector< double > &joint_positions)
 
KinematicsInverseResp lebai::l_master::Robot::get_inverse_kin (const CartesianPose &pose, const std::vector< double > &joint_init_positions={})
 根据机械臂的末端位姿计算关节位置(位置的运动学逆解). More...
 
KinematicsInverseResp lebai::l_master::Robot::kinematics_inverse (const CartesianPose &pose, const std::vector< double > &joint_init_positions={})
 
double lebai::l_master::Robot::measure_manipulation (const std::vector< double > &joint_positions)
 估算关节位置的灵活性. More...
 
CartesianPose lebai::l_master::Robot::get_pose_trans (const CartesianPose &a, const CartesianPose &b)
 位姿变换乘法(等价于对应的齐次坐标矩阵乘法) More...
 
CartesianPose lebai::l_master::Robot::pose_times (const CartesianPose &a, const CartesianPose &b)
 
CartesianPose lebai::l_master::Robot::get_pose_add (const CartesianPose &pose, const CartesianPose &delta)
 位姿加. More...
 
CartesianPose lebai::l_master::Robot::calc_frame (const CartesianPose &o, const CartesianPose &x, const CartesianPose &xy)
 三点采样计算原点特征. More...
 
CartesianPose lebai::l_master::Robot::calc_tcp (const std::vector< CartesianPose > &poses)
 三点采样计算工具中心点. More...
 
CartesianPose lebai::l_master::Robot::get_pose_inverse (const CartesianPose &in)
 位姿变换的逆(等价于对应的齐次坐标矩的逆) More...
 
CartesianPose lebai::l_master::Robot::pose_inverse (const CartesianPose &in)
 

Detailed Description

机器人计算相关的接口.

Function Documentation

◆ calc_frame()

CartesianPose lebai::l_master::Robot::calc_frame ( const CartesianPose &  o,
const CartesianPose &  x,
const CartesianPose &  xy 
)

三点采样计算原点特征.

Parameters
o原点.
xX轴点.
xyXY平面点.

◆ calc_tcp()

CartesianPose lebai::l_master::Robot::calc_tcp ( const std::vector< CartesianPose > &  poses)

三点采样计算工具中心点.

Parameters
poses采样位姿列表,至少3个.

◆ get_forward_kin()

KinematicsForwardResp lebai::l_master::Robot::get_forward_kin ( const std::vector< double > &  joint_positions)

根据机械臂关节位置计算机器人末端位姿(位置的运动学正解).

Parameters
joint_positions机械臂关节位置的数组.
Returns
返回计算结果 KinematicsForwardResp.

◆ get_inverse_kin()

KinematicsInverseResp lebai::l_master::Robot::get_inverse_kin ( const CartesianPose &  pose,
const std::vector< double > &  joint_init_positions = {} 
)

根据机械臂的末端位姿计算关节位置(位置的运动学逆解).

Parameters
pose机械臂末端位姿,应当包括键为x,y,z,rz,ry,rx的值.
joint_init_positions机械臂关节初始位置, 以数组形式传入.
Returns
返回计算结果 KinematicsInverseResp.

◆ get_pose_add()

CartesianPose lebai::l_master::Robot::get_pose_add ( const CartesianPose &  pose,
const CartesianPose &  delta 
)

位姿加.

Parameters
pose基准位姿.
delta增量位姿.

◆ get_pose_inverse()

CartesianPose lebai::l_master::Robot::get_pose_inverse ( const CartesianPose &  in)

位姿变换的逆(等价于对应的齐次坐标矩的逆)

Parameters
in位姿,应当包括键为x,y,z,rz,ry,rx的值.
Returns
CartesianPose 返回位姿变换的逆,应当包括键为x,y,z,rz,ry,rx的值.

◆ get_pose_trans()

CartesianPose lebai::l_master::Robot::get_pose_trans ( const CartesianPose &  a,
const CartesianPose &  b 
)

位姿变换乘法(等价于对应的齐次坐标矩阵乘法)

Parameters
[in]a位姿,应当包括键为x,y,z,rz,ry,rx的值.
[in]b位姿,应当包括键为x,y,z,rz,ry,rx的值.
Returns
CartesianPose 返回的位姿,应当包括键为x,y,z,rz,ry,rx的值.

◆ measure_manipulation()

double lebai::l_master::Robot::measure_manipulation ( const std::vector< double > &  joint_positions)

估算关节位置的灵活性.

Parameters
joint_positions机械臂关节位置数组.
Returns
灵活性估算值.