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

Introduce UrException as exception base class

This commit is contained in:
Felix Mauch
2019-06-11 10:25:50 +02:00
parent 48103aca49
commit c88022eefd
3 changed files with 57 additions and 3 deletions

View File

@@ -0,0 +1,44 @@
// 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-11
*
*/
//----------------------------------------------------------------------
#ifndef UR_RTDE_DRIVER_EXCEPTIONS_H_INCLUDED
#define UR_RTDE_DRIVER_EXCEPTIONS_H_INCLUDED
#include <stdexcept>
namespace ur_driver
{
/*!
* \brief Our base class for exceptions. Specialized exceptions should inherit from those.
*/
class UrException : virtual public std::runtime_error
{
public:
explicit UrException() : std::runtime_error("")
{
}
explicit UrException(const std::string& what_arg) : std::runtime_error(what_arg)
{
}
explicit UrException(const char* what_arg) : std::runtime_error(what_arg)
{
}
virtual ~UrException() = default;
private:
/* data */
};
} // namespace ur_driver
#endif // ifndef UR_RTDE_DRIVER_EXCEPTIONS_H_INCLUDED

View File

@@ -29,6 +29,7 @@
#include <csignal> #include <csignal>
#include <ur_rtde_driver/ros/hardware_interface.h> #include <ur_rtde_driver/ros/hardware_interface.h>
#include <ur_rtde_driver/exceptions.h>
std::unique_ptr<ur_driver::HardwareInterface> g_hw_interface; std::unique_ptr<ur_driver::HardwareInterface> g_hw_interface;
@@ -64,9 +65,17 @@ int main(int argc, char** argv)
g_hw_interface.reset(new ur_driver::HardwareInterface); g_hw_interface.reset(new ur_driver::HardwareInterface);
if (!g_hw_interface->init(nh, nh_priv)) try
{ {
ROS_ERROR_STREAM("Could not correctly initialize robot. Exiting"); 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());
exit(1); exit(1);
} }
ROS_INFO_STREAM("initialized hw interface"); ROS_INFO_STREAM("initialized hw interface");

View File

@@ -32,6 +32,7 @@
#include "ur_rtde_driver/ur/ur_driver.h" #include "ur_rtde_driver/ur/ur_driver.h"
#include "ur_rtde_driver/primary/package_header.h" #include "ur_rtde_driver/primary/package_header.h"
#include "ur_rtde_driver/exceptions.h"
#include <memory> #include <memory>
namespace ur_driver namespace ur_driver
@@ -51,7 +52,7 @@ ur_driver::UrDriver::UrDriver(const std::string& robot_ip, const std::string& sc
if (!rtde_client_->init()) if (!rtde_client_->init())
{ {
throw std::runtime_error("initialization went wrong"); // TODO: be less harsh throw UrException("Initialization of RTDE client went wrong.");
} }
rtde_frequency_ = rtde_client_->getMaxFrequency(); rtde_frequency_ = rtde_client_->getMaxFrequency();