Skip to content

Commit

Permalink
Uncrustify 0.67 (#510)
Browse files Browse the repository at this point in the history
* fix indentation to comply with uncrusity 0.67

* fix spacing before opening brackets

* space between reference and variable name in signature

* questionable space between pointer marker and variable name
  • Loading branch information
mikaelarguedas committed Jul 11, 2018
1 parent d36910d commit ae6f8e3
Show file tree
Hide file tree
Showing 13 changed files with 25 additions and 25 deletions.
4 changes: 2 additions & 2 deletions rclcpp/include/rclcpp/any_service_callback.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,12 +32,12 @@ class AnyServiceCallback
{
private:
using SharedPtrCallback = std::function<
void(
void (
const std::shared_ptr<typename ServiceT::Request>,
std::shared_ptr<typename ServiceT::Response>
)>;
using SharedPtrWithRequestHeaderCallback = std::function<
void(
void (
const std::shared_ptr<rmw_request_id_t>,
const std::shared_ptr<typename ServiceT::Request>,
std::shared_ptr<typename ServiceT::Response>
Expand Down
12 changes: 6 additions & 6 deletions rclcpp/include/rclcpp/any_subscription_callback.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,15 +38,15 @@ class AnySubscriptionCallback
using MessageDeleter = allocator::Deleter<MessageAlloc, MessageT>;
using MessageUniquePtr = std::unique_ptr<MessageT, MessageDeleter>;

using SharedPtrCallback = std::function<void(const std::shared_ptr<MessageT>)>;
using SharedPtrCallback = std::function<void (const std::shared_ptr<MessageT>)>;
using SharedPtrWithInfoCallback =
std::function<void(const std::shared_ptr<MessageT>, const rmw_message_info_t &)>;
using ConstSharedPtrCallback = std::function<void(const std::shared_ptr<const MessageT>)>;
std::function<void (const std::shared_ptr<MessageT>, const rmw_message_info_t &)>;
using ConstSharedPtrCallback = std::function<void (const std::shared_ptr<const MessageT>)>;
using ConstSharedPtrWithInfoCallback =
std::function<void(const std::shared_ptr<const MessageT>, const rmw_message_info_t &)>;
using UniquePtrCallback = std::function<void(MessageUniquePtr)>;
std::function<void (const std::shared_ptr<const MessageT>, const rmw_message_info_t &)>;
using UniquePtrCallback = std::function<void (MessageUniquePtr)>;
using UniquePtrWithInfoCallback =
std::function<void(MessageUniquePtr, const rmw_message_info_t &)>;
std::function<void (MessageUniquePtr, const rmw_message_info_t &)>;

SharedPtrCallback shared_ptr_callback_;
SharedPtrWithInfoCallback shared_ptr_with_info_callback_;
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/include/rclcpp/client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -130,8 +130,8 @@ class Client : public ClientBase
using SharedFuture = std::shared_future<SharedResponse>;
using SharedFutureWithRequest = std::shared_future<std::pair<SharedRequest, SharedResponse>>;

using CallbackType = std::function<void(SharedFuture)>;
using CallbackWithRequestType = std::function<void(SharedFutureWithRequest)>;
using CallbackType = std::function<void (SharedFuture)>;
using CallbackWithRequestType = std::function<void (SharedFutureWithRequest)>;

RCLCPP_SMART_PTR_DEFINITIONS(Client)

Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/exceptions.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,7 @@ throw_from_rcl_error(
rcl_ret_t ret,
const std::string & prefix = "",
const rcl_error_state_t * error_state = nullptr,
void (*reset_error)() = rcl_reset_error);
void (* reset_error)() = rcl_reset_error);

class RCLErrorBase
{
Expand Down
6 changes: 3 additions & 3 deletions rclcpp/include/rclcpp/function_traits.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -130,20 +130,20 @@ struct function_traits<FunctionT &&>: function_traits<FunctionT>
*/
template<std::size_t Arity, typename FunctorT>
struct arity_comparator : std::integral_constant<
bool, (Arity == function_traits<FunctorT>::arity)>{};
bool, (Arity == function_traits<FunctorT>::arity)> {};

template<typename FunctorT, typename ... Args>
struct check_arguments : std::is_same<
typename function_traits<FunctorT>::arguments,
std::tuple<Args ...>
>
>
{};

template<typename FunctorAT, typename FunctorBT>
struct same_arguments : std::is_same<
typename function_traits<FunctorAT>::arguments,
typename function_traits<FunctorBT>::arguments
>
>
{};

} // namespace function_traits
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/intra_process_manager.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -326,7 +326,7 @@ class IntraProcessManager
message_sequence_number,
requesting_subscriptions_intra_process_id,
target_subs_size
);
);
typename TypedMRB::SharedPtr typed_buffer = std::static_pointer_cast<TypedMRB>(buffer);
if (!typed_buffer) {
return;
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/include/rclcpp/service.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -89,12 +89,12 @@ class Service : public ServiceBase
{
public:
using CallbackType = std::function<
void(
void (
const std::shared_ptr<typename ServiceT::Request>,
std::shared_ptr<typename ServiceT::Response>)>;

using CallbackWithHeaderType = std::function<
void(
void (
const std::shared_ptr<rmw_request_id_t>,
const std::shared_ptr<typename ServiceT::Request>,
std::shared_ptr<typename ServiceT::Response>)>;
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/include/rclcpp/subscription.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -266,8 +266,8 @@ class Subscription : public SubscriptionBase
}

using GetMessageCallbackType =
std::function<void(uint64_t, uint64_t, uint64_t, MessageUniquePtr &)>;
using MatchesAnyPublishersCallbackType = std::function<bool(const rmw_gid_t *)>;
std::function<void (uint64_t, uint64_t, uint64_t, MessageUniquePtr &)>;
using MatchesAnyPublishersCallbackType = std::function<bool (const rmw_gid_t *)>;

/// Implemenation detail.
void setup_intra_process(
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/subscription_factory.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ struct SubscriptionFactory

// Function that takes a MessageT from the intra process manager
using SetupIntraProcessFunction = std::function<
void(
void (
rclcpp::intra_process_manager::IntraProcessManager::SharedPtr ipm,
rclcpp::SubscriptionBase::SharedPtr subscription,
const rcl_subscription_options_t & subscription_options)>;
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/include/rclcpp/timer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -89,8 +89,8 @@ class TimerBase
};


using VoidCallbackType = std::function<void()>;
using TimerCallbackType = std::function<void(TimerBase &)>;
using VoidCallbackType = std::function<void ()>;
using TimerCallbackType = std::function<void (TimerBase &)>;

/// Generic timer templated on the clock type. Periodically executes a user-specified callback.
template<
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/exceptions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ throw_from_rcl_error(
rcl_ret_t ret,
const std::string & prefix,
const rcl_error_state_t * error_state,
void (*reset_error)())
void (* reset_error)())
{
if (RCL_RET_OK == ret) {
throw std::invalid_argument("ret is RCL_RET_OK");
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -628,7 +628,7 @@ rclcpp::executor::operator<<(std::ostream & os, const FutureReturnCode & future_
}

std::string
rclcpp::executor::to_string(const FutureReturnCode &future_return_code)
rclcpp::executor::to_string(const FutureReturnCode & future_return_code)
{
using enum_type = std::underlying_type<FutureReturnCode>::type;
std::string prefix = "Unknown enum value (";
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/time_source.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@ void TimeSource::attachNode(
node_topics_,
node_graph_,
node_services_
);
);
parameter_subscription_ =
parameter_client_->on_parameter_event(std::bind(&TimeSource::on_parameter_event,
this, std::placeholders::_1));
Expand Down

0 comments on commit ae6f8e3

Please sign in to comment.