ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
So my assumption is the IK solution given by ur_driver is not precise.
ur_driver
does not contain any functionality related to IK or FK.
FK is performed by robot_state_publisher
based on the urdf.
IK is performed by whatever kinematics solver you have configured. That could be ur_kinematics
, trac_ik
, KDL
or something else.
The urdf is most certainly not completely correct for your robot. That would be the one source of positional error. That is being addressed in ros-industrial/universal_robot#414.
Secondly: both URScript, MoveIt and the driver use different tolerances for when a motion is completed. It could well be that this also contributes here.
Finally, the differences you show appear to be in the micrometers range (ROS uses metres for distances):
X Y Z
moveit: 0.33561 -0.13135 0.1815
movej: 0.33667 -0.13125 0.18217
----------------------------------
-0.00106 0.0001 -0.00067
The repeatability of a UR5 is specced as +-0.1mm
or 0.001m
. Taking that into account the differences don't seem to be so egregious.
2 | No.2 Revision |
So my assumption is the IK solution given by ur_driver is not precise.
ur_driver
does not contain any functionality related to IK or FK.
FK is performed by robot_state_publisher
based on the urdf.
IK is performed by whatever kinematics solver you have configured. That could be ur_kinematics
, trac_ik
, KDL
or something else.
The urdf is most certainly not completely correct for your robot. That would be the one source of positional error. That is being addressed in ros-industrial/universal_robot#414.
Secondly: both URScript, MoveIt and the driver use different tolerances for when a motion is completed. It could well be that this also contributes here.
Finally, the differences you show appear to be in the micrometers range (ROS uses metres for distances):
X Y Z
moveit: 0.33561 -0.13135 0.1815
movej: 0.33667 -0.13125 0.18217
----------------------------------
-0.00106 0.0001 -0.00067
The repeatability of a UR5 is specced as +-0.1mm
or 0.001m
. (datasheet). Taking that into account the differences don't seem to be so egregious.
3 | No.3 Revision |
So my assumption is the IK solution given by ur_driver is not precise.
ur_driver
does not contain any functionality related to IK or FK.
FK is performed by robot_state_publisher
based on the urdf.urdf, or the integrated version of that in MoveIt.
IK is performed by whatever kinematics solver you have configured. That could be ur_kinematics
, trac_ik
, KDL
or something else.
The urdf is most certainly not completely correct for your robot. That would be the one source of positional error. That is being addressed in ros-industrial/universal_robot#414.
Secondly: both URScript, MoveIt and the driver use different tolerances for when a motion is completed. It could well be that this also contributes here.
Finally, the differences you show appear to be in the micrometers range (ROS uses metres for distances):
X Y Z
moveit: 0.33561 -0.13135 0.1815
movej: 0.33667 -0.13125 0.18217
----------------------------------
-0.00106 0.0001 -0.00067
The repeatability of a UR5 is specced as +-0.1mm
or 0.001m
(datasheet). Taking that into account the differences don't seem to be so egregious.
4 | No.4 Revision |
So my assumption is the IK solution given by ur_driver is not precise.
ur_driver
does not contain any functionality related to IK or FK.
FK is performed by robot_state_publisher
based on the urdf, or the integrated version of that in MoveIt.
IK is performed by whatever kinematics solver you have configured. That could be ur_kinematics
, trac_ik
, KDL
or something else.
The urdf is most certainly not completely correct for your robot. That would be the one source of positional error. That is being addressed in ros-industrial/universal_robot#414.
Secondly: both URScript, MoveIt and the driver use different tolerances for when a motion is completed. It could well be that this also contributes here.
Finally, the differences you show appear to be in the micrometers range (ROS uses metres for distances):
X Y Z
moveit: 0.33561 -0.13135 0.1815
movej: 0.33667 -0.13125 0.18217
----------------------------------
-0.00106 0.0001 -0.00067
The repeatability of a UR5 is specced as +-0.1mm
or 0.001m
(datasheet). Taking that into account the differences don't seem to be so egregious.