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

explicitly throw special exception when tool_comm is not available

This way, we can catch it and give a better feedback to the user.
This commit is contained in:
Felix Mauch
2019-06-12 09:06:34 +02:00
parent 520cd4d860
commit 5f405b3996
4 changed files with 36 additions and 17 deletions

View File

@@ -27,6 +27,7 @@
#include "ur_rtde_driver/ros/hardware_interface.h"
#include "ur_rtde_driver/ur/tool_communication.h"
#include <ur_rtde_driver/exceptions.h>
#include <Eigen/Geometry>
@@ -125,9 +126,22 @@ bool HardwareInterface ::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_h
}
ROS_INFO_STREAM("Initializing urdriver");
ur_driver_.reset(new UrDriver(robot_ip, script_filename, recipe_filename,
std::bind(&HardwareInterface::handleRobotProgramState, this, std::placeholders::_1),
std::move(tool_comm_setup)));
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)));
}
catch (ur_driver::ToolCommNotAvailable& e)
{
ROS_FATAL_STREAM(e.what() << " See parameter '" << robot_hw_nh.resolveName("use_tool_communication") << "'.");
return false;
}
catch (ur_driver::UrException& e)
{
ROS_FATAL_STREAM(e.what());
return false;
}
if (!root_nh.getParam("hardware_interface/joints", joint_names_))
{

View File

@@ -29,7 +29,6 @@
#include <csignal>
#include <ur_rtde_driver/ros/hardware_interface.h>
#include <ur_rtde_driver/exceptions.h>
std::unique_ptr<ur_driver::HardwareInterface> g_hw_interface;
@@ -65,17 +64,9 @@ int main(int argc, char** argv)
g_hw_interface.reset(new ur_driver::HardwareInterface);
try
if (!g_hw_interface->init(nh, nh_priv))
{
if (!g_hw_interface->init(nh, nh_priv))
{
ROS_ERROR_STREAM("Could not correctly initialize robot. Exiting");
exit(1);
}
}
catch (ur_driver::UrException& e)
{
ROS_FATAL_STREAM("Could not correctly initialize robot: " << e.what());
ROS_ERROR_STREAM("Could not correctly initialize robot. Exiting");
exit(1);
}
ROS_INFO_STREAM("initialized hw interface");
@@ -152,7 +143,8 @@ int main(int argc, char** argv)
period.fromSec(std::chrono::duration_cast<std::chrono::duration<double>>(stopwatch_now - stopwatch_last).count());
stopwatch_last = stopwatch_now;
cm.update(timestamp, period, !g_hw_interface->isRobotProgramRunning());
// cm.update(timestamp, period, !g_hw_interface->isRobotProgramRunning());
cm.update(timestamp, period);
g_hw_interface->write(timestamp, period);
// if (!control_rate.sleep())