Fail on invalid and unknown ROS specific arguments (#842)
* Fail on invalid and unknown ROS specific arguments. Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com> * Revert changes to utilities.hpp in rclcpp Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com> * Fully revert change to utilities.hpp Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com>
This commit is contained in:
parent
1fff8cbac1
commit
458967bb56
6 changed files with 86 additions and 1 deletions
|
@ -7,6 +7,7 @@ find_package(builtin_interfaces REQUIRED)
|
||||||
find_package(rcl REQUIRED)
|
find_package(rcl REQUIRED)
|
||||||
find_package(rcl_interfaces REQUIRED)
|
find_package(rcl_interfaces REQUIRED)
|
||||||
find_package(rcl_yaml_param_parser REQUIRED)
|
find_package(rcl_yaml_param_parser REQUIRED)
|
||||||
|
find_package(rcpputils REQUIRED)
|
||||||
find_package(rmw REQUIRED)
|
find_package(rmw REQUIRED)
|
||||||
find_package(rmw_implementation REQUIRED)
|
find_package(rmw_implementation REQUIRED)
|
||||||
find_package(rosgraph_msgs REQUIRED)
|
find_package(rosgraph_msgs REQUIRED)
|
||||||
|
@ -106,6 +107,7 @@ add_library(${PROJECT_NAME}
|
||||||
ament_target_dependencies(${PROJECT_NAME}
|
ament_target_dependencies(${PROJECT_NAME}
|
||||||
"rcl"
|
"rcl"
|
||||||
"rcl_yaml_param_parser"
|
"rcl_yaml_param_parser"
|
||||||
|
"rcpputils"
|
||||||
"builtin_interfaces"
|
"builtin_interfaces"
|
||||||
"rosgraph_msgs"
|
"rosgraph_msgs"
|
||||||
"rosidl_typesupport_cpp"
|
"rosidl_typesupport_cpp"
|
||||||
|
@ -129,6 +131,7 @@ ament_export_libraries(${PROJECT_NAME})
|
||||||
|
|
||||||
ament_export_dependencies(ament_cmake)
|
ament_export_dependencies(ament_cmake)
|
||||||
ament_export_dependencies(rcl)
|
ament_export_dependencies(rcl)
|
||||||
|
ament_export_dependencies(rcpputils)
|
||||||
ament_export_dependencies(builtin_interfaces)
|
ament_export_dependencies(builtin_interfaces)
|
||||||
ament_export_dependencies(rosgraph_msgs)
|
ament_export_dependencies(rosgraph_msgs)
|
||||||
ament_export_dependencies(rosidl_typesupport_cpp)
|
ament_export_dependencies(rosidl_typesupport_cpp)
|
||||||
|
|
|
@ -17,11 +17,14 @@
|
||||||
|
|
||||||
#include <stdexcept>
|
#include <stdexcept>
|
||||||
#include <string>
|
#include <string>
|
||||||
|
#include <vector>
|
||||||
|
|
||||||
#include "rcl/error_handling.h"
|
#include "rcl/error_handling.h"
|
||||||
#include "rcl/types.h"
|
#include "rcl/types.h"
|
||||||
#include "rclcpp/visibility_control.hpp"
|
#include "rclcpp/visibility_control.hpp"
|
||||||
|
|
||||||
|
#include "rcpputils/join.hpp"
|
||||||
|
|
||||||
namespace rclcpp
|
namespace rclcpp
|
||||||
{
|
{
|
||||||
namespace exceptions
|
namespace exceptions
|
||||||
|
@ -167,6 +170,31 @@ public:
|
||||||
RCLInvalidArgument(const RCLErrorBase & base_exc, const std::string & prefix);
|
RCLInvalidArgument(const RCLErrorBase & base_exc, const std::string & prefix);
|
||||||
};
|
};
|
||||||
|
|
||||||
|
/// Created when the ret is RCL_RET_INVALID_ROS_ARGS.
|
||||||
|
class RCLInvalidROSArgsError : public RCLErrorBase, public std::runtime_error
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
RCLCPP_PUBLIC
|
||||||
|
RCLInvalidROSArgsError(
|
||||||
|
rcl_ret_t ret, const rcl_error_state_t * error_state, const std::string & prefix);
|
||||||
|
RCLCPP_PUBLIC
|
||||||
|
RCLInvalidROSArgsError(const RCLErrorBase & base_exc, const std::string & prefix);
|
||||||
|
};
|
||||||
|
|
||||||
|
/// Thrown when unparsed ROS specific arguments are found.
|
||||||
|
class UnknownROSArgsError : public std::runtime_error
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
explicit UnknownROSArgsError(std::vector<std::string> && unknown_ros_args_in)
|
||||||
|
: std::runtime_error(
|
||||||
|
"found unknown ROS arguments: '" + rcpputils::join(unknown_ros_args_in, "', '") + "'"),
|
||||||
|
unknown_ros_args(unknown_ros_args_in)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
const std::vector<std::string> unknown_ros_args;
|
||||||
|
};
|
||||||
|
|
||||||
/// Thrown when an invalid rclcpp::Event object or SharedPtr is encountered.
|
/// Thrown when an invalid rclcpp::Event object or SharedPtr is encountered.
|
||||||
class InvalidEventError : public std::runtime_error
|
class InvalidEventError : public std::runtime_error
|
||||||
{
|
{
|
||||||
|
|
|
@ -26,6 +26,7 @@
|
||||||
|
|
||||||
<depend>rcl</depend>
|
<depend>rcl</depend>
|
||||||
<depend>rcl_yaml_param_parser</depend>
|
<depend>rcl_yaml_param_parser</depend>
|
||||||
|
<depend>rcpputils</depend>
|
||||||
<depend>rmw_implementation</depend>
|
<depend>rmw_implementation</depend>
|
||||||
|
|
||||||
<exec_depend>ament_cmake</exec_depend>
|
<exec_depend>ament_cmake</exec_depend>
|
||||||
|
|
|
@ -17,6 +17,7 @@
|
||||||
#include <cstdio>
|
#include <cstdio>
|
||||||
#include <functional>
|
#include <functional>
|
||||||
#include <string>
|
#include <string>
|
||||||
|
#include <vector>
|
||||||
|
|
||||||
using namespace std::string_literals;
|
using namespace std::string_literals;
|
||||||
|
|
||||||
|
@ -68,6 +69,8 @@ from_rcl_error(
|
||||||
return std::make_exception_ptr(RCLBadAlloc(base_exc));
|
return std::make_exception_ptr(RCLBadAlloc(base_exc));
|
||||||
case RCL_RET_INVALID_ARGUMENT:
|
case RCL_RET_INVALID_ARGUMENT:
|
||||||
return std::make_exception_ptr(RCLInvalidArgument(base_exc, formatted_prefix));
|
return std::make_exception_ptr(RCLInvalidArgument(base_exc, formatted_prefix));
|
||||||
|
case RCL_RET_INVALID_ROS_ARGS:
|
||||||
|
return std::make_exception_ptr(RCLInvalidROSArgsError(base_exc, formatted_prefix));
|
||||||
default:
|
default:
|
||||||
return std::make_exception_ptr(RCLError(base_exc, formatted_prefix));
|
return std::make_exception_ptr(RCLError(base_exc, formatted_prefix));
|
||||||
}
|
}
|
||||||
|
@ -126,5 +129,18 @@ RCLInvalidArgument::RCLInvalidArgument(
|
||||||
: RCLErrorBase(base_exc), std::invalid_argument(prefix + base_exc.formatted_message)
|
: RCLErrorBase(base_exc), std::invalid_argument(prefix + base_exc.formatted_message)
|
||||||
{}
|
{}
|
||||||
|
|
||||||
|
RCLInvalidROSArgsError::RCLInvalidROSArgsError(
|
||||||
|
rcl_ret_t ret,
|
||||||
|
const rcl_error_state_t * error_state,
|
||||||
|
const std::string & prefix)
|
||||||
|
: RCLInvalidROSArgsError(RCLErrorBase(ret, error_state), prefix)
|
||||||
|
{}
|
||||||
|
|
||||||
|
RCLInvalidROSArgsError::RCLInvalidROSArgsError(
|
||||||
|
const RCLErrorBase & base_exc,
|
||||||
|
const std::string & prefix)
|
||||||
|
: RCLErrorBase(base_exc), std::runtime_error(prefix + base_exc.formatted_message)
|
||||||
|
{}
|
||||||
|
|
||||||
} // namespace exceptions
|
} // namespace exceptions
|
||||||
} // namespace rclcpp
|
} // namespace rclcpp
|
||||||
|
|
|
@ -18,6 +18,7 @@
|
||||||
#include <memory>
|
#include <memory>
|
||||||
#include <string>
|
#include <string>
|
||||||
#include <vector>
|
#include <vector>
|
||||||
|
#include <utility>
|
||||||
|
|
||||||
#include "rclcpp/exceptions.hpp"
|
#include "rclcpp/exceptions.hpp"
|
||||||
#include "rclcpp/logging.hpp"
|
#include "rclcpp/logging.hpp"
|
||||||
|
@ -105,12 +106,33 @@ NodeOptions::get_rcl_node_options() const
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
rmw_ret_t ret = rcl_parse_arguments(
|
rcl_ret_t ret = rcl_parse_arguments(
|
||||||
c_argc, c_argv.get(), this->allocator_, &(node_options_->arguments));
|
c_argc, c_argv.get(), this->allocator_, &(node_options_->arguments));
|
||||||
|
|
||||||
if (RCL_RET_OK != ret) {
|
if (RCL_RET_OK != ret) {
|
||||||
throw_from_rcl_error(ret, "failed to parse arguments");
|
throw_from_rcl_error(ret, "failed to parse arguments");
|
||||||
}
|
}
|
||||||
|
|
||||||
|
int unparsed_ros_args_count =
|
||||||
|
rcl_arguments_get_count_unparsed_ros(&(node_options_->arguments));
|
||||||
|
if (unparsed_ros_args_count > 0) {
|
||||||
|
int * unparsed_ros_args_indices = nullptr;
|
||||||
|
ret = rcl_arguments_get_unparsed_ros(
|
||||||
|
&(node_options_->arguments), this->allocator_, &unparsed_ros_args_indices);
|
||||||
|
if (RCL_RET_OK != ret) {
|
||||||
|
throw_from_rcl_error(ret, "failed to get unparsed ROS arguments");
|
||||||
|
}
|
||||||
|
try {
|
||||||
|
std::vector<std::string> unparsed_ros_args;
|
||||||
|
for (int i = 0; i < unparsed_ros_args_count; ++i) {
|
||||||
|
unparsed_ros_args.push_back(c_argv[unparsed_ros_args_indices[i]]);
|
||||||
|
}
|
||||||
|
throw exceptions::UnknownROSArgsError(std::move(unparsed_ros_args));
|
||||||
|
} catch (...) {
|
||||||
|
this->allocator_.deallocate(unparsed_ros_args_indices, this->allocator_.state);
|
||||||
|
throw;
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
return node_options_.get();
|
return node_options_.get();
|
||||||
|
|
|
@ -83,3 +83,18 @@ TEST(TestNodeOptions, ros_args_and_non_ros_args) {
|
||||||
EXPECT_EQ("non-ros-arg", args[output_indices[1]]);
|
EXPECT_EQ("non-ros-arg", args[output_indices[1]]);
|
||||||
allocator.deallocate(output_indices, allocator.state);
|
allocator.deallocate(output_indices, allocator.state);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
TEST(TestNodeOptions, bad_ros_args) {
|
||||||
|
rcl_allocator_t allocator = rcl_get_default_allocator();
|
||||||
|
auto options = rclcpp::NodeOptions(allocator)
|
||||||
|
.arguments({"--ros-args", "-r", "foo:="});
|
||||||
|
|
||||||
|
EXPECT_THROW(
|
||||||
|
options.get_rcl_node_options(),
|
||||||
|
rclcpp::exceptions::RCLInvalidROSArgsError);
|
||||||
|
|
||||||
|
options.arguments({"--ros-args", "-r", "foo:=bar", "not-a-ros-arg"});
|
||||||
|
EXPECT_THROW(
|
||||||
|
options.get_rcl_node_options(),
|
||||||
|
rclcpp::exceptions::UnknownROSArgsError);
|
||||||
|
}
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue