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_
42 template<
typename MessageT,
typename AllocatorT>
50 return rclcpp::create_publisher<MessageT, AllocatorT, PublisherT>(
62 typename CallbackMessageT,
63 typename SubscriptionT,
64 typename MessageMemoryStrategyT>
69 CallbackT && callback,
71 typename MessageMemoryStrategyT::SharedPtr msg_mem_strat)
73 return rclcpp::create_subscription<MessageT>(
77 std::forward<CallbackT>(callback),
82 template<
typename DurationRepT,
typename DurationT,
typename CallbackT>
87 rclcpp::CallbackGroup::SharedPtr group)
90 std::chrono::duration_cast<std::chrono::nanoseconds>(period),
91 std::move(callback), this->node_base_->get_context());
92 node_timers_->add_timer(timer, group);
96 template<
typename ServiceT>
101 rclcpp::CallbackGroup::SharedPtr group)
103 rcl_client_options_t options = rcl_client_get_default_options();
104 options.qos = qos_profile;
109 auto cli = Client<ServiceT>::make_shared(
115 auto cli_base_ptr = std::dynamic_pointer_cast<ClientBase>(cli);
116 node_services_->add_client(cli_base_ptr, group);
120 template<
typename ServiceT,
typename CallbackT>
124 CallbackT && callback,
126 rclcpp::CallbackGroup::SharedPtr group)
128 return rclcpp::create_service<ServiceT, CallbackT>(
129 node_base_, node_services_,
130 service_name, std::forward<CallbackT>(callback), qos_profile, group);
133 template<
typename ParameterT>
137 const ParameterT & default_value,
138 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor)
147 template<
typename ParameterT>
154 std::string normalized_namespace = namespace_.
empty() ?
"" : (namespace_ +
".");
157 [
this, &normalized_namespace](
auto element) {
158 return this->declare_parameter(normalized_namespace + element.first, element.second);
164 template<
typename ParameterT>
174 std::string normalized_namespace = namespace_.
empty() ?
"" : (namespace_ +
".");
177 [
this, &normalized_namespace](
auto element) {
178 return static_cast<ParameterT>(
179 this->declare_parameter(
180 normalized_namespace + element.first,
181 element.second.first,
182 element.second.second)
189 template<
typename ParameterT>
195 parameter = param.
get_value<ParameterT>();
203 template<
typename MapValueT>
210 bool result = node_parameters_->get_parameters_by_prefix(prefix, params);
212 for (
const auto & param : params) {
213 values[param.first] = param.second.get_value<MapValueT>();
220 template<
typename ParameterT>
225 const ParameterT & alternative_value)
const
228 if (!got_parameter) {
229 value = alternative_value;
231 return got_parameter;
235 #endif // RCLCPP_LIFECYCLE__LIFECYCLE_NODE_IMPL_HPP_
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:149
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_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:44
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:84
Definition: lifecycle_node.hpp:90
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:122
const rclcpp::ParameterValue & declare_parameter(const std::string &name, const rclcpp::ParameterValue &default_value=rclcpp::ParameterValue(), const rcl_interfaces::msg::ParameterDescriptor ¶meter_descriptor=rcl_interfaces::msg::ParameterDescriptor())
Declare and initialize a parameter, return the effective value.
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:98
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:222
brief child class of rclcpp Publisher class.
Definition: lifecycle_publisher.hpp:50