Skip to content

Commit

Permalink
Catch XmlRpc::XmlRpcExceptions when constructing QoS from parameters
Browse files Browse the repository at this point in the history
Signed-off-by: Loy van Beek <loy.vanbeek@mojin-robotics.de>
  • Loading branch information
LoyVanBeek committed Oct 18, 2021
1 parent 90afae3 commit fd9d12f
Show file tree
Hide file tree
Showing 3 changed files with 31 additions and 0 deletions.
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@ find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rmw_implementation_cmake REQUIRED)
find_package(std_msgs REQUIRED)
find_package(xmlrpcpp REQUIRED)

# find ROS 1 packages
set(cmake_extras_files cmake/find_ros1_package.cmake cmake/find_ros1_interface_packages.cmake)
Expand Down
1 change: 1 addition & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
<build_depend>rcutils</build_depend>
<build_depend>rmw_implementation_cmake</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>xmlrpcpp</build_depend>

<buildtool_export_depend>pkg-config</buildtool_export_depend>

Expand Down
29 changes: 29 additions & 0 deletions src/parameter_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@

// include ROS 2
#include "rclcpp/rclcpp.hpp"
#include <xmlrpcpp/XmlRpcException.h>

#include "ros1_bridge/bridge.hpp"

Expand Down Expand Up @@ -131,6 +132,13 @@ rclcpp::QoS qos_from_params(XmlRpc::XmlRpcValue qos_params)
"failed to create parametrize deadline: '%s'\n",
e.what());
}
catch (XmlRpc::XmlRpcException &e)
{
fprintf(
stderr,
"failed to create parametrize deadline: '%s'\n",
e.getMessage().c_str());
}
}

if (qos_params.hasMember("lifespan"))
Expand All @@ -150,6 +158,13 @@ rclcpp::QoS qos_from_params(XmlRpc::XmlRpcValue qos_params)
"failed to create parametrize lifespan: '%s'\n",
e.what());
}
catch (XmlRpc::XmlRpcException &e)
{
fprintf(
stderr,
"failed to create parametrize lifespan: '%s'\n",
e.getMessage().c_str());
}
}

if (qos_params.hasMember("liveliness"))
Expand All @@ -167,6 +182,13 @@ rclcpp::QoS qos_from_params(XmlRpc::XmlRpcValue qos_params)
"failed to create parametrize liveliness: '%s'\n",
e.what());
}
catch (XmlRpc::XmlRpcException &e)
{
fprintf(
stderr,
"failed to create parametrize liveliness: '%s'\n",
e.getMessage().c_str());
}
}

if (qos_params.hasMember("liveliness_lease_duration"))
Expand All @@ -186,6 +208,13 @@ rclcpp::QoS qos_from_params(XmlRpc::XmlRpcValue qos_params)
"failed to create parametrize liveliness_lease_duration: '%s'\n",
e.what());
}
catch (XmlRpc::XmlRpcException &e)
{
fprintf(
stderr,
"failed to create parametrize liveliness_lease_duration: '%s'\n",
e.getMessage().c_str());
}
}
}
else
Expand Down

0 comments on commit fd9d12f

Please sign in to comment.