mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 10:00:48 +02:00
print an error message in calibration and exit when connection cannot be established
This commit is contained in:
@@ -183,13 +183,20 @@ int main(int argc, char* argv[])
|
|||||||
ros::init(argc, argv, "ur_calibration");
|
ros::init(argc, argv, "ur_calibration");
|
||||||
ros::NodeHandle nh("~");
|
ros::NodeHandle nh("~");
|
||||||
|
|
||||||
CalibrationCorrection my_calibration_correction(nh);
|
try
|
||||||
my_calibration_correction.run();
|
|
||||||
if (!my_calibration_correction.writeCalibrationData())
|
|
||||||
{
|
{
|
||||||
ROS_ERROR_STREAM("Failed writing calibration data. See errors above for details.");
|
CalibrationCorrection my_calibration_correction(nh);
|
||||||
return -1;
|
my_calibration_correction.run();
|
||||||
|
if (!my_calibration_correction.writeCalibrationData())
|
||||||
|
{
|
||||||
|
ROS_ERROR_STREAM("Failed writing calibration data. See errors above for details.");
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
ROS_INFO("Calibration correction done");
|
||||||
|
}
|
||||||
|
catch (const UrException& e)
|
||||||
|
{
|
||||||
|
ROS_ERROR_STREAM(e.what());
|
||||||
}
|
}
|
||||||
ROS_INFO("Calibration correction done");
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|||||||
Reference in New Issue
Block a user