Skip to content

Commit

Permalink
Move exceptions to exceptions.hpp
Browse files Browse the repository at this point in the history
  • Loading branch information
sloretz committed Jun 1, 2018
1 parent 94807c6 commit b415df7
Show file tree
Hide file tree
Showing 4 changed files with 31 additions and 52 deletions.
15 changes: 15 additions & 0 deletions rclcpp/include/rclcpp/exceptions.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -181,6 +181,21 @@ class EventNotRegisteredError : public std::runtime_error
: std::runtime_error("event already registered") {}
};

/// Thrown if passed parameters are inconsistent or invalid
class InvalidParametersException : public std::runtime_error
{
public:
// Inherit constructors from runtime_error;
using std::runtime_error::runtime_error;
};

/// Throwing if passed parameter value is invalid.
class InvalidParameterValueException : public std::runtime_error
{
// Inherit constructors from runtime_error;
using std::runtime_error::runtime_error;
};

} // namespace exceptions
} // namespace rclcpp

Expand Down
32 changes: 3 additions & 29 deletions rclcpp/include/rclcpp/parameter_map.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,46 +15,20 @@
#ifndef RCLCPP__PARAMETER_MAP_HPP_
#define RCLCPP__PARAMETER_MAP_HPP_

#include <exception>
#include <rcl_yaml_param_parser/types.h>

#include <string>
#include <unordered_map>
#include <vector>

#include "rclcpp/exceptions.hpp"
#include "rclcpp/parameter.hpp"
#include "rclcpp/parameter_value.hpp"
#include "rclcpp/visibility_control.hpp"
#include "rcl_yaml_param_parser/types.h"

namespace rclcpp
{

/// Indicate `rcl_params_t` is or invalid.
class InvalidParametersException : public std::exception
{
public:
/// Instantiate exception with a message.
/// \param[in] message A message to be included in the output of what().
RCLCPP_PUBLIC
explicit InvalidParametersException(std::string message);

RCLCPP_PUBLIC
~InvalidParametersException();

RCLCPP_PUBLIC
const char *
what() const noexcept override;

private:
std::string msg_;
};

/// Indicate `rcl_variant_t` is or invalid.
class InvalidParameterValueException : public InvalidParametersException
{
// inherit constructor
using InvalidParametersException::InvalidParametersException;
};

/// A map of fully qualified node names to a list of parameters
using ParameterMap = std::unordered_map<std::string, std::vector<Parameter>>;

Expand Down
19 changes: 2 additions & 17 deletions rclcpp/src/rclcpp/parameter_map.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,26 +17,11 @@

#include "rclcpp/parameter_map.hpp"

using rclcpp::InvalidParametersException;
using rclcpp::InvalidParameterValueException;
using rclcpp::exceptions::InvalidParametersException;
using rclcpp::exceptions::InvalidParameterValueException;
using rclcpp::ParameterMap;
using rclcpp::ParameterValue;

InvalidParametersException::InvalidParametersException(std::string message)
: msg_(message)
{
}

InvalidParametersException::~InvalidParametersException()
{
}

const char *
InvalidParametersException::what() const noexcept
{
return msg_.c_str();
}

ParameterMap
rclcpp::parameter_map_from(const rcl_params_t * const c_params)
{
Expand Down
17 changes: 11 additions & 6 deletions rclcpp/test/test_parameter_map.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,15 +84,16 @@ make_node_params(rcl_params_t * c_params, size_t node_idx, std::vector<std::stri

TEST(Test_parameter_map_from, null_c_parameter)
{
EXPECT_THROW(rclcpp::parameter_map_from(NULL), rclcpp::InvalidParametersException);
EXPECT_THROW(rclcpp::parameter_map_from(NULL), rclcpp::exceptions::InvalidParametersException);
}

TEST(Test_parameter_map_from, null_node_names)
{
rcl_params_t * c_params = make_params({});
c_params->num_nodes = 1;

EXPECT_THROW(rclcpp::parameter_map_from(c_params), rclcpp::InvalidParametersException);
EXPECT_THROW(
rclcpp::parameter_map_from(c_params), rclcpp::exceptions::InvalidParametersException);

c_params->num_nodes = 0;
rcl_yaml_node_struct_fini(c_params);
Expand All @@ -105,7 +106,8 @@ TEST(Test_parameter_map_from, null_node_params)
auto allocated_params = c_params->params;
c_params->params = NULL;

EXPECT_THROW(rclcpp::parameter_map_from(c_params), rclcpp::InvalidParametersException);
EXPECT_THROW(
rclcpp::parameter_map_from(c_params), rclcpp::exceptions::InvalidParametersException);

c_params->params = allocated_params;
rcl_yaml_node_struct_fini(c_params);
Expand All @@ -117,7 +119,8 @@ TEST(Test_parameter_map_from, null_node_name_in_node_names)
auto allocated_name = c_params->node_names[0];
c_params->node_names[0] = NULL;

EXPECT_THROW(rclcpp::parameter_map_from(c_params), rclcpp::InvalidParametersException);
EXPECT_THROW(
rclcpp::parameter_map_from(c_params), rclcpp::exceptions::InvalidParametersException);

c_params->node_names[0] = allocated_name;
rcl_yaml_node_struct_fini(c_params);
Expand All @@ -128,7 +131,8 @@ TEST(Test_parameter_map_from, null_node_param_value)
rcl_params_t * c_params = make_params({"foo"});
make_node_params(c_params, 0, {"bar"});

EXPECT_THROW(rclcpp::parameter_map_from(c_params), rclcpp::InvalidParameterValueException);
EXPECT_THROW(
rclcpp::parameter_map_from(c_params), rclcpp::exceptions::InvalidParameterValueException);

rcl_yaml_node_struct_fini(c_params);
}
Expand All @@ -140,7 +144,8 @@ TEST(Test_parameter_map_from, null_node_param_name)
auto allocated_name = c_params->params[0].parameter_names[0];
c_params->params[0].parameter_names[0] = NULL;

EXPECT_THROW(rclcpp::parameter_map_from(c_params), rclcpp::InvalidParametersException);
EXPECT_THROW(
rclcpp::parameter_map_from(c_params), rclcpp::exceptions::InvalidParametersException);

c_params->params[0].parameter_names[0] = allocated_name;
rcl_yaml_node_struct_fini(c_params);
Expand Down

0 comments on commit b415df7

Please sign in to comment.