update style (#445)
This commit is contained in:
parent
2b7cb21cbd
commit
1a604b0c28
14 changed files with 63 additions and 63 deletions
|
@ -94,11 +94,11 @@ void set_allocator_for_deleter(AllocatorDeleter<T> * deleter, Alloc * alloc)
|
||||||
|
|
||||||
template<typename Alloc, typename T>
|
template<typename Alloc, typename T>
|
||||||
using Deleter = typename std::conditional<
|
using Deleter = typename std::conditional<
|
||||||
std::is_same<typename std::allocator_traits<Alloc>::template rebind_alloc<T>,
|
std::is_same<typename std::allocator_traits<Alloc>::template rebind_alloc<T>,
|
||||||
typename std::allocator<void>::template rebind<T>::other>::value,
|
typename std::allocator<void>::template rebind<T>::other>::value,
|
||||||
std::default_delete<T>,
|
std::default_delete<T>,
|
||||||
AllocatorDeleter<Alloc>
|
AllocatorDeleter<Alloc>
|
||||||
>::type;
|
>::type;
|
||||||
} // namespace allocator
|
} // namespace allocator
|
||||||
} // namespace rclcpp
|
} // namespace rclcpp
|
||||||
|
|
||||||
|
|
|
@ -32,16 +32,16 @@ class AnyServiceCallback
|
||||||
{
|
{
|
||||||
private:
|
private:
|
||||||
using SharedPtrCallback = std::function<
|
using SharedPtrCallback = std::function<
|
||||||
void(
|
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<
|
using SharedPtrWithRequestHeaderCallback = std::function<
|
||||||
void(
|
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>
|
||||||
)>;
|
)>;
|
||||||
|
|
||||||
SharedPtrCallback shared_ptr_callback_;
|
SharedPtrCallback shared_ptr_callback_;
|
||||||
SharedPtrWithRequestHeaderCallback shared_ptr_with_request_header_callback_;
|
SharedPtrWithRequestHeaderCallback shared_ptr_with_request_header_callback_;
|
||||||
|
|
|
@ -40,13 +40,13 @@ class AnySubscriptionCallback
|
||||||
|
|
||||||
using SharedPtrCallback = std::function<void(const std::shared_ptr<MessageT>)>;
|
using SharedPtrCallback = std::function<void(const std::shared_ptr<MessageT>)>;
|
||||||
using SharedPtrWithInfoCallback =
|
using SharedPtrWithInfoCallback =
|
||||||
std::function<void(const std::shared_ptr<MessageT>, const rmw_message_info_t &)>;
|
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 ConstSharedPtrCallback = std::function<void(const std::shared_ptr<const MessageT>)>;
|
||||||
using ConstSharedPtrWithInfoCallback =
|
using ConstSharedPtrWithInfoCallback =
|
||||||
std::function<void(const std::shared_ptr<const MessageT>, const rmw_message_info_t &)>;
|
std::function<void(const std::shared_ptr<const MessageT>, const rmw_message_info_t &)>;
|
||||||
using UniquePtrCallback = std::function<void(MessageUniquePtr)>;
|
using UniquePtrCallback = std::function<void(MessageUniquePtr)>;
|
||||||
using UniquePtrWithInfoCallback =
|
using UniquePtrWithInfoCallback =
|
||||||
std::function<void(MessageUniquePtr, const rmw_message_info_t &)>;
|
std::function<void(MessageUniquePtr, const rmw_message_info_t &)>;
|
||||||
|
|
||||||
SharedPtrCallback shared_ptr_callback_;
|
SharedPtrCallback shared_ptr_callback_;
|
||||||
SharedPtrWithInfoCallback shared_ptr_with_info_callback_;
|
SharedPtrWithInfoCallback shared_ptr_with_info_callback_;
|
||||||
|
|
|
@ -49,7 +49,7 @@ template<typename FunctionT>
|
||||||
struct function_traits
|
struct function_traits
|
||||||
{
|
{
|
||||||
using arguments = typename tuple_tail<
|
using arguments = typename tuple_tail<
|
||||||
typename function_traits<decltype( & FunctionT::operator())>::arguments>::type;
|
typename function_traits<decltype( & FunctionT::operator())>::arguments>::type;
|
||||||
|
|
||||||
static constexpr std::size_t arity = std::tuple_size<arguments>::value;
|
static constexpr std::size_t arity = std::tuple_size<arguments>::value;
|
||||||
|
|
||||||
|
|
|
@ -258,9 +258,9 @@ private:
|
||||||
|
|
||||||
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<
|
using SubscriptionMap = std::unordered_map<
|
||||||
uint64_t, SubscriptionBase::WeakPtr,
|
uint64_t, 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, SubscriptionBase::WeakPtr>>>;
|
RebindAlloc<std::pair<const uint64_t, SubscriptionBase::WeakPtr>>>;
|
||||||
|
|
||||||
struct strcmp_wrapper : public std::binary_function<const char *, const char *, bool>
|
struct strcmp_wrapper : public std::binary_function<const char *, const char *, bool>
|
||||||
{
|
{
|
||||||
|
@ -271,10 +271,10 @@ private:
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
using IDTopicMap = std::map<
|
using IDTopicMap = std::map<
|
||||||
const char *,
|
const char *,
|
||||||
AllocSet,
|
AllocSet,
|
||||||
strcmp_wrapper,
|
strcmp_wrapper,
|
||||||
RebindAlloc<std::pair<const char * const, AllocSet>>>;
|
RebindAlloc<std::pair<const char * const, AllocSet>>>;
|
||||||
|
|
||||||
SubscriptionMap subscriptions_;
|
SubscriptionMap subscriptions_;
|
||||||
|
|
||||||
|
@ -291,16 +291,16 @@ private:
|
||||||
mapped_ring_buffer::MappedRingBufferBase::SharedPtr buffer;
|
mapped_ring_buffer::MappedRingBufferBase::SharedPtr buffer;
|
||||||
|
|
||||||
using TargetSubscriptionsMap = std::unordered_map<
|
using TargetSubscriptionsMap = std::unordered_map<
|
||||||
uint64_t, AllocSet,
|
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<
|
using PublisherMap = std::unordered_map<
|
||||||
uint64_t, PublisherInfo,
|
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>>>;
|
||||||
|
|
||||||
PublisherMap publishers_;
|
PublisherMap publishers_;
|
||||||
|
|
||||||
|
|
|
@ -82,8 +82,8 @@ public:
|
||||||
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 = std::function<
|
using ParametersCallbackFunction = 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
|
||||||
virtual
|
virtual
|
||||||
|
|
|
@ -46,19 +46,19 @@ struct PublisherFactory
|
||||||
{
|
{
|
||||||
// Creates a PublisherT<MessageT, ...> publisher object and returns it as a PublisherBase.
|
// Creates a PublisherT<MessageT, ...> publisher object and returns it as a PublisherBase.
|
||||||
using PublisherFactoryFunction = std::function<
|
using PublisherFactoryFunction = std::function<
|
||||||
rclcpp::PublisherBase::SharedPtr(
|
rclcpp::PublisherBase::SharedPtr(
|
||||||
rclcpp::node_interfaces::NodeBaseInterface * node_base,
|
rclcpp::node_interfaces::NodeBaseInterface * node_base,
|
||||||
const std::string & topic_name,
|
const std::string & topic_name,
|
||||||
rcl_publisher_options_t & publisher_options)>;
|
rcl_publisher_options_t & publisher_options)>;
|
||||||
|
|
||||||
PublisherFactoryFunction create_typed_publisher;
|
PublisherFactoryFunction create_typed_publisher;
|
||||||
|
|
||||||
// Adds the PublisherBase to the intraprocess manager with the correctly
|
// Adds the PublisherBase to the intraprocess manager with the correctly
|
||||||
// templated call to IntraProcessManager::store_intra_process_message.
|
// templated call to IntraProcessManager::store_intra_process_message.
|
||||||
using AddPublisherToIntraProcessManagerFunction = std::function<
|
using AddPublisherToIntraProcessManagerFunction = std::function<
|
||||||
uint64_t(
|
uint64_t(
|
||||||
rclcpp::intra_process_manager::IntraProcessManager * ipm,
|
rclcpp::intra_process_manager::IntraProcessManager * ipm,
|
||||||
rclcpp::PublisherBase::SharedPtr publisher)>;
|
rclcpp::PublisherBase::SharedPtr publisher)>;
|
||||||
|
|
||||||
AddPublisherToIntraProcessManagerFunction add_publisher_to_intra_process_manager;
|
AddPublisherToIntraProcessManagerFunction add_publisher_to_intra_process_manager;
|
||||||
|
|
||||||
|
@ -66,8 +66,8 @@ struct PublisherFactory
|
||||||
// PublisherT::publish() and which handles the intra process transmission of
|
// PublisherT::publish() and which handles the intra process transmission of
|
||||||
// the message being published.
|
// the message being published.
|
||||||
using SharedPublishCallbackFactoryFunction = std::function<
|
using SharedPublishCallbackFactoryFunction = std::function<
|
||||||
rclcpp::PublisherBase::StoreMessageCallbackT(
|
rclcpp::PublisherBase::StoreMessageCallbackT(
|
||||||
rclcpp::intra_process_manager::IntraProcessManager::SharedPtr ipm)>;
|
rclcpp::intra_process_manager::IntraProcessManager::SharedPtr ipm)>;
|
||||||
|
|
||||||
SharedPublishCallbackFactoryFunction create_shared_publish_callback;
|
SharedPublishCallbackFactoryFunction create_shared_publish_callback;
|
||||||
};
|
};
|
||||||
|
|
|
@ -94,15 +94,15 @@ class Service : public ServiceBase
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
using CallbackType = std::function<
|
using CallbackType = std::function<
|
||||||
void(
|
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 CallbackWithHeaderType = std::function<
|
using CallbackWithHeaderType = std::function<
|
||||||
void(
|
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>)>;
|
||||||
RCLCPP_SMART_PTR_DEFINITIONS(Service)
|
RCLCPP_SMART_PTR_DEFINITIONS(Service)
|
||||||
|
|
||||||
Service(
|
Service(
|
||||||
|
|
|
@ -387,7 +387,7 @@ public:
|
||||||
private:
|
private:
|
||||||
template<typename T>
|
template<typename T>
|
||||||
using VectorRebind =
|
using VectorRebind =
|
||||||
std::vector<T, typename std::allocator_traits<Alloc>::template rebind_alloc<T>>;
|
std::vector<T, typename std::allocator_traits<Alloc>::template rebind_alloc<T>>;
|
||||||
|
|
||||||
VectorRebind<const rcl_guard_condition_t *> guard_conditions_;
|
VectorRebind<const rcl_guard_condition_t *> guard_conditions_;
|
||||||
|
|
||||||
|
|
|
@ -229,7 +229,7 @@ public:
|
||||||
}
|
}
|
||||||
|
|
||||||
using GetMessageCallbackType =
|
using GetMessageCallbackType =
|
||||||
std::function<void(uint64_t, uint64_t, uint64_t, MessageUniquePtr &)>;
|
std::function<void(uint64_t, uint64_t, uint64_t, MessageUniquePtr &)>;
|
||||||
using MatchesAnyPublishersCallbackType = std::function<bool(const rmw_gid_t *)>;
|
using MatchesAnyPublishersCallbackType = std::function<bool(const rmw_gid_t *)>;
|
||||||
|
|
||||||
/// Implemenation detail.
|
/// Implemenation detail.
|
||||||
|
|
|
@ -47,19 +47,19 @@ struct SubscriptionFactory
|
||||||
{
|
{
|
||||||
// Creates a Subscription<MessageT> object and returns it as a SubscriptionBase.
|
// Creates a Subscription<MessageT> object and returns it as a SubscriptionBase.
|
||||||
using SubscriptionFactoryFunction = std::function<
|
using SubscriptionFactoryFunction = std::function<
|
||||||
rclcpp::SubscriptionBase::SharedPtr(
|
rclcpp::SubscriptionBase::SharedPtr(
|
||||||
rclcpp::node_interfaces::NodeBaseInterface * node_base,
|
rclcpp::node_interfaces::NodeBaseInterface * node_base,
|
||||||
const std::string & topic_name,
|
const std::string & topic_name,
|
||||||
rcl_subscription_options_t & subscription_options)>;
|
rcl_subscription_options_t & subscription_options)>;
|
||||||
|
|
||||||
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<
|
using SetupIntraProcessFunction = std::function<
|
||||||
void(
|
void(
|
||||||
rclcpp::intra_process_manager::IntraProcessManager::SharedPtr ipm,
|
rclcpp::intra_process_manager::IntraProcessManager::SharedPtr ipm,
|
||||||
rclcpp::SubscriptionBase::SharedPtr subscription,
|
rclcpp::SubscriptionBase::SharedPtr subscription,
|
||||||
const rcl_subscription_options_t & subscription_options)>;
|
const rcl_subscription_options_t & subscription_options)>;
|
||||||
|
|
||||||
SetupIntraProcessFunction setup_intra_process;
|
SetupIntraProcessFunction setup_intra_process;
|
||||||
};
|
};
|
||||||
|
|
|
@ -603,7 +603,7 @@ rclcpp::executor::operator<<(std::ostream & os, const FutureReturnCode & future_
|
||||||
}
|
}
|
||||||
|
|
||||||
std::string
|
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;
|
using enum_type = std::underlying_type<FutureReturnCode>::type;
|
||||||
std::string prefix = "Unknown enum value (";
|
std::string prefix = "Unknown enum value (";
|
||||||
|
|
|
@ -227,7 +227,7 @@ ParameterVariant::value_to_string() const
|
||||||
}
|
}
|
||||||
|
|
||||||
std::string
|
std::string
|
||||||
rclcpp::parameter::_to_json_dict_entry(const ParameterVariant & param)
|
rclcpp::parameter::_to_json_dict_entry(const ParameterVariant ¶m)
|
||||||
{
|
{
|
||||||
std::stringstream ss;
|
std::stringstream ss;
|
||||||
ss << "\"" << param.get_name() << "\": ";
|
ss << "\"" << param.get_name() << "\": ";
|
||||||
|
|
|
@ -409,9 +409,9 @@ public:
|
||||||
using ChangeStateSrvPtr = std::shared_ptr<rclcpp::Service<ChangeStateSrv>>;
|
using ChangeStateSrvPtr = std::shared_ptr<rclcpp::Service<ChangeStateSrv>>;
|
||||||
using GetStateSrvPtr = std::shared_ptr<rclcpp::Service<GetStateSrv>>;
|
using GetStateSrvPtr = std::shared_ptr<rclcpp::Service<GetStateSrv>>;
|
||||||
using GetAvailableStatesSrvPtr =
|
using GetAvailableStatesSrvPtr =
|
||||||
std::shared_ptr<rclcpp::Service<GetAvailableStatesSrv>>;
|
std::shared_ptr<rclcpp::Service<GetAvailableStatesSrv>>;
|
||||||
using GetAvailableTransitionsSrvPtr =
|
using GetAvailableTransitionsSrvPtr =
|
||||||
std::shared_ptr<rclcpp::Service<GetAvailableTransitionsSrv>>;
|
std::shared_ptr<rclcpp::Service<GetAvailableTransitionsSrv>>;
|
||||||
|
|
||||||
NodeBasePtr node_base_interface_;
|
NodeBasePtr node_base_interface_;
|
||||||
NodeServicesPtr node_services_interface_;
|
NodeServicesPtr node_services_interface_;
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue