Skip to content

Commit

Permalink
deprecate redundant namespaces, move classes to own files, rename som…
Browse files Browse the repository at this point in the history
…e classes

Signed-off-by: William Woodall <william@osrfoundation.org>
  • Loading branch information
wjwwood committed Apr 22, 2020
1 parent c9319da commit db43729
Show file tree
Hide file tree
Showing 70 changed files with 690 additions and 552 deletions.
3 changes: 2 additions & 1 deletion rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ set(${PROJECT_NAME}_SRCS
src/rclcpp/detail/utilities.cpp
src/rclcpp/duration.cpp
src/rclcpp/event.cpp
src/rclcpp/exceptions.cpp
src/rclcpp/exceptions/exceptions.cpp
src/rclcpp/executable_list.cpp
src/rclcpp/executor.cpp
src/rclcpp/executors.cpp
Expand All @@ -50,6 +50,7 @@ set(${PROJECT_NAME}_SRCS
src/rclcpp/executors/single_threaded_executor.cpp
src/rclcpp/executors/static_executor_entities_collector.cpp
src/rclcpp/executors/static_single_threaded_executor.cpp
src/rclcpp/future_return_code.cpp
src/rclcpp/graph_listener.cpp
src/rclcpp/guard_condition.cpp
src/rclcpp/init_options.cpp
Expand Down
9 changes: 6 additions & 3 deletions rclcpp/include/rclcpp/any_executable.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,6 @@

namespace rclcpp
{
namespace executor
{

struct AnyExecutable
{
Expand All @@ -47,10 +45,15 @@ struct AnyExecutable
rclcpp::ClientBase::SharedPtr client;
rclcpp::Waitable::SharedPtr waitable;
// These are used to keep the scope on the containing items
rclcpp::callback_group::CallbackGroup::SharedPtr callback_group;
rclcpp::CallbackGroup::SharedPtr callback_group;
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base;
};

namespace executor
{

using AnyExecutable [[deprecated("use rclcpp::AnyExecutable instead")]] = AnyExecutable;

} // namespace executor
} // namespace rclcpp

Expand Down
9 changes: 6 additions & 3 deletions rclcpp/include/rclcpp/callback_group.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,9 +40,6 @@ class NodeTopics;
class NodeWaitables;
} // namespace node_interfaces

namespace callback_group
{

enum class CallbackGroupType
{
MutuallyExclusive,
Expand Down Expand Up @@ -162,6 +159,12 @@ class CallbackGroup
}
};

namespace callback_group
{

using CallbackGroupType [[deprecated("use rclcpp::CallbackGroupType instead")]] = CallbackGroupType;
using CallbackGroup [[deprecated("use rclcpp::CallbackGroup instead")]] = CallbackGroup;

} // namespace callback_group
} // namespace rclcpp

Expand Down
17 changes: 15 additions & 2 deletions rclcpp/include/rclcpp/contexts/default_context.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,6 @@ namespace rclcpp
{
namespace contexts
{
namespace default_context
{

class DefaultContext : public rclcpp::Context
{
Expand All @@ -38,6 +36,21 @@ RCLCPP_PUBLIC
DefaultContext::SharedPtr
get_global_default_context();

namespace default_context
{

using DefaultContext
[[deprecated("use rclcpp::contexts::DefaultContext instead")]] = DefaultContext;

[[deprecated("use rclcpp::contexts::get_global_default_context() instead")]]
RCLCPP_PUBLIC
inline
DefaultContext::SharedPtr
get_global_default_context()
{
return rclcpp::contexts::get_global_default_context();
}

} // namespace default_context
} // namespace contexts
} // namespace rclcpp
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/create_client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ create_client(
std::shared_ptr<node_interfaces::NodeServicesInterface> node_services,
const std::string & service_name,
const rmw_qos_profile_t & qos_profile,
rclcpp::callback_group::CallbackGroup::SharedPtr group)
rclcpp::CallbackGroup::SharedPtr group)
{
rcl_client_options_t options = rcl_client_get_default_options();
options.qos = qos_profile;
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/create_service.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ create_service(
const std::string & service_name,
CallbackT && callback,
const rmw_qos_profile_t & qos_profile,
rclcpp::callback_group::CallbackGroup::SharedPtr group)
rclcpp::CallbackGroup::SharedPtr group)
{
rclcpp::AnyServiceCallback<ServiceT> any_service_callback;
any_service_callback.set(std::forward<CallbackT>(callback));
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/include/rclcpp/create_timer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ create_timer(
rclcpp::Clock::SharedPtr clock,
rclcpp::Duration period,
CallbackT && callback,
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr)
rclcpp::CallbackGroup::SharedPtr group = nullptr)
{
auto timer = rclcpp::GenericTimer<CallbackT>::make_shared(
clock,
Expand All @@ -57,7 +57,7 @@ create_timer(
rclcpp::Clock::SharedPtr clock,
rclcpp::Duration period,
CallbackT && callback,
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr)
rclcpp::CallbackGroup::SharedPtr group = nullptr)
{
return create_timer(
rclcpp::node_interfaces::get_node_base_interface(node),
Expand Down
261 changes: 1 addition & 260 deletions rclcpp/include/rclcpp/exceptions.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,265 +15,6 @@
#ifndef RCLCPP__EXCEPTIONS_HPP_
#define RCLCPP__EXCEPTIONS_HPP_

#include <stdexcept>
#include <string>
#include <vector>

#include "rcl/error_handling.h"
#include "rcl/types.h"
#include "rclcpp/visibility_control.hpp"

#include "rcpputils/join.hpp"

namespace rclcpp
{
namespace exceptions
{

/// Thrown when a method is trying to use a node, but it is invalid.
class InvalidNodeError : public std::runtime_error
{
public:
InvalidNodeError()
: std::runtime_error("node is invalid") {}
};

/// Thrown when a any kind of name (node, namespace, topic, etc.) is invalid.
class NameValidationError : public std::invalid_argument
{
public:
NameValidationError(
const char * name_type_,
const char * name_,
const char * error_msg_,
size_t invalid_index_)
: std::invalid_argument(format_error(name_type_, name_, error_msg_, invalid_index_)),
name_type(name_type_), name(name_), error_msg(error_msg_), invalid_index(invalid_index_)
{}

static std::string
format_error(
const char * name_type,
const char * name,
const char * error_msg,
size_t invalid_index);

const std::string name_type;
const std::string name;
const std::string error_msg;
const size_t invalid_index;
};

/// Thrown when a node name is invalid.
class InvalidNodeNameError : public NameValidationError
{
public:
InvalidNodeNameError(const char * node_name, const char * error_msg, size_t invalid_index)
: NameValidationError("node name", node_name, error_msg, invalid_index)
{}
};

/// Thrown when a node namespace is invalid.
class InvalidNamespaceError : public NameValidationError
{
public:
InvalidNamespaceError(const char * namespace_, const char * error_msg, size_t invalid_index)
: NameValidationError("namespace", namespace_, error_msg, invalid_index)
{}
};

/// Thrown when a topic name is invalid.
class InvalidTopicNameError : public NameValidationError
{
public:
InvalidTopicNameError(const char * namespace_, const char * error_msg, size_t invalid_index)
: NameValidationError("topic name", namespace_, error_msg, invalid_index)
{}
};

/// Thrown when a service name is invalid.
class InvalidServiceNameError : public NameValidationError
{
public:
InvalidServiceNameError(const char * namespace_, const char * error_msg, size_t invalid_index)
: NameValidationError("service name", namespace_, error_msg, invalid_index)
{}
};

/// Throw a C++ std::exception which was created based on an rcl error.
/**
* Passing nullptr for reset_error is safe and will avoid calling any function
* to reset the error.
*
* \param ret the return code for the current error state
* \param prefix string to prefix to the error if applicable (not all errors have custom messages)
* \param error_state error state to create exception from, if nullptr rcl_get_error_state is used
* \param reset_error function to be called before throwing which whill clear the error state
* \throws std::invalid_argument if ret is RCL_RET_OK
* \throws std::runtime_error if the rcl_get_error_state returns 0
* \throws RCLErrorBase some child class exception based on ret
*/
/* *INDENT-OFF* */ // Uncrustify cannot yet understand [[noreturn]] properly
RCLCPP_PUBLIC
void
throw_from_rcl_error [[noreturn]] (
rcl_ret_t ret,
const std::string & prefix = "",
const rcl_error_state_t * error_state = nullptr,
void (* reset_error)() = rcl_reset_error);
/* *INDENT-ON* */

class RCLErrorBase
{
public:
RCLCPP_PUBLIC
RCLErrorBase(rcl_ret_t ret, const rcl_error_state_t * error_state);
virtual ~RCLErrorBase() {}

rcl_ret_t ret;
std::string message;
std::string file;
size_t line;
std::string formatted_message;
};

/// Created when the return code does not match one of the other specialized exceptions.
class RCLError : public RCLErrorBase, public std::runtime_error
{
public:
RCLCPP_PUBLIC
RCLError(rcl_ret_t ret, const rcl_error_state_t * error_state, const std::string & prefix);
RCLCPP_PUBLIC
RCLError(const RCLErrorBase & base_exc, const std::string & prefix);
};

/// Created when the ret is RCL_RET_BAD_ALLOC.
class RCLBadAlloc : public RCLErrorBase, public std::bad_alloc
{
public:
RCLCPP_PUBLIC
RCLBadAlloc(rcl_ret_t ret, const rcl_error_state_t * error_state);
RCLCPP_PUBLIC
explicit RCLBadAlloc(const RCLErrorBase & base_exc);
};

/// Created when the ret is RCL_RET_INVALID_ARGUMENT.
class RCLInvalidArgument : public RCLErrorBase, public std::invalid_argument
{
public:
RCLCPP_PUBLIC
RCLInvalidArgument(
rcl_ret_t ret,
const rcl_error_state_t * error_state,
const std::string & prefix);
RCLCPP_PUBLIC
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.
class InvalidEventError : public std::runtime_error
{
public:
InvalidEventError()
: std::runtime_error("event is invalid") {}
};

/// Thrown when an unregistered rclcpp::Event is encountered where a registered one was expected.
class EventNotRegisteredError : public std::runtime_error
{
public:
EventNotRegisteredError()
: 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;
};

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

/// Thrown if requested parameter type is invalid.
/**
* Essentially the same as rclcpp::ParameterTypeException, but with parameter
* name in the error message.
*/
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
{
// Inherit constructors from runtime_error.
using std::runtime_error::runtime_error;
};

/// Thrown if parameter is not declared, e.g. either set or get was called without first declaring.
class ParameterNotDeclaredException : public std::runtime_error
{
// Inherit constructors from runtime_error.
using std::runtime_error::runtime_error;
};

/// Thrown if parameter is immutable and therefore cannot be undeclared.
class ParameterImmutableException : public std::runtime_error
{
// Inherit constructors from runtime_error.
using std::runtime_error::runtime_error;
};

/// Thrown if parameter is modified while in a set callback.
class ParameterModifiedInCallbackException : public std::runtime_error
{
// Inherit constructors from runtime_error.
using std::runtime_error::runtime_error;
};

} // namespace exceptions
} // namespace rclcpp
#include "rclcpp/exceptions/exceptions.hpp"

#endif // RCLCPP__EXCEPTIONS_HPP_
Loading

0 comments on commit db43729

Please sign in to comment.