xArm-Developer / xArm-Python-SDK

Python SDK for UFACTORY robots, 850, xArm5/6/7, and Lite6.
https://www.ufactory.cc
BSD 3-Clause "New" or "Revised" License
149 stars 100 forks source link

Wrong forward kinematics? #115

Open orrkrup opened 1 month ago

orrkrup commented 1 month ago

I'm using the xArm Lite6, and it seems like I am getting wrong kinematics calculations when calling get_forward_kinematics().

For example, if calling get_forward_kinematics([0, 0, 0, 0, 0, 0]) I expect to get the TCP position of (87, 0, 70.6), given the kinematic parameters here, and the TCP offset of 83.6 mm. This can be verified by manual calculation, using the DH parameters (both from the link above and by calling get_dh_parameters()). However, the API returns (90.1, 0.6, 69.8), which is also what appears on Studio.

Is this a bug in the forward kinematics function? Or is there an inherent offset in the joint angles?

penglongxiang commented 1 month ago

Hi @orrkrup, recently we have added kinematics calibration to our product, thus the actual kinematic parameters will be a little different from the nominal DH parameters we provide. The results from get_forward_kinematics() API and Studio have already taken the calibration into account.

If you need to extract the calibrated parameters, please download the following python script and run python3 gen_kinematics_params.py {robot_ip} {kinematics_suffix}, the suffix is an arbitrary string to distinguish between multiple arms. It will then generate a yaml file in user/ directory.

Inside the yaml file, there is the extracted calibrated parameters of your robot arm. Please note the form will not be DH any more, it is the 6DOF (x,y,z, roll pitch yaw) transformation relationship between adjacent joint coordinates, and the unit is in Meters and Radians. Please refer to our user manual for roll pitch yaw Euler angle definitions. If you apply serial matrix calculation based on this extracted parameters, the FK result should agree with that shown on Studio.

orrkrup commented 1 month ago

Thank you, the script works as described.

Should I expect these parameters to vary between different Lite 6 robots? Or is this kinematics calibration identical for all Lite 6 instances?

penglongxiang commented 4 weeks ago

Calibration parameters are different from any other robot, due to the mechanical part and assembly error are not the same for each arm.