Skip to content

Commit

Permalink
Replace usage of typedef with using
Browse files Browse the repository at this point in the history
  • Loading branch information
esteve committed Aug 14, 2015
1 parent 32160fe commit 59a399b
Show file tree
Hide file tree
Showing 8 changed files with 22 additions and 22 deletions.
8 changes: 4 additions & 4 deletions rclcpp/include/rclcpp/client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -93,11 +93,11 @@ template<typename ServiceT>
class Client : public ClientBase
{
public:
typedef std::promise<typename ServiceT::Response::SharedPtr> Promise;
typedef std::shared_ptr<Promise> SharedPromise;
typedef std::shared_future<typename ServiceT::Response::SharedPtr> SharedFuture;
using Promise = std::promise<typename ServiceT::Response::SharedPtr>;
using SharedPromise = std::shared_ptr<Promise>;
using SharedFuture = std::shared_future<typename ServiceT::Response::SharedPtr>;

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

RCLCPP_SMART_PTR_DEFINITIONS(Client);

Expand Down
6 changes: 3 additions & 3 deletions rclcpp/include/rclcpp/executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -861,11 +861,11 @@ class Executor
RCLCPP_DISABLE_COPY(Executor);

std::vector<std::weak_ptr<rclcpp::node::Node>> weak_nodes_;
typedef std::list<void *> SubscriberHandles;
using SubscriberHandles = std::list<void *>;
SubscriberHandles subscriber_handles_;
typedef std::list<void *> ServiceHandles;
using ServiceHandles = std::list<void *>;
ServiceHandles service_handles_;
typedef std::list<void *> ClientHandles;
using ClientHandles = std::list<void *>;
ClientHandles client_handles_;

};
Expand Down
6 changes: 3 additions & 3 deletions rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -151,9 +151,9 @@ class Node
rclcpp::timer::CallbackType callback,
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);

typedef rclcpp::callback_group::CallbackGroup CallbackGroup;
typedef std::weak_ptr<CallbackGroup> CallbackGroupWeakPtr;
typedef std::list<CallbackGroupWeakPtr> CallbackGroupWeakPtrList;
using CallbackGroup = rclcpp::callback_group::CallbackGroup;
using CallbackGroupWeakPtr = std::weak_ptr<CallbackGroup>;
using CallbackGroupWeakPtrList = std::list<CallbackGroupWeakPtr>;

/* Create and return a Client. */
template<typename ServiceT>
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/include/rclcpp/rate.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -112,8 +112,8 @@ class GenericRate : public RateBase

};

typedef GenericRate<std::chrono::system_clock> Rate;
typedef GenericRate<std::chrono::steady_clock> WallRate;
using Rate = GenericRate<std::chrono::system_clock>;
using WallRate = GenericRate<std::chrono::steady_clock>;

} // namespace rate
} // namespace rclcpp
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/rclcpp.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ using rclcpp::rate::WallRate;
using rclcpp::timer::GenericTimer;
using rclcpp::timer::TimerBase;
using rclcpp::timer::WallTimer;
typedef rclcpp::context::Context::SharedPtr ContextSharedPtr;
using ContextSharedPtr = rclcpp::context::Context::SharedPtr;
using rclcpp::utilities::ok;
using rclcpp::utilities::shutdown;
using rclcpp::utilities::init;
Expand Down
12 changes: 6 additions & 6 deletions rclcpp/include/rclcpp/service.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,16 +95,16 @@ template<typename ServiceT>
class Service : public ServiceBase
{
public:
typedef std::function<
void (
using CallbackType = std::function<
void(
const std::shared_ptr<typename ServiceT::Request> &,
std::shared_ptr<typename ServiceT::Response> &)> CallbackType;
std::shared_ptr<typename ServiceT::Response> &)>;

typedef std::function<
void (
using CallbackWithHeaderType = std::function<
void(
const std::shared_ptr<rmw_request_id_t> &,
const std::shared_ptr<typename ServiceT::Request> &,
std::shared_ptr<typename ServiceT::Response> &)> CallbackWithHeaderType;
std::shared_ptr<typename ServiceT::Response> &)>;
RCLCPP_SMART_PTR_DEFINITIONS(Service);

Service(
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/subscription.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -96,7 +96,7 @@ template<typename MessageT>
class Subscription : public SubscriptionBase
{
public:
typedef std::function<void (const std::shared_ptr<MessageT> &)> CallbackType;
using CallbackType = std::function<void(const std::shared_ptr<MessageT> &)>;
RCLCPP_SMART_PTR_DEFINITIONS(Subscription);

Subscription(
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 @@ -40,7 +40,7 @@ class Executor;
namespace timer
{

typedef std::function<void ()> CallbackType;
using CallbackType = std::function<void()>;

class TimerBase
{
Expand Down Expand Up @@ -151,7 +151,7 @@ class GenericTimer : public TimerBase

};

typedef GenericTimer<std::chrono::steady_clock> WallTimer;
using WallTimer = GenericTimer<std::chrono::steady_clock>;

} /* namespace timer */
} /* namespace rclcpp */
Expand Down

0 comments on commit 59a399b

Please sign in to comment.