mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 18:10:47 +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:
committed by
Tristan Schnell
parent
344052d4c7
commit
5138ecab82
35
README.md
35
README.md
@@ -125,42 +125,19 @@ Each UR robot is calibrated inside the factory giving exact forward and inverse
|
|||||||
make use of this in ROS, you first have to extract the calibration information from the robot.
|
make use of this in ROS, you first have to extract the calibration information from the robot.
|
||||||
|
|
||||||
Though this step is not necessary, to control the robot using this driver, it is highly recommended
|
Though this step is not necessary, to control the robot using this driver, it is highly recommended
|
||||||
to do so, as endeffector positions might be off in the magnitude of centimeters.
|
to do so, as otherwise endeffector positions might be off in the magnitude of centimeters.
|
||||||
|
|
||||||
|
|
||||||
For this, there exists a helper script:
|
For this, there exists a helper script:
|
||||||
|
|
||||||
$ roslaunch ur_calibration calibration_correction.launch \
|
$ roslaunch ur_calibration calibration_correction.launch \
|
||||||
robot_ip:=<robot_ip> \
|
robot_ip:=<robot_ip> target_filename:="${HOME}/my_robot_calibration.yaml"
|
||||||
robot_name:=<robot_name> \
|
|
||||||
output_package_name:=ur_calibration \
|
|
||||||
subfolder_name:=etc
|
|
||||||
|
|
||||||
|
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.
|
||||||
|
|
||||||
As soon as you see the output:
|
We recommend keeping calibrations for all robots in your organization in a common package. See the
|
||||||
|
[package's documentation](ur_calibration/README.md) for details.
|
||||||
[ INFO] [1560953586.352160902]: Calibration correction done
|
|
||||||
|
|
||||||
you can exit the roslaunch by bressing `CTRL+C`.
|
|
||||||
|
|
||||||
|
|
||||||
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.
|
|
||||||
|
|
||||||
The resulting yaml file is stored in the package specified in the **output_package_name** parameter
|
|
||||||
inside the folder **subfolder_name** with the name **robot_name***_calibration.yaml*. The parameter
|
|
||||||
**subfolder_name** is optional and defaults to *etc* if not given.
|
|
||||||
|
|
||||||
|
|
||||||
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 (before performing the calibration) by
|
|
||||||
going to your catkin_workspace's src folder and calling:
|
|
||||||
|
|
||||||
catkin_create_pkg my_calibrations
|
|
||||||
|
|
||||||
For further information on the calibration extraction, please see the [documentation of package
|
|
||||||
`ur_calibration`](ur_calibration/README.md).
|
|
||||||
|
|
||||||
#### Quick start
|
#### Quick start
|
||||||
Once the driver is built and the **externalcontrol** URCap is installed on the robot, you are good
|
Once the driver is built and the **externalcontrol** URCap is installed on the robot, you are good
|
||||||
|
|||||||
@@ -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
|
This node extracts calibration information directly from a robot, calculates the URDF correction and
|
||||||
saves it into a .yaml file.
|
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:
|
In the launch folder of the ur_calibration package is a helper script:
|
||||||
|
|
||||||
$ roslaunch ur_calibration calibration_correction.launch \
|
```bash
|
||||||
robot_ip:=<robot_ip> \
|
$ roslaunch ur_calibration calibration_correction.launch \
|
||||||
robot_name:=<robot_name> \
|
robot_ip:=<robot_ip> target_filename:="${HOME}/my_robot_calibration.yaml"
|
||||||
output_package_name:=ur_calibration \
|
```
|
||||||
subfolder_name:=etc
|
|
||||||
|
|
||||||
For the parameter **<robot_ip>** insert the ip on which the ROS pc can reach the robot. The
|
For the parameter `robot_ip` insert the IP address on which the ROS pc can reach the robot. As
|
||||||
**<robot_name>** is an arbitrary name you can give to the robot. It is recommended, to choose a unique
|
`target_filename` provide an absolute path where the result will be saved to.
|
||||||
name that can be easily matched to the physical robot.
|
|
||||||
|
|
||||||
As soon as you see the output
|
## 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)
|
||||||
|
|
||||||
[ INFO] [1560953586.352160902]: Calibration correction done
|
```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
|
||||||
|
```
|
||||||
|
|
||||||
you can exit the roslaunch by pressing `CTRL+C`.
|
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*.
|
||||||
|
|
||||||
|
```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"
|
||||||
|
```
|
||||||
|
|
||||||
#### Prerequisites for binary installation
|
To make life easier, we create a launchfile for this particular robot. We base it upon the
|
||||||
In the example above, we use the **ur_calibration** package from this repository. This won't work,
|
respective launchfile in the driver:
|
||||||
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:
|
|
||||||
|
|
||||||
catkin_create_pkg my_calibrations
|
```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
|
||||||
|
```
|
||||||
|
|
||||||
It is recommended to adapt the new package's *package.xml* with a meaningful description.
|
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
|
||||||
|
```
|
||||||
|
|||||||
@@ -1,14 +1,10 @@
|
|||||||
<?xml version="1.0"?>
|
<?xml version="1.0"?>
|
||||||
<launch>
|
<launch>
|
||||||
<arg name="robot_ip"/>
|
<arg name="robot_ip" doc="The IP address at which the robot is reachable."/>
|
||||||
<arg name="robot_name"/>
|
<arg name="target_filename" default="robot_calibration.yaml" doc="The extracted calibration information will be written to this target file."/>
|
||||||
<arg name="output_package_name" default="ur_calibration"/>
|
|
||||||
<arg name="subfolder_name" default="etc"/>
|
|
||||||
|
|
||||||
<node name="calibration_correction" pkg="ur_calibration" type="calibration_correction" respawn="false" output="screen">
|
<node name="calibration_correction" pkg="ur_calibration" type="calibration_correction" respawn="false" output="screen">
|
||||||
<param name="robot_ip" value="$(arg robot_ip)"/>
|
<param name="robot_ip" value="$(arg robot_ip)"/>
|
||||||
<param name="robot_name" value="$(arg robot_name)"/>
|
<param name="output_filename" value="$(arg target_filename)"/>
|
||||||
<param name="output_package_name" value="$(arg output_package_name)"/>
|
|
||||||
<param name="subfolder_name" value="$(arg subfolder_name)"/>
|
|
||||||
</node>
|
</node>
|
||||||
</launch>
|
</launch>
|
||||||
|
|||||||
@@ -60,33 +60,20 @@ class CalibrationCorrection
|
|||||||
public:
|
public:
|
||||||
CalibrationCorrection(const ros::NodeHandle& nh) : nh_(nh)
|
CalibrationCorrection(const ros::NodeHandle& nh) : nh_(nh)
|
||||||
{
|
{
|
||||||
subfolder_ = nh_.param<std::string>("subfolder_name", "etc");
|
|
||||||
std::string output_package_name;
|
std::string output_package_name;
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
// The robot's IP address
|
// The robot's IP address
|
||||||
robot_ip_ = getRequiredParameter<std::string>("robot_ip");
|
robot_ip_ = getRequiredParameter<std::string>("robot_ip");
|
||||||
|
|
||||||
// Name with which the robot will be referenced. Will be used for the filename the calibration
|
// The target file where the calibration data is written to
|
||||||
// data is stored in. This can be any arbitrary name. If left empty, the robot's serial number
|
output_filename_ = getRequiredParameter<std::string>("output_filename");
|
||||||
// will be used.
|
|
||||||
robot_name_ = getRequiredParameter<std::string>("robot_name");
|
|
||||||
|
|
||||||
// The resulting parameter file will be stored inside
|
|
||||||
// <output_package_name>/<subfolder>/<robot_name>_calibration.yaml
|
|
||||||
output_package_name = getRequiredParameter<std::string>("output_package_name");
|
|
||||||
}
|
}
|
||||||
catch (const ParamaterMissingException& e)
|
catch (const ParamaterMissingException& e)
|
||||||
{
|
{
|
||||||
ROS_FATAL_STREAM(e.what());
|
ROS_FATAL_STREAM(e.what());
|
||||||
exit(1);
|
exit(1);
|
||||||
}
|
}
|
||||||
package_path_ = ros::package::getPath(output_package_name);
|
|
||||||
if (package_path_ == "")
|
|
||||||
{
|
|
||||||
ROS_FATAL_STREAM("Could not find package " << output_package_name << ". Cannot save output file there.");
|
|
||||||
exit(1);
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
virtual ~CalibrationCorrection() = default;
|
virtual ~CalibrationCorrection() = default;
|
||||||
@@ -118,26 +105,20 @@ public:
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
ROS_INFO_STREAM("Writing calibration data");
|
fs::path out_path = fs::complete(output_filename_);
|
||||||
fs::path dst_path = fs::path(package_path_) / fs::path(subfolder_);
|
|
||||||
|
fs::path dst_path = out_path.parent_path();
|
||||||
if (!fs::exists(dst_path))
|
if (!fs::exists(dst_path))
|
||||||
{
|
{
|
||||||
try
|
ROS_ERROR_STREAM("Parent folder " << dst_path << " does not exist.");
|
||||||
{
|
return false;
|
||||||
fs::create_directory(dst_path);
|
|
||||||
}
|
|
||||||
catch (const boost::filesystem::filesystem_error& e)
|
|
||||||
{
|
|
||||||
ROS_ERROR_STREAM("Could not create " << dst_path << ". Reason: " << e.what());
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
fs::path output_filename = dst_path / fs::path(robot_name_ + "_calibration.yaml");
|
ROS_INFO_STREAM("Writing calibration data to " << out_path);
|
||||||
if (fs::exists(output_filename))
|
if (fs::exists(output_filename_))
|
||||||
{
|
{
|
||||||
ROS_WARN_STREAM("Output file " << output_filename << " already exists. Overwriting.");
|
ROS_WARN_STREAM("Output file " << output_filename_ << " already exists. Overwriting.");
|
||||||
}
|
}
|
||||||
std::ofstream file(output_filename.string());
|
std::ofstream file(output_filename_);
|
||||||
if (file.is_open())
|
if (file.is_open())
|
||||||
{
|
{
|
||||||
file << *calibration_data_;
|
file << *calibration_data_;
|
||||||
@@ -147,7 +128,7 @@ public:
|
|||||||
ROS_ERROR_STREAM("Failed writing the file. Do you have the correct rights?");
|
ROS_ERROR_STREAM("Failed writing the file. Do you have the correct rights?");
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
ROS_INFO_STREAM("Wrote output to " << output_filename);
|
ROS_INFO_STREAM("Wrote output.");
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
@@ -171,9 +152,7 @@ private:
|
|||||||
|
|
||||||
ros::NodeHandle nh_;
|
ros::NodeHandle nh_;
|
||||||
std::string robot_ip_;
|
std::string robot_ip_;
|
||||||
std::string robot_name_;
|
std::string output_filename_;
|
||||||
std::string package_path_;
|
|
||||||
std::string subfolder_;
|
|
||||||
|
|
||||||
std::unique_ptr<YAML::Node> calibration_data_;
|
std::unique_ptr<YAML::Node> calibration_data_;
|
||||||
};
|
};
|
||||||
|
|||||||
Reference in New Issue
Block a user