1
0
mirror of https://gitlab.com/obbart/universal_robots_ros_driver.git synced 2026-04-10 01:50:46 +02:00

Simplified calibration interface

When showing this to collegues it turned out that this was quite complicated.
I reduced the target definition to a simple filename, while documenting
the package approach separately.
This commit is contained in:
Felix Mauch
2019-10-07 10:42:54 +02:00
committed by Tristan Schnell
parent 344052d4c7
commit 5138ecab82
4 changed files with 72 additions and 97 deletions

View File

@@ -13,37 +13,60 @@ to do so, as end effector positions might be off in the magnitude of centimeters
This node extracts calibration information directly from a robot, calculates the URDF correction and
saves it into a .yaml file.
With the parameters explained below calibration will be saved inside
```bash
<output_package_name>/<subfolder>/<robot_name>_calibration.yaml
```
#### Helper script
In the launch folder of the ur_calibration package is a helper script:
$ roslaunch ur_calibration calibration_correction.launch \
robot_ip:=<robot_ip> \
robot_name:=<robot_name> \
output_package_name:=ur_calibration \
subfolder_name:=etc
```bash
$ roslaunch ur_calibration calibration_correction.launch \
robot_ip:=<robot_ip> target_filename:="${HOME}/my_robot_calibration.yaml"
```
For the parameter **<robot_ip>** insert the ip on which the ROS pc can reach the robot. The
**<robot_name>** is an arbitrary name you can give to the robot. It is recommended, to choose a unique
name that can be easily matched to the physical robot.
As soon as you see the output
For the parameter `robot_ip` insert the IP address on which the ROS pc can reach the robot. As
`target_filename` provide an absolute path where the result will be saved to.
[ INFO] [1560953586.352160902]: Calibration correction done
## Creating a calibration / launch package for all local robots
When dealing with multiple robots in one organization it might make sense to store calibration data
into a package dedicated to that purpose only. To do so, create a new package (if it doesn't already
exist)
you can exit the roslaunch by pressing `CTRL+C`.
#### Prerequisites for binary installation
In the example above, we use the **ur_calibration** package from this repository. This won't work,
if you use a binary installation of this driver. In that case please create a new ROS package
by going to your catkin_workspace's src folder and calling:
```bash
# Replace your actual catkin_ws folder
$ cd <catkin_ws>/src
$ catkin_create_pkg example_organization_ur_launch ur_rtde_driver \
-D "Package containing calibrations and launch files for our UR robots."
# Create a skeleton package
$ mkdir -p example_organization_ur_launch/etc
$ mkdir -p example_organization_ur_launch/launch
```
catkin_create_pkg my_calibrations
We can use the new package to store the calibration data in that package. We recommend naming each
robot individually, e.g. *ex-ur10-1*.
It is recommended to adapt the new package's *package.xml* with a meaningful description.
```bash
$ roslaunch ur_calibration calibration_correction.launch \
robot_ip:=<robot_ip> \
target_filename:="$(rospack find example_organization_ur_launch)/etc/ex-ur10-1_calibration.yaml"
```
To make life easier, we create a launchfile for this particular robot. We base it upon the
respective launchfile in the driver:
```bash
# Replace your actual catkin_ws folder
$ cd <catkin_ws>/src/example_organization_ur_launch/launch
$ roscp ur_rtde_driver ur10_bringup.launch ex-ur10-1.launch
```
Next, modify the parameter section of the new launchfile to match your actual calibration:
```xml
<!-- Note: Only the relevant lines are printed here-->
<arg name="robot_ip" default="192.168.0.101"/> <!-- if there is a default IP scheme for your
robots -->
<arg name="kinematics_config" default="$(find example_organization_ur_launch)/etc/ex-ur10-1_calibration.yaml"/>
```
Then, anybody cloning this repository can startup the robot simply by launching
```bash
$ roslaunch example_organization_ur_launch ex-ur10-1.launch
```