rclcpp_lifecycle
master
C++ ROS Lifecycle Library API
|
Go to the documentation of this file.
15 #ifndef RCLCPP_LIFECYCLE__LIFECYCLE_NODE_IMPL_HPP_
16 #define RCLCPP_LIFECYCLE__LIFECYCLE_NODE_IMPL_HPP_
44 template<
typename MessageT,
typename AllocatorT>
52 return rclcpp::create_publisher<MessageT, AllocatorT, PublisherT>(
64 typename CallbackMessageT,
65 typename SubscriptionT,
66 typename MessageMemoryStrategyT>
71 CallbackT && callback,
73 typename MessageMemoryStrategyT::SharedPtr msg_mem_strat)
75 return rclcpp::create_subscription<MessageT>(
79 std::forward<CallbackT>(callback),
84 template<
typename DurationRepT,
typename DurationT,
typename CallbackT>
89 rclcpp::CallbackGroup::SharedPtr group)
92 std::chrono::duration_cast<std::chrono::nanoseconds>(period),
93 std::move(callback), this->node_base_->get_context());
94 node_timers_->add_timer(timer, group);
98 template<
typename ServiceT>
103 rclcpp::CallbackGroup::SharedPtr group)
105 rcl_client_options_t options = rcl_client_get_default_options();
106 options.qos = qos_profile;
111 auto cli = Client<ServiceT>::make_shared(
117 auto cli_base_ptr = std::dynamic_pointer_cast<ClientBase>(cli);
118 node_services_->add_client(cli_base_ptr, group);
122 template<
typename ServiceT,
typename CallbackT>
126 CallbackT && callback,
128 rclcpp::CallbackGroup::SharedPtr group)
130 return rclcpp::create_service<ServiceT, CallbackT>(
131 node_base_, node_services_,
132 service_name, std::forward<CallbackT>(callback), qos_profile, group);
135 template<
typename AllocatorT>
154 template<
typename AllocatorT>
175 template<
typename ParameterT>
179 const ParameterT & default_value,
180 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
181 bool ignore_override)
186 parameter_descriptor,
191 template<
typename ParameterT>
195 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
196 bool ignore_override)
204 parameter_descriptor,
209 template<
typename ParameterT>
216 std::string normalized_namespace = namespace_.
empty() ?
"" : (namespace_ +
".");
219 [
this, &normalized_namespace](
auto element) {
220 return this->declare_parameter(normalized_namespace + element.first, element.second);
226 template<
typename ParameterT>
236 std::string normalized_namespace = namespace_.
empty() ?
"" : (namespace_ +
".");
239 [
this, &normalized_namespace](
auto element) {
240 return static_cast<ParameterT>(
241 this->declare_parameter(
242 normalized_namespace + element.first,
243 element.second.first,
244 element.second.second)
251 template<
typename ParameterT>
257 parameter = param.
get_value<ParameterT>();
265 template<
typename MapValueT>
272 bool result = node_parameters_->get_parameters_by_prefix(prefix, params);
274 for (
const auto & param : params) {
275 values[param.first] = param.second.get_value<MapValueT>();
282 template<
typename ParameterT>
287 const ParameterT & alternative_value)
const
290 if (!got_parameter) {
291 value = alternative_value;
293 return got_parameter;
297 #endif // RCLCPP_LIFECYCLE__LIFECYCLE_NODE_IMPL_HPP_
std::shared_ptr< GenericPublisher > create_generic_publisher(rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr topics_interface, const std::string &topic_name, const std::string &topic_type, const rclcpp::QoS &qos, const rclcpp::PublisherOptionsWithAllocator< AllocatorT > &options=(rclcpp::PublisherOptionsWithAllocator< AllocatorT >()))
std::vector< ParameterT > declare_parameters(const std::string &namespace_, const std::map< std::string, ParameterT > ¶meters)
Declare and initialize several parameters with the same namespace and type.
Definition: lifecycle_node_impl.hpp:211
constexpr std::enable_if< type==ParameterType::PARAMETER_BOOL, const bool & >::type get() const
T back_inserter(T... args)
decltype(auto) get_value() const
rclcpp::Parameter get_parameter(const std::string &name) const
Return the parameter by the given name.
std::shared_ptr< rclcpp::GenericPublisher > create_generic_publisher(const std::string &topic_name, const std::string &topic_type, const rclcpp::QoS &qos, const rclcpp::PublisherOptionsWithAllocator< AllocatorT > &options=(rclcpp::PublisherOptionsWithAllocator< AllocatorT >()))
Create and return a GenericPublisher.
Definition: lifecycle_node_impl.hpp:137
std::shared_ptr< rclcpp_lifecycle::LifecyclePublisher< MessageT, AllocatorT > > create_publisher(const std::string &topic_name, const rclcpp::QoS &qos, const PublisherOptionsWithAllocator< AllocatorT > &options=(create_default_publisher_options< AllocatorT >()))
Create and return a Publisher.
Definition: lifecycle_node_impl.hpp:46
rclcpp::WallTimer< CallbackT >::SharedPtr create_wall_timer(std::chrono::duration< DurationRepT, DurationT > period, CallbackT callback, rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create a timer.
Definition: lifecycle_node_impl.hpp:86
Definition: lifecycle_node.hpp:92
std::shared_ptr< SubscriptionT > create_subscription(const std::string &topic_name, const rclcpp::QoS &qos, CallbackT &&callback, const SubscriptionOptionsWithAllocator< AllocatorT > &options=create_default_subscription_options< AllocatorT >(), typename MessageMemoryStrategyT::SharedPtr msg_mem_strat=(MessageMemoryStrategyT::create_default()))
Create and return a Subscription.
rclcpp::Service< ServiceT >::SharedPtr create_service(const std::string &service_name, CallbackT &&callback, const rmw_qos_profile_t &qos_profile=rmw_qos_profile_services_default, rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create and return a Service.
Definition: lifecycle_node_impl.hpp:124
const rclcpp::ParameterValue & declare_parameter(const std::string &name, const rclcpp::ParameterValue &default_value, const rcl_interfaces::msg::ParameterDescriptor ¶meter_descriptor=rcl_interfaces::msg::ParameterDescriptor(), bool ignore_override=false)
Declare and initialize a parameter, return the effective value.
std::shared_ptr< rclcpp::GenericSubscription > create_generic_subscription(const std::string &topic_name, const std::string &topic_type, const rclcpp::QoS &qos, std::function< void(std::shared_ptr< rclcpp::SerializedMessage >)> callback, const rclcpp::SubscriptionOptionsWithAllocator< AllocatorT > &options=(rclcpp::SubscriptionOptionsWithAllocator< AllocatorT >()))
Create and return a GenericSubscription.
Definition: lifecycle_node_impl.hpp:156
rclcpp::Client< ServiceT >::SharedPtr create_client(const std::string &service_name, const rmw_qos_profile_t &qos_profile=rmw_qos_profile_services_default, rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create and return a Client.
Definition: lifecycle_node_impl.hpp:100
std::vector< rclcpp::Parameter > get_parameters(const std::vector< std::string > &names) const
Return the parameters by the given parameter names.
bool get_parameter_or(const std::string &name, ParameterT &value, const ParameterT &alternative_value) const
Get the parameter value, or the "alternative_value" if not set, and assign it to "parameter".
Definition: lifecycle_node_impl.hpp:284
std::shared_ptr< GenericSubscription > create_generic_subscription(rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr topics_interface, const std::string &topic_name, const std::string &topic_type, const rclcpp::QoS &qos, std::function< void(std::shared_ptr< rclcpp::SerializedMessage >)> callback, const rclcpp::SubscriptionOptionsWithAllocator< AllocatorT > &options=(rclcpp::SubscriptionOptionsWithAllocator< AllocatorT >()))
brief child class of rclcpp Publisher class.
Definition: lifecycle_publisher.hpp:50