mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-12 19:10:47 +02:00
move calibration check to ros-independent part
This commit is contained in:
@@ -31,10 +31,6 @@
|
||||
|
||||
#include <Eigen/Geometry>
|
||||
|
||||
#include <ur_rtde_driver/primary/package_header.h>
|
||||
#include <ur_rtde_driver/primary/primary_parser.h>
|
||||
#include <ur_rtde_driver/ur/calibration_checker.h>
|
||||
|
||||
namespace ur_driver
|
||||
{
|
||||
HardwareInterface::HardwareInterface()
|
||||
@@ -72,10 +68,6 @@ bool HardwareInterface ::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_h
|
||||
|
||||
std::string tf_prefix = robot_hw_nh.param<std::string>("tf_prefix", "");
|
||||
|
||||
ROS_INFO_STREAM("Checking if calibration data matches connected robot.");
|
||||
std::string calibration_checksum = robot_hw_nh.param<std::string>("kinematics/hash", "");
|
||||
checkCalibration(calibration_checksum);
|
||||
|
||||
program_state_pub_ = robot_hw_nh.advertise<std_msgs::Bool>("robot_program_running", 10, true);
|
||||
tcp_transform_.header.frame_id = "base";
|
||||
tcp_transform_.child_frame_id = "tool0_controller";
|
||||
@@ -137,12 +129,13 @@ bool HardwareInterface ::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_h
|
||||
tool_comm_setup->setTxIdleChars(tx_idle_chars);
|
||||
}
|
||||
|
||||
std::string calibration_checksum = robot_hw_nh.param<std::string>("kinematics/hash", "");
|
||||
ROS_INFO_STREAM("Initializing urdriver");
|
||||
try
|
||||
{
|
||||
ur_driver_.reset(new UrDriver(robot_ip_, script_filename, recipe_filename,
|
||||
std::bind(&HardwareInterface::handleRobotProgramState, this, std::placeholders::_1),
|
||||
std::move(tool_comm_setup)));
|
||||
std::move(tool_comm_setup), calibration_checksum));
|
||||
}
|
||||
catch (ur_driver::ToolCommNotAvailable& e)
|
||||
{
|
||||
@@ -435,27 +428,6 @@ void HardwareInterface ::publishPose()
|
||||
}
|
||||
}
|
||||
|
||||
void HardwareInterface ::checkCalibration(const std::string& checksum)
|
||||
{
|
||||
comm::URStream<ur_driver::primary_interface::PackageHeader> stream(robot_ip_,
|
||||
ur_driver::primary_interface::UR_PRIMARY_PORT);
|
||||
primary_interface::PrimaryParser parser;
|
||||
comm::URProducer<ur_driver::primary_interface::PackageHeader> prod(stream, parser);
|
||||
|
||||
CalibrationChecker consumer(checksum);
|
||||
|
||||
comm::INotifier notifier;
|
||||
|
||||
comm::Pipeline<ur_driver::primary_interface::PackageHeader> pipeline(prod, consumer, "Pipeline", notifier);
|
||||
pipeline.run();
|
||||
|
||||
while (!consumer.isChecked())
|
||||
{
|
||||
ros::Duration(1).sleep();
|
||||
}
|
||||
ROS_DEBUG_STREAM("Got calibration information from robot.");
|
||||
}
|
||||
|
||||
bool HardwareInterface::stopControl(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res)
|
||||
{
|
||||
if (isRobotProgramRunning())
|
||||
|
||||
Reference in New Issue
Block a user