Position and Pose
Load Waypoint Pose from Resource Library
pose = lebai:load_pose(name, dir)
- Parameters
name
Namedir
Workspace name. Optional, default root directory
- Returns
pose
Pose relative to base
JSON-RPC
// Request:
{ "jsonrpc": "2.0", "method": "load_pose", "params": [{"name": "", "dir": ""}], "id": 1 }
// Response:
{ "jsonrpc": "2.0", "result": {"kind": ""}, "id": 1 }
Save Waypoint Pose to Resource Library
lebai:save_pose(name, pose, dir)
- Parameters
name
Namepose
Pose relative to basedir
Workspace name. Optional, default root directory
JSON-RPC
// Request:
{ "jsonrpc": "2.0", "method": "save_pose", "params": [{"name": "", "dir": "", "data": {}}], "id": 1 }
// Response:
{ "jsonrpc": "2.0", "result": {}, "id": 1 }
Load Feature Coordinate System from Resource Library
frame = lebai:load_frame(name, dir)
- Parameters
name
Namedir
Workspace name. Optional, default root directory
- Returns
frame
Offset relative to base
JSON-RPC
// Request:
{ "jsonrpc": "2.0", "method": "load_frame", "params": [{"name": "", "dir": ""}], "id": 1 }
// Response:
{ "jsonrpc": "2.0", "result": {"position": {}, "rotation": {}}, "id": 1 }
Forward Kinematics
cart = lebai:kinematics_forward(pose)
Convert joint angles to Cartesian position and pose through robot forward kinematics.
- Parameters
pose
Pose
- Returns
cart
Cartesian space pose
JSON-RPC
// Request:
{ "jsonrpc": "2.0", "method": "get_forward_kin", "params": [{"kind": ""}], "id": 1 }
// Response:
{ "jsonrpc": "2.0", "result": {"position": {}, "rotation": {}}, "id": 1 }
Inverse Kinematics
joints = lebai:kinematics_inverse(pose, joints)
Convert Cartesian position and pose to joint angles through robot inverse kinematics. The calculation result depends on current TCP settings and current joint position.
- Parameters
pose
Posejoints
Joint space reference position. Optional, default is current feedback joint position. When multiple solutions exist, the solution closest tojoints
will be chosen.
- Returns
joints
Joint space pose
JSON-RPC
// Request:
{ "jsonrpc": "2.0", "method": "get_inverse_kin", "params": [{"kind": ""}], "id": 1 }
// Response:
{ "jsonrpc": "2.0", "result": {"joint": [0]}, "id": 1 }
Pose Feature Coordinate System Transformation
c = lebai:pose_trans(a, b)
Using a as user coordinate system , b is pose description relative to coordinate system . Finally returns pose description relative to robot world coordinate system
- Parameters
a
Poseb
Pose
- Returns
c
Pose
JSON-RPC
// Request:
{ "jsonrpc": "2.0", "method": "get_pose_trans", "params": [{"from": {"kind": ""}, "from_to": {"kind": ""}}], "id": 1 }
// Response:
{ "jsonrpc": "2.0", "result": {"position": {}, "rotation": {}}, "id": 1 }
Inverse of Pose
c = lebai:pose_inverse(a)
Used to find pose description of inverse of homogeneous matrix corresponding to pose a. Can be used to solve pose equations.
Inverse of homogeneous matrix equals its transpose .
- Parameters
a
Pose
- Returns
c
Inverse of :
JSON-RPC
// Request:
{ "jsonrpc": "2.0", "method": "get_pose_inverse", "params": [{"kind": ""}], "id": 1 }
// Response:
{ "jsonrpc": "2.0", "result": {"position": {}, "rotation": {}}, "id": 1 }
3.1.13
Add Posepose = lebai:pose_add(base, delta, frame)
Pose after moving delta in frame direction from base position
- Parameters
base
. Starting posedelta
. Pose offsetframe
. Direction of pose offset, only valid for pose part. Optional, default base direction
- Returns
pose
. Pose after movement
Example Program
base = {x=-0.4, y=0, z=0.1, rz=-1.57, ry=0, rx=1.57}
frame = {x=0, y=0, z=0, rz=0, ry=-0.78, rx=0} -- Rotate 45° around y-axis to make z-axis point diagonally up
delta = {x=0, y=0, z=0.1, rz=0, ry=0, rx=0} -- Move 0.1m along z-axis
pose = lebai:pose_add(base, delta, frame)
lebai:movej(base, 0.4, 0.1)
lebai:movel(pose, 0.4, 0.1)