Skip to content

Commit

Permalink
Merge pull request #18 from ros2/code_style_uncrustify
Browse files Browse the repository at this point in the history
code style only
  • Loading branch information
dirk-thomas committed Apr 8, 2015
2 parents b4a2822 + 8054786 commit 0c0bb8a
Show file tree
Hide file tree
Showing 18 changed files with 411 additions and 504 deletions.
26 changes: 18 additions & 8 deletions rclcpp/include/rclcpp/callback_group.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,49 +28,59 @@ namespace rclcpp
{

// Forward declarations for friend statement in class CallbackGroup
namespace node {class Node;}
namespace executor {class Executor;}
namespace node
{
class Node;
} // namespace node
namespace executor
{
class Executor;
} // namespace executor

namespace callback_group
{

enum class CallbackGroupType {MutuallyExclusive, Reentrant};
enum class CallbackGroupType {
MutuallyExclusive,
Reentrant
};

class CallbackGroup
{
friend class rclcpp::node::Node;
friend class rclcpp::executor::Executor;

public:
RCLCPP_MAKE_SHARED_DEFINITIONS(CallbackGroup);

CallbackGroup(CallbackGroupType group_type)
: type_(group_type), can_be_taken_from_(true)
: type_(group_type), can_be_taken_from_(true)
{}

private:
RCLCPP_DISABLE_COPY(CallbackGroup);

void
add_subscription(
const subscription::SubscriptionBase::SharedPtr &subscription_ptr)
const subscription::SubscriptionBase::SharedPtr & subscription_ptr)
{
subscription_ptrs_.push_back(subscription_ptr);
}

void
add_timer(const timer::TimerBase::SharedPtr &timer_ptr)
add_timer(const timer::TimerBase::SharedPtr & timer_ptr)
{
timer_ptrs_.push_back(timer_ptr);
}

void
add_service(const service::ServiceBase::SharedPtr &service_ptr)
add_service(const service::ServiceBase::SharedPtr & service_ptr)
{
service_ptrs_.push_back(service_ptr);
}

void
add_client(const client::ClientBase::SharedPtr &client_ptr)
add_client(const client::ClientBase::SharedPtr & client_ptr)
{
client_ptrs_.push_back(client_ptr);
}
Expand Down
31 changes: 16 additions & 15 deletions rclcpp/include/rclcpp/client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,26 +29,28 @@ namespace rclcpp
{

// Forward declaration for friend statement
namespace executor {class Executor;}
namespace executor
{
class Executor;
} // namespace executor

namespace client
{

class ClientBase
{
friend class rclcpp::executor::Executor;

public:
RCLCPP_MAKE_SHARED_DEFINITIONS(ClientBase);

ClientBase(rmw_client_t * client_handle,
const std::string &service_name)
ClientBase(rmw_client_t * client_handle, const std::string & service_name)
: client_handle_(client_handle), service_name_(service_name)
{}

~ClientBase()
{
if (client_handle_ != nullptr)
{
if (client_handle_ != nullptr) {
rmw_destroy_client(client_handle_);
client_handle_ = nullptr;
}
Expand All @@ -66,8 +68,8 @@ class ClientBase

virtual std::shared_ptr<void> create_response() = 0;
virtual std::shared_ptr<void> create_request_header() = 0;
virtual void handle_response(std::shared_ptr<void> &request_header,
std::shared_ptr<void> &response) = 0;
virtual void handle_response(
std::shared_ptr<void> & request_header, std::shared_ptr<void> & response) = 0;

private:
RCLCPP_DISABLE_COPY(ClientBase);
Expand All @@ -85,12 +87,11 @@ class Client : public ClientBase
typedef std::shared_ptr<Promise> SharedPromise;
typedef std::shared_future<typename ServiceT::Response::Ptr> SharedFuture;

typedef std::function<void(SharedFuture)> CallbackType;
typedef std::function<void (SharedFuture)> CallbackType;

RCLCPP_MAKE_SHARED_DEFINITIONS(Client);

Client(rmw_client_t * client_handle,
const std::string& service_name)
Client(rmw_client_t * client_handle, const std::string & service_name)
: ClientBase(client_handle, service_name)
{}

Expand All @@ -106,7 +107,7 @@ class Client : public ClientBase
return std::shared_ptr<void>(new rmw_request_id_t);
}

void handle_response(std::shared_ptr<void> &request_header, std::shared_ptr<void> &response)
void handle_response(std::shared_ptr<void> & request_header, std::shared_ptr<void> & response)
{
auto typed_request_header = std::static_pointer_cast<rmw_request_id_t>(request_header);
auto typed_response = std::static_pointer_cast<typename ServiceT::Response>(response);
Expand All @@ -121,13 +122,13 @@ class Client : public ClientBase
}

SharedFuture async_send_request(
typename ServiceT::Request::Ptr &request)
typename ServiceT::Request::Ptr & request)
{
return async_send_request(request, [] (SharedFuture f) { });
return async_send_request(request, [](SharedFuture f) {});
}

SharedFuture async_send_request(
typename ServiceT::Request::Ptr &request,
typename ServiceT::Request::Ptr & request,
CallbackType cb)
{
int64_t sequence_number;
Expand All @@ -143,7 +144,7 @@ class Client : public ClientBase
private:
RCLCPP_DISABLE_COPY(Client);

std::map<int64_t, std::tuple<SharedPromise, CallbackType, SharedFuture> > pending_requests_;
std::map<int64_t, std::tuple<SharedPromise, CallbackType, SharedFuture>> pending_requests_;
};

} /* namespace client */
Expand Down
6 changes: 3 additions & 3 deletions rclcpp/include/rclcpp/contexts/default_context.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,8 +33,8 @@ class DefaultContext : public rclcpp::context::Context

};

}
}
}
} // namespace default_context
} // namespace contexts
} // namespace rclcpp

#endif /* RCLCPP_RCLCPP_CONTEXTS_DEFAULT_CONTEXT_HPP_ */
Loading

0 comments on commit 0c0bb8a

Please sign in to comment.