1
0
mirror of https://gitlab.com/obbart/universal_robots_ros_driver.git synced 2026-04-12 11:00:47 +02:00

replace tcp_accuracy_checker with hash comparison

This closes #34
This commit is contained in:
Felix Mauch
2019-06-14 14:35:50 +02:00
parent 34eb8dcf08
commit 7e6b203b67
13 changed files with 133 additions and 106 deletions

View File

@@ -0,0 +1,47 @@
// this is for emacs file handling -*- mode: c++; indent-tabs-mode: nil -*-
// -- BEGIN LICENSE BLOCK ----------------------------------------------
// -- END LICENSE BLOCK ------------------------------------------------
//----------------------------------------------------------------------
/*!\file
*
* \author Felix Mauch mauch@fzi.de
* \date 2019-06-14
*
*/
//----------------------------------------------------------------------
#include <ur_rtde_driver/ur/calibration_checker.h>
namespace ur_driver
{
CalibrationChecker::CalibrationChecker(const std::string& expected_hash)
: expected_hash_(expected_hash), checked_(false)
{
}
bool CalibrationChecker::consume(std::shared_ptr<comm::URPackage<primary_interface::PackageHeader>> product)
{
auto kin_info = std::dynamic_pointer_cast<primary_interface::KinematicsInfo>(product);
if (kin_info != nullptr)
{
// LOG_INFO("%s", product->toString().c_str());
//
if (kin_info->toHash() != expected_hash_)
{
LOG_ERROR("The calibration parameters of the connected robot don't match the ones from the given kinematics "
"config file. Please be aware that this can lead to critical inaccuracies of tcp positions. Use the "
"ur_calibration tool to extract the correct calibration from the robot and pass that into the "
"description. See [TODO Link to documentation] for details.");
}
else
{
LOG_INFO("Calibration checked successfully.");
}
checked_ = true;
}
return true;
}
} // namespace ur_driver