Skip to content

Commit

Permalink
update
Browse files Browse the repository at this point in the history
  • Loading branch information
dirk-thomas committed Apr 7, 2015
1 parent 9a6b48e commit c6b8fb2
Show file tree
Hide file tree
Showing 10 changed files with 23 additions and 22 deletions.
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/callback_group.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ class CallbackGroup
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:
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 @@ -45,7 +45,7 @@ class ClientBase
RCLCPP_MAKE_SHARED_DEFINITIONS(ClientBase);

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

~ClientBase()
Expand Down Expand Up @@ -92,7 +92,7 @@ class Client : public ClientBase
RCLCPP_MAKE_SHARED_DEFINITIONS(Client);

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

std::shared_ptr<void> create_response()
Expand Down
14 changes: 8 additions & 6 deletions rclcpp/include/rclcpp/executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,9 @@ class Executor
public:
RCLCPP_MAKE_SHARED_DEFINITIONS(Executor);

Executor() : interrupt_guard_condition_(rmw_create_guard_condition()) {}
Executor()
: interrupt_guard_condition_(rmw_create_guard_condition())
{}

virtual ~Executor()
{
Expand All @@ -58,8 +60,7 @@ class Executor
auto node = weak_node.lock();
if (node == node_ptr) {
// TODO: Use a different error here?
throw std::runtime_error(
"Cannot add node to executor, node already added.");
throw std::runtime_error("Cannot add node to executor, node already added.");
}
}
weak_nodes_.push_back(node_ptr);
Expand Down Expand Up @@ -100,7 +101,9 @@ class Executor
protected:
struct AnyExecutable
{
AnyExecutable() : subscription(0), timer(0), callback_group(0), node(0) {}
AnyExecutable()
: subscription(0), timer(0), callback_group(0), node(0)
{}
// Either the subscription or the timer will be set, but not both
rclcpp::subscription::SubscriptionBase::SharedPtr subscription;
rclcpp::timer::TimerBase::SharedPtr timer;
Expand Down Expand Up @@ -313,8 +316,7 @@ class Executor
std::malloc(sizeof(void *) * number_of_guard_conds));
if (guard_condition_handles.guard_conditions == NULL) {
// TODO(wjwwood): Use a different error here? maybe std::bad_alloc?
throw std::runtime_error(
"Could not malloc for guard condition pointers.");
throw std::runtime_error("Could not malloc for guard condition pointers.");
}
// Put the global ctrl-c guard condition in
assert(guard_condition_handles.guard_condition_count > 1);
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/include/rclcpp/node_impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,11 +34,11 @@ using namespace rclcpp::node;
using rclcpp::contexts::default_context::DefaultContext;

Node::Node(std::string node_name)
: Node(node_name, DefaultContext::make_shared())
: Node(node_name, DefaultContext::make_shared())
{}

Node::Node(std::string node_name, context::Context::SharedPtr context)
: name_(node_name), context_(context),
: name_(node_name), context_(context),
number_of_subscriptions_(0), number_of_timers_(0), number_of_services_(0)
{
node_handle_ = rmw_create_node(name_.c_str());
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ class Publisher
RCLCPP_MAKE_SHARED_DEFINITIONS(Publisher);

Publisher(rmw_publisher_t * publisher_handle)
: publisher_handle_(publisher_handle)
: publisher_handle_(publisher_handle)
{}

template<typename MessageT>
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 @@ -48,11 +48,11 @@ class GenericRate : public RateBase
RCLCPP_MAKE_SHARED_DEFINITIONS(GenericRate);

GenericRate(double rate)
: GenericRate<Clock>(
: GenericRate<Clock>(
duration_cast<nanoseconds>(duration<double>(1.0 / rate)))
{}
GenericRate(std::chrono::nanoseconds period)
: period_(period), last_interval_(Clock::now())
: period_(period), last_interval_(Clock::now())
{}

virtual bool
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 @@ -46,7 +46,7 @@ class ServiceBase
ServiceBase(
rmw_service_t * service_handle,
const std::string service_name)
: service_handle_(service_handle), service_name_(service_name)
: service_handle_(service_handle), service_name_(service_name)
{}

~ServiceBase()
Expand Down Expand Up @@ -94,7 +94,7 @@ class Service : public ServiceBase
rmw_service_t * service_handle,
const std::string & service_name,
CallbackType callback)
: ServiceBase(service_handle, service_name), callback_(callback)
: ServiceBase(service_handle, service_name), callback_(callback)
{}

std::shared_ptr<void> create_request()
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 @@ -45,7 +45,7 @@ class SubscriptionBase
SubscriptionBase(
rmw_subscription_t * subscription_handle,
std::string & topic_name)
: subscription_handle_(subscription_handle), topic_name_(topic_name)
: subscription_handle_(subscription_handle), topic_name_(topic_name)
{}

std::string get_topic_name()
Expand Down Expand Up @@ -75,7 +75,7 @@ class Subscription : public SubscriptionBase
rmw_subscription_t * subscription_handle,
std::string & topic_name,
CallbackType callback)
: SubscriptionBase(subscription_handle, topic_name), callback_(callback)
: SubscriptionBase(subscription_handle, topic_name), callback_(callback)
{}

std::shared_ptr<void> create_message()
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 @@ -48,7 +48,7 @@ class TimerBase
RCLCPP_MAKE_SHARED_DEFINITIONS(TimerBase);

TimerBase(std::chrono::nanoseconds period, CallbackType callback)
: period_(period),
: period_(period),
callback_(callback),
canceled_(false)
{
Expand Down Expand Up @@ -81,7 +81,7 @@ class GenericTimer : public TimerBase
RCLCPP_MAKE_SHARED_DEFINITIONS(GenericTimer);

GenericTimer(std::chrono::nanoseconds period, CallbackType callback)
: TimerBase(period, callback), loop_rate_(period)
: TimerBase(period, callback), loop_rate_(period)
{
thread_ = std::thread(&GenericTimer<Clock>::run, this);
}
Expand Down
3 changes: 1 addition & 2 deletions rclcpp/include/rclcpp/utilities.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -109,8 +109,7 @@ init(int argc, char * argv[])
#endif
{
throw std::runtime_error(
std::string("Failed to set SIGINT signal handler: (" +
std::to_string(errno) + ")") +
std::string("Failed to set SIGINT signal handler: (" + std::to_string(errno) + ")") +
// TODO(wjwwood): use strerror_r on POSIX and strerror_s on Windows.
std::strerror(errno));
}
Expand Down

0 comments on commit c6b8fb2

Please sign in to comment.