Merge pull request #381 from ros2/uncrustify_master

update style to match latest uncrustify
This commit is contained in:
Dirk Thomas 2017-09-29 11:12:43 -07:00 committed by GitHub
commit c70f2f1452
28 changed files with 151 additions and 100 deletions

View file

@ -64,8 +64,9 @@ void * retyped_reallocate(void * untyped_pointer, size_t size, void * untyped_al
// Convert a std::allocator_traits-formatted Allocator into an rcl allocator // Convert a std::allocator_traits-formatted Allocator into an rcl allocator
template<typename T, typename Alloc, template<
typename std::enable_if<!std::is_same<Alloc, std::allocator<void>>::value>::type * = nullptr> typename T, typename Alloc,
typename std::enable_if<!std::is_same<Alloc, std::allocator<void>>::value>::type * = nullptr>
rcl_allocator_t get_rcl_allocator(Alloc & allocator) rcl_allocator_t get_rcl_allocator(Alloc & allocator)
{ {
rcl_allocator_t rcl_allocator = rcl_get_default_allocator(); rcl_allocator_t rcl_allocator = rcl_get_default_allocator();
@ -81,8 +82,9 @@ rcl_allocator_t get_rcl_allocator(Alloc & allocator)
} }
// TODO(jacquelinekay) Workaround for an incomplete implementation of std::allocator<void> // TODO(jacquelinekay) Workaround for an incomplete implementation of std::allocator<void>
template<typename T, typename Alloc, template<
typename std::enable_if<std::is_same<Alloc, std::allocator<void>>::value>::type * = nullptr> typename T, typename Alloc,
typename std::enable_if<std::is_same<Alloc, std::allocator<void>>::value>::type * = nullptr>
rcl_allocator_t get_rcl_allocator(Alloc & allocator) rcl_allocator_t get_rcl_allocator(Alloc & allocator)
{ {
(void)allocator; (void)allocator;

View file

@ -34,11 +34,13 @@ template<typename ServiceT>
class AnyServiceCallback class AnyServiceCallback
{ {
private: private:
using SharedPtrCallback = std::function<void( using SharedPtrCallback = std::function<
void(
const std::shared_ptr<typename ServiceT::Request>, const std::shared_ptr<typename ServiceT::Request>,
std::shared_ptr<typename ServiceT::Response> std::shared_ptr<typename ServiceT::Response>
)>; )>;
using SharedPtrWithRequestHeaderCallback = std::function<void( using SharedPtrWithRequestHeaderCallback = std::function<
void(
const std::shared_ptr<rmw_request_id_t>, const std::shared_ptr<rmw_request_id_t>,
const std::shared_ptr<typename ServiceT::Request>, const std::shared_ptr<typename ServiceT::Request>,
std::shared_ptr<typename ServiceT::Response> std::shared_ptr<typename ServiceT::Response>

View file

@ -193,7 +193,8 @@ public:
} }
void void
handle_response(std::shared_ptr<rmw_request_id_t> request_header, handle_response(
std::shared_ptr<rmw_request_id_t> request_header,
std::shared_ptr<void> response) std::shared_ptr<void> response)
{ {
std::lock_guard<std::mutex> lock(pending_requests_mutex_); std::lock_guard<std::mutex> lock(pending_requests_mutex_);

View file

@ -116,7 +116,7 @@ throw_from_rcl_error(
rcl_ret_t ret, rcl_ret_t ret,
const std::string & prefix = "", const std::string & prefix = "",
const rcl_error_state_t * error_state = nullptr, const rcl_error_state_t * error_state = nullptr,
void (* reset_error)() = rcl_reset_error); void (*reset_error)() = rcl_reset_error);
class RCLErrorBase class RCLErrorBase
{ {

View file

@ -151,7 +151,8 @@ public:
*/ */
template<typename T = std::milli> template<typename T = std::milli>
void void
spin_node_once(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node, spin_node_once(
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node,
std::chrono::duration<int64_t, T> timeout = std::chrono::duration<int64_t, T>(-1)) std::chrono::duration<int64_t, T> timeout = std::chrono::duration<int64_t, T>(-1))
{ {
return spin_node_once_nanoseconds( return spin_node_once_nanoseconds(
@ -163,7 +164,8 @@ public:
/// Convenience function which takes Node and forwards NodeBaseInterface. /// Convenience function which takes Node and forwards NodeBaseInterface.
template<typename NodeT = rclcpp::node::Node, typename T = std::milli> template<typename NodeT = rclcpp::node::Node, typename T = std::milli>
void void
spin_node_once(std::shared_ptr<NodeT> node, spin_node_once(
std::shared_ptr<NodeT> node,
std::chrono::duration<int64_t, T> timeout = std::chrono::duration<int64_t, T>(-1)) std::chrono::duration<int64_t, T> timeout = std::chrono::duration<int64_t, T>(-1))
{ {
return spin_node_once_nanoseconds( return spin_node_once_nanoseconds(

View file

@ -186,14 +186,16 @@ public:
*/ */
template<typename MessageT, typename Alloc> template<typename MessageT, typename Alloc>
uint64_t uint64_t
add_publisher(typename publisher::Publisher<MessageT, Alloc>::SharedPtr publisher, add_publisher(
typename publisher::Publisher<MessageT, Alloc>::SharedPtr publisher,
size_t buffer_size = 0) size_t buffer_size = 0)
{ {
auto id = IntraProcessManager::get_next_unique_id(); auto id = IntraProcessManager::get_next_unique_id();
size_t size = buffer_size > 0 ? buffer_size : publisher->get_queue_size(); size_t size = buffer_size > 0 ? buffer_size : publisher->get_queue_size();
auto mrb = mapped_ring_buffer::MappedRingBuffer<MessageT, auto mrb = mapped_ring_buffer::MappedRingBuffer<
typename publisher::Publisher<MessageT, Alloc>::MessageAlloc>::make_shared( MessageT,
size, publisher->get_allocator()); typename publisher::Publisher<MessageT, Alloc>::MessageAlloc
>::make_shared(size, publisher->get_allocator());
impl_->add_publisher(id, publisher, mrb, size); impl_->add_publisher(id, publisher, mrb, size);
return id; return id;
} }
@ -239,7 +241,8 @@ public:
* \param message the message that is being stored. * \param message the message that is being stored.
* \return the message sequence number. * \return the message sequence number.
*/ */
template<typename MessageT, typename Alloc = std::allocator<void>, template<
typename MessageT, typename Alloc = std::allocator<void>,
typename Deleter = std::default_delete<MessageT>> typename Deleter = std::default_delete<MessageT>>
uint64_t uint64_t
store_intra_process_message( store_intra_process_message(
@ -302,7 +305,8 @@ public:
* \param requesting_subscriptions_intra_process_id the subscription's id. * \param requesting_subscriptions_intra_process_id the subscription's id.
* \param message the message typed unique_ptr used to return the message. * \param message the message typed unique_ptr used to return the message.
*/ */
template<typename MessageT, typename Alloc = std::allocator<void>, template<
typename MessageT, typename Alloc = std::allocator<void>,
typename Deleter = std::default_delete<MessageT>> typename Deleter = std::default_delete<MessageT>>
void void
take_intra_process_message( take_intra_process_message(

View file

@ -53,7 +53,8 @@ public:
virtual void virtual void
remove_subscription(uint64_t intra_process_subscription_id) = 0; remove_subscription(uint64_t intra_process_subscription_id) = 0;
virtual void add_publisher(uint64_t id, virtual void add_publisher(
uint64_t id,
publisher::PublisherBase::WeakPtr publisher, publisher::PublisherBase::WeakPtr publisher,
mapped_ring_buffer::MappedRingBufferBase::SharedPtr mrb, mapped_ring_buffer::MappedRingBufferBase::SharedPtr mrb,
size_t size) = 0; size_t size) = 0;
@ -70,7 +71,8 @@ public:
store_intra_process_message(uint64_t intra_process_publisher_id, uint64_t message_seq) = 0; store_intra_process_message(uint64_t intra_process_publisher_id, uint64_t message_seq) = 0;
virtual mapped_ring_buffer::MappedRingBufferBase::SharedPtr virtual mapped_ring_buffer::MappedRingBufferBase::SharedPtr
take_intra_process_message(uint64_t intra_process_publisher_id, take_intra_process_message(
uint64_t intra_process_publisher_id,
uint64_t message_sequence_number, uint64_t message_sequence_number,
uint64_t requesting_subscriptions_intra_process_id, uint64_t requesting_subscriptions_intra_process_id,
size_t & size) = 0; size_t & size) = 0;
@ -114,7 +116,8 @@ public:
} }
} }
void add_publisher(uint64_t id, void add_publisher(
uint64_t id,
publisher::PublisherBase::WeakPtr publisher, publisher::PublisherBase::WeakPtr publisher,
mapped_ring_buffer::MappedRingBufferBase::SharedPtr mrb, mapped_ring_buffer::MappedRingBufferBase::SharedPtr mrb,
size_t size) size_t size)
@ -189,7 +192,8 @@ public:
} }
mapped_ring_buffer::MappedRingBufferBase::SharedPtr mapped_ring_buffer::MappedRingBufferBase::SharedPtr
take_intra_process_message(uint64_t intra_process_publisher_id, take_intra_process_message(
uint64_t intra_process_publisher_id,
uint64_t message_sequence_number, uint64_t message_sequence_number,
uint64_t requesting_subscriptions_intra_process_id, uint64_t requesting_subscriptions_intra_process_id,
size_t & size size_t & size
@ -253,7 +257,8 @@ private:
RebindAlloc<uint64_t> uint64_allocator; RebindAlloc<uint64_t> uint64_allocator;
using AllocSet = std::set<uint64_t, std::less<uint64_t>, RebindAlloc<uint64_t>>; using AllocSet = std::set<uint64_t, std::less<uint64_t>, RebindAlloc<uint64_t>>;
using SubscriptionMap = std::unordered_map<uint64_t, subscription::SubscriptionBase::WeakPtr, using SubscriptionMap = std::unordered_map<
uint64_t, subscription::SubscriptionBase::WeakPtr,
std::hash<uint64_t>, std::equal_to<uint64_t>, std::hash<uint64_t>, std::equal_to<uint64_t>,
RebindAlloc<std::pair<const uint64_t, subscription::SubscriptionBase::WeakPtr>>>; RebindAlloc<std::pair<const uint64_t, subscription::SubscriptionBase::WeakPtr>>>;
@ -285,13 +290,15 @@ private:
std::atomic<uint64_t> sequence_number; std::atomic<uint64_t> sequence_number;
mapped_ring_buffer::MappedRingBufferBase::SharedPtr buffer; mapped_ring_buffer::MappedRingBufferBase::SharedPtr buffer;
using TargetSubscriptionsMap = std::unordered_map<uint64_t, AllocSet, using TargetSubscriptionsMap = std::unordered_map<
uint64_t, AllocSet,
std::hash<uint64_t>, std::equal_to<uint64_t>, std::hash<uint64_t>, std::equal_to<uint64_t>,
RebindAlloc<std::pair<const uint64_t, AllocSet>>>; RebindAlloc<std::pair<const uint64_t, AllocSet>>>;
TargetSubscriptionsMap target_subscriptions_by_message_sequence; TargetSubscriptionsMap target_subscriptions_by_message_sequence;
}; };
using PublisherMap = std::unordered_map<uint64_t, PublisherInfo, using PublisherMap = std::unordered_map<
uint64_t, PublisherInfo,
std::hash<uint64_t>, std::equal_to<uint64_t>, std::hash<uint64_t>, std::equal_to<uint64_t>,
RebindAlloc<std::pair<const uint64_t, PublisherInfo>>>; RebindAlloc<std::pair<const uint64_t, PublisherInfo>>>;

View file

@ -64,22 +64,26 @@ public:
virtual void remove_guard_condition(const rcl_guard_condition_t * guard_condition) = 0; virtual void remove_guard_condition(const rcl_guard_condition_t * guard_condition) = 0;
virtual void virtual void
get_next_subscription(rclcpp::executor::AnyExecutable::SharedPtr any_exec, get_next_subscription(
rclcpp::executor::AnyExecutable::SharedPtr any_exec,
const WeakNodeVector & weak_nodes) = 0; const WeakNodeVector & weak_nodes) = 0;
virtual void virtual void
get_next_service(rclcpp::executor::AnyExecutable::SharedPtr any_exec, get_next_service(
rclcpp::executor::AnyExecutable::SharedPtr any_exec,
const WeakNodeVector & weak_nodes) = 0; const WeakNodeVector & weak_nodes) = 0;
virtual void virtual void
get_next_client(rclcpp::executor::AnyExecutable::SharedPtr any_exec, get_next_client(
rclcpp::executor::AnyExecutable::SharedPtr any_exec,
const WeakNodeVector & weak_nodes) = 0; const WeakNodeVector & weak_nodes) = 0;
virtual rcl_allocator_t virtual rcl_allocator_t
get_allocator() = 0; get_allocator() = 0;
static rclcpp::subscription::SubscriptionBase::SharedPtr static rclcpp::subscription::SubscriptionBase::SharedPtr
get_subscription_by_handle(const rcl_subscription_t * subscriber_handle, get_subscription_by_handle(
const rcl_subscription_t * subscriber_handle,
const WeakNodeVector & weak_nodes); const WeakNodeVector & weak_nodes);
static rclcpp::service::ServiceBase::SharedPtr static rclcpp::service::ServiceBase::SharedPtr
@ -89,7 +93,8 @@ public:
get_client_by_handle(const rcl_client_t * client_handle, const WeakNodeVector & weak_nodes); get_client_by_handle(const rcl_client_t * client_handle, const WeakNodeVector & weak_nodes);
static rclcpp::node_interfaces::NodeBaseInterface::SharedPtr static rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
get_node_by_group(rclcpp::callback_group::CallbackGroup::SharedPtr group, get_node_by_group(
rclcpp::callback_group::CallbackGroup::SharedPtr group,
const WeakNodeVector & weak_nodes); const WeakNodeVector & weak_nodes);
static rclcpp::callback_group::CallbackGroup::SharedPtr static rclcpp::callback_group::CallbackGroup::SharedPtr
@ -103,7 +108,8 @@ public:
const WeakNodeVector & weak_nodes); const WeakNodeVector & weak_nodes);
static rclcpp::callback_group::CallbackGroup::SharedPtr static rclcpp::callback_group::CallbackGroup::SharedPtr
get_group_by_client(rclcpp::client::ClientBase::SharedPtr client, get_group_by_client(
rclcpp::client::ClientBase::SharedPtr client,
const WeakNodeVector & weak_nodes); const WeakNodeVector & weak_nodes);
}; };

View file

@ -81,8 +81,8 @@ public:
rcl_interfaces::msg::ListParametersResult rcl_interfaces::msg::ListParametersResult
list_parameters(const std::vector<std::string> & prefixes, uint64_t depth) const = 0; list_parameters(const std::vector<std::string> & prefixes, uint64_t depth) const = 0;
using ParametersCallbackFunction = using ParametersCallbackFunction = std::function<
std::function<rcl_interfaces::msg::SetParametersResult( rcl_interfaces::msg::SetParametersResult(
const std::vector<rclcpp::parameter::ParameterVariant> &)>; const std::vector<rclcpp::parameter::ParameterVariant> &)>;
RCLCPP_PUBLIC RCLCPP_PUBLIC

View file

@ -50,7 +50,7 @@ namespace publisher
class PublisherBase class PublisherBase
{ {
friend rclcpp::node_interfaces::NodeTopicsInterface; friend ::rclcpp::node_interfaces::NodeTopicsInterface;
public: public:
RCLCPP_SMART_PTR_DEFINITIONS(PublisherBase) RCLCPP_SMART_PTR_DEFINITIONS(PublisherBase)

View file

@ -31,7 +31,7 @@ struct ScopeExit
{ {
explicit ScopeExit(Callable callable) explicit ScopeExit(Callable callable)
: callable_(callable) {} : callable_(callable) {}
~ScopeExit() {callable_(); } ~ScopeExit() {callable_();}
private: private:
Callable callable_; Callable callable_;
@ -47,6 +47,6 @@ make_scope_exit(Callable callable)
} // namespace rclcpp } // namespace rclcpp
#define RCLCPP_SCOPE_EXIT(code) \ #define RCLCPP_SCOPE_EXIT(code) \
auto RCLCPP_STRING_JOIN(scope_exit_, __LINE__) = rclcpp::make_scope_exit([&]() {code; }) auto RCLCPP_STRING_JOIN(scope_exit_, __LINE__) = rclcpp::make_scope_exit([&]() {code;})
#endif // RCLCPP__SCOPE_EXIT_HPP_ #endif // RCLCPP__SCOPE_EXIT_HPP_

View file

@ -196,7 +196,8 @@ public:
return std::shared_ptr<rmw_request_id_t>(new rmw_request_id_t); return std::shared_ptr<rmw_request_id_t>(new rmw_request_id_t);
} }
void handle_request(std::shared_ptr<rmw_request_id_t> request_header, void handle_request(
std::shared_ptr<rmw_request_id_t> request_header,
std::shared_ptr<void> request) std::shared_ptr<void> request)
{ {
auto typed_request = std::static_pointer_cast<typename ServiceT::Request>(request); auto typed_request = std::static_pointer_cast<typename ServiceT::Request>(request);

View file

@ -231,7 +231,8 @@ public:
} }
virtual void virtual void
get_next_subscription(executor::AnyExecutable::SharedPtr any_exec, get_next_subscription(
executor::AnyExecutable::SharedPtr any_exec,
const WeakNodeVector & weak_nodes) const WeakNodeVector & weak_nodes)
{ {
auto it = subscription_handles_.begin(); auto it = subscription_handles_.begin();
@ -274,7 +275,8 @@ public:
} }
virtual void virtual void
get_next_service(executor::AnyExecutable::SharedPtr any_exec, get_next_service(
executor::AnyExecutable::SharedPtr any_exec,
const WeakNodeVector & weak_nodes) const WeakNodeVector & weak_nodes)
{ {
auto it = service_handles_.begin(); auto it = service_handles_.begin();

View file

@ -55,7 +55,8 @@ struct SubscriptionFactory
SubscriptionFactoryFunction create_typed_subscription; SubscriptionFactoryFunction create_typed_subscription;
// Function that takes a MessageT from the intra process manager // Function that takes a MessageT from the intra process manager
using SetupIntraProcessFunction = std::function<void( using SetupIntraProcessFunction = std::function<
void(
rclcpp::intra_process_manager::IntraProcessManager::SharedPtr ipm, rclcpp::intra_process_manager::IntraProcessManager::SharedPtr ipm,
rclcpp::subscription::SubscriptionBase::SharedPtr subscription, rclcpp::subscription::SubscriptionBase::SharedPtr subscription,
const rcl_subscription_options_t & subscription_options)>; const rcl_subscription_options_t & subscription_options)>;

View file

@ -44,7 +44,7 @@ throw_from_rcl_error(
rcl_ret_t ret, rcl_ret_t ret,
const std::string & prefix, const std::string & prefix,
const rcl_error_state_t * error_state, const rcl_error_state_t * error_state,
void (* reset_error)()) void (*reset_error)())
{ {
if (RCL_RET_OK == ret) { if (RCL_RET_OK == ret) {
throw std::invalid_argument("ret is RCL_RET_OK"); throw std::invalid_argument("ret is RCL_RET_OK");

View file

@ -54,7 +54,8 @@ rclcpp::expand_topic_or_service_name(
if (rcutils_error_state_copy(rcl_get_error_state(), &error_state) != RCUTILS_RET_OK) { if (rcutils_error_state_copy(rcl_get_error_state(), &error_state) != RCUTILS_RET_OK) {
throw std::bad_alloc(); throw std::bad_alloc();
} }
auto error_state_scope_exit = rclcpp::make_scope_exit([&error_state]() { auto error_state_scope_exit = rclcpp::make_scope_exit(
[&error_state]() {
rcutils_error_state_fini(&error_state); rcutils_error_state_fini(&error_state);
}); });
// finalize the string map before throwing // finalize the string map before throwing

View file

@ -75,7 +75,8 @@ GraphListener::start_if_not_started()
// This is important to ensure that the wait set is finalized before // This is important to ensure that the wait set is finalized before
// destruction of static objects occurs. // destruction of static objects occurs.
std::weak_ptr<GraphListener> weak_this = shared_from_this(); std::weak_ptr<GraphListener> weak_this = shared_from_this();
rclcpp::utilities::on_shutdown([weak_this]() { rclcpp::utilities::on_shutdown(
[weak_this]() {
auto shared_this = weak_this.lock(); auto shared_this = weak_this.lock();
if (shared_this) { if (shared_this) {
shared_this->shutdown(); shared_this->shutdown();

View file

@ -47,7 +47,8 @@ MemoryStrategy::get_subscription_by_handle(
} }
rclcpp::service::ServiceBase::SharedPtr rclcpp::service::ServiceBase::SharedPtr
MemoryStrategy::get_service_by_handle(const rcl_service_t * service_handle, MemoryStrategy::get_service_by_handle(
const rcl_service_t * service_handle,
const WeakNodeVector & weak_nodes) const WeakNodeVector & weak_nodes)
{ {
for (auto & weak_node : weak_nodes) { for (auto & weak_node : weak_nodes) {
@ -72,7 +73,8 @@ MemoryStrategy::get_service_by_handle(const rcl_service_t * service_handle,
} }
rclcpp::client::ClientBase::SharedPtr rclcpp::client::ClientBase::SharedPtr
MemoryStrategy::get_client_by_handle(const rcl_client_t * client_handle, MemoryStrategy::get_client_by_handle(
const rcl_client_t * client_handle,
const WeakNodeVector & weak_nodes) const WeakNodeVector & weak_nodes)
{ {
for (auto & weak_node : weak_nodes) { for (auto & weak_node : weak_nodes) {
@ -97,7 +99,8 @@ MemoryStrategy::get_client_by_handle(const rcl_client_t * client_handle,
} }
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
MemoryStrategy::get_node_by_group(rclcpp::callback_group::CallbackGroup::SharedPtr group, MemoryStrategy::get_node_by_group(
rclcpp::callback_group::CallbackGroup::SharedPtr group,
const WeakNodeVector & weak_nodes) const WeakNodeVector & weak_nodes)
{ {
if (!group) { if (!group) {

View file

@ -117,7 +117,8 @@ Node::get_parameter(const std::string & name) const
return node_parameters_->get_parameter(name); return node_parameters_->get_parameter(name);
} }
bool Node::get_parameter(const std::string & name, bool Node::get_parameter(
const std::string & name,
rclcpp::parameter::ParameterVariant & parameter) const rclcpp::parameter::ParameterVariant & parameter) const
{ {
return node_parameters_->get_parameter(name, parameter); return node_parameters_->get_parameter(name, parameter);

View file

@ -133,7 +133,9 @@ NodeBase::NodeBase(
throw_from_rcl_error(ret, "failed to initialize rcl node"); throw_from_rcl_error(ret, "failed to initialize rcl node");
} }
node_handle_.reset(rcl_node, [](rcl_node_t * node) -> void { node_handle_.reset(
rcl_node,
[](rcl_node_t * node) -> void {
if (rcl_node_fini(node) != RCL_RET_OK) { if (rcl_node_fini(node) != RCL_RET_OK) {
fprintf( fprintf(
stderr, "Error in destruction of rcl node handle: %s\n", rcl_get_error_string_safe()); stderr, "Error in destruction of rcl node handle: %s\n", rcl_get_error_string_safe());

View file

@ -176,13 +176,15 @@ rclcpp::utilities::init(int argc, char * argv[])
action.sa_flags = SA_SIGINFO; action.sa_flags = SA_SIGINFO;
::old_action = set_sigaction(SIGINT, action); ::old_action = set_sigaction(SIGINT, action);
// Register an on_shutdown hook to restore the old action. // Register an on_shutdown hook to restore the old action.
rclcpp::utilities::on_shutdown([]() { rclcpp::utilities::on_shutdown(
[]() {
set_sigaction(SIGINT, ::old_action); set_sigaction(SIGINT, ::old_action);
}); });
#else #else
::old_signal_handler = set_signal_handler(SIGINT, ::signal_handler); ::old_signal_handler = set_signal_handler(SIGINT, ::signal_handler);
// Register an on_shutdown hook to restore the old signal handler. // Register an on_shutdown hook to restore the old signal handler.
rclcpp::utilities::on_shutdown([]() { rclcpp::utilities::on_shutdown(
[]() {
set_signal_handler(SIGINT, ::old_signal_handler); set_signal_handler(SIGINT, ::old_signal_handler);
}); });
#endif #endif

View file

@ -37,7 +37,8 @@ protected:
}; };
void void
callback(const std::shared_ptr<rclcpp::srv::Mock::Request>/*req*/, callback(
const std::shared_ptr<rclcpp::srv::Mock::Request>/*req*/,
std::shared_ptr<rclcpp::srv::Mock::Response>/*resp*/) std::shared_ptr<rclcpp::srv::Mock::Response>/*resp*/)
{} {}

View file

@ -25,7 +25,9 @@ struct has_on_activate
}; };
template<class T> template<class T>
struct has_on_activate<T, typename std::enable_if< struct has_on_activate<
T,
typename std::enable_if<
std::is_same<void, decltype(std::declval<T>().on_activate())>::value>::type> std::is_same<void, decltype(std::declval<T>().on_activate())>::value>::type>
{ {
static constexpr bool value = true; static constexpr bool value = true;
@ -38,7 +40,9 @@ struct has_on_deactivate
}; };
template<class T> template<class T>
struct has_on_deactivate<T, typename std::enable_if< struct has_on_deactivate<
T,
typename std::enable_if<
std::is_same<void, decltype(std::declval<T>().on_deactivate())>::value>::type> std::is_same<void, decltype(std::declval<T>().on_deactivate())>::value>::type>
{ {
static constexpr bool value = true; static constexpr bool value = true;
@ -49,7 +53,9 @@ struct is_manageable_node : std::false_type
{}; {};
template<class T> template<class T>
struct is_manageable_node<T, typename std::enable_if< struct is_manageable_node<
T,
typename std::enable_if<
has_on_activate<T>::value && has_on_deactivate<T>::value>::type>: std::true_type has_on_activate<T>::value && has_on_deactivate<T>::value>::type>: std::true_type
{}; {};

View file

@ -135,7 +135,8 @@ LifecycleNode::get_parameter(const std::string & name) const
return node_parameters_->get_parameter(name); return node_parameters_->get_parameter(name);
} }
bool LifecycleNode::get_parameter(const std::string & name, bool LifecycleNode::get_parameter(
const std::string & name,
rclcpp::parameter::ParameterVariant & parameter) const rclcpp::parameter::ParameterVariant & parameter) const
{ {
return node_parameters_->get_parameter(name, parameter); return node_parameters_->get_parameter(name, parameter);

View file

@ -164,7 +164,8 @@ public:
} }
bool bool
register_callback(std::uint8_t lifecycle_transition, std::function<rcl_lifecycle_transition_key_t( register_callback(
std::uint8_t lifecycle_transition, std::function<rcl_lifecycle_transition_key_t(
const State &)> & cb) const State &)> & cb)
{ {
cb_map_[lifecycle_transition] = cb; cb_map_[lifecycle_transition] = cb;
@ -172,7 +173,8 @@ public:
} }
void void
on_change_state(const std::shared_ptr<rmw_request_id_t> header, on_change_state(
const std::shared_ptr<rmw_request_id_t> header,
const std::shared_ptr<ChangeStateSrv::Request> req, const std::shared_ptr<ChangeStateSrv::Request> req,
std::shared_ptr<ChangeStateSrv::Response> resp) std::shared_ptr<ChangeStateSrv::Response> resp)
{ {
@ -192,7 +194,8 @@ public:
} }
void void
on_get_state(const std::shared_ptr<rmw_request_id_t> header, on_get_state(
const std::shared_ptr<rmw_request_id_t> header,
const std::shared_ptr<GetStateSrv::Request> req, const std::shared_ptr<GetStateSrv::Request> req,
std::shared_ptr<GetStateSrv::Response> resp) std::shared_ptr<GetStateSrv::Response> resp)
{ {
@ -207,7 +210,8 @@ public:
} }
void void
on_get_available_states(const std::shared_ptr<rmw_request_id_t> header, on_get_available_states(
const std::shared_ptr<rmw_request_id_t> header,
const std::shared_ptr<GetAvailableStatesSrv::Request> req, const std::shared_ptr<GetAvailableStatesSrv::Request> req,
std::shared_ptr<GetAvailableStatesSrv::Response> resp) std::shared_ptr<GetAvailableStatesSrv::Response> resp)
{ {
@ -226,7 +230,8 @@ public:
} }
void void
on_get_available_transitions(const std::shared_ptr<rmw_request_id_t> header, on_get_available_transitions(
const std::shared_ptr<rmw_request_id_t> header,
const std::shared_ptr<GetAvailableTransitionsSrv::Request> req, const std::shared_ptr<GetAvailableTransitionsSrv::Request> req,
std::shared_ptr<GetAvailableTransitionsSrv::Response> resp) std::shared_ptr<GetAvailableTransitionsSrv::Response> resp)
{ {