mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-12 19:10:47 +02:00
Made calibration extraction a working node.
This commit is contained in:
@@ -14,6 +14,8 @@
|
||||
|
||||
#include <ur_calibration/calibration.h>
|
||||
|
||||
namespace ur_calibration
|
||||
{
|
||||
Calibration::Calibration(const DHRobot& robot_parameters) : robot_parameters_(robot_parameters)
|
||||
{
|
||||
buildChain();
|
||||
@@ -206,7 +208,7 @@ std::vector<Eigen::Matrix4d> Calibration::getSimplified() const
|
||||
return simplified_chain;
|
||||
}
|
||||
|
||||
void Calibration::writeToYaml(std::ofstream& ofstream) const
|
||||
YAML::Node Calibration::toYaml() const
|
||||
{
|
||||
YAML::Node node;
|
||||
|
||||
@@ -226,5 +228,6 @@ void Calibration::writeToYaml(std::ofstream& ofstream) const
|
||||
node["kinematics"][link_names_[i]] = link;
|
||||
}
|
||||
|
||||
ofstream << node;
|
||||
return node;
|
||||
}
|
||||
} // namespace ur_calibration
|
||||
|
||||
Reference in New Issue
Block a user