Skip to content

Commit

Permalink
Add InvalidParameterTypeException
Browse files Browse the repository at this point in the history
Used to wrap the ParameterTypeException coming from ParameterValue::get() for improving the error message.

Signed-off-by: Jacob Perron <jacob@openrobotics.org>
  • Loading branch information
jacobperron committed Mar 18, 2020
1 parent 96ebf59 commit b05c6e7
Show file tree
Hide file tree
Showing 4 changed files with 33 additions and 9 deletions.
15 changes: 15 additions & 0 deletions rclcpp/include/rclcpp/exceptions.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -226,6 +226,21 @@ class InvalidParameterValueException : public std::runtime_error
using std::runtime_error::runtime_error;
};

/// Thrown if requested parameter type is invalid.
class InvalidParameterTypeException : public std::runtime_error
{
public:
/// Construct an instance.
/**
* \param[in] name the name of the parameter.
* \param[in] message custom exception message.
*/
RCLCPP_PUBLIC
InvalidParameterTypeException(const std::string & name, const std::string message)
: std::runtime_error("parameter '" + name + "' has invalid type: " + message)
{}
};

/// Thrown if parameter is already declared.
class ParameterAlreadyDeclaredException : public std::runtime_error
{
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -301,7 +301,7 @@ class Node : public std::enable_shared_from_this<Node>
*
* If the type of the default value, and therefore also the type of return
* value, differs from the initial value provided in the node options, then
* a rclcpp::ParameterTypeException may be thrown.
* a rclcpp::exceptions::InvalidParameterTypeException may be thrown.
* To avoid this, use the declare_parameter() method which returns an
* rclcpp::ParameterValue instead.
*
Expand Down
16 changes: 10 additions & 6 deletions rclcpp/include/rclcpp/node_impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -158,12 +158,16 @@ Node::declare_parameter(
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
bool ignore_override)
{
return this->declare_parameter(
name,
rclcpp::ParameterValue(default_value),
parameter_descriptor,
ignore_override
).get<ParameterT>();
try {
return this->declare_parameter(
name,
rclcpp::ParameterValue(default_value),
parameter_descriptor,
ignore_override
).get<ParameterT>();
} catch (const ParameterTypeException & ex) {
throw exceptions::InvalidParameterTypeException(name, ex.what());
}
}

template<typename ParameterT>
Expand Down
9 changes: 7 additions & 2 deletions rclcpp/include/rclcpp/parameter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
#include <vector>

#include "rcl_interfaces/msg/parameter.hpp"
#include "rclcpp/exceptions.hpp"
#include "rclcpp/parameter_value.hpp"
#include "rclcpp/visibility_control.hpp"

Expand Down Expand Up @@ -221,8 +222,12 @@ template<typename T>
decltype(auto)
Parameter::get_value() const
{
// use the helper to specialize for the ParameterValue and Parameter cases.
return detail::get_value_helper<T>(this);
try {
// use the helper to specialize for the ParameterValue and Parameter cases.
return detail::get_value_helper<T>(this);
} catch (const ParameterTypeException & ex) {
throw exceptions::InvalidParameterTypeException(this->name_, ex.what());
}
}

} // namespace rclcpp
Expand Down

0 comments on commit b05c6e7

Please sign in to comment.