.. _program_listing_file_include_rclcpp_lifecycle_lifecycle_node_impl.hpp: Program Listing for File lifecycle_node_impl.hpp ================================================ |exhale_lsh| :ref:`Return to documentation for file ` (``include/rclcpp_lifecycle/lifecycle_node_impl.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp // Copyright 2016 Open Source Robotics Foundation, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 // // Unless required by applicable law or agreed to in writing, software // distributed under the License is distributed on an "AS IS" BASIS, // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. #ifndef RCLCPP_LIFECYCLE__LIFECYCLE_NODE_IMPL_HPP_ #define RCLCPP_LIFECYCLE__LIFECYCLE_NODE_IMPL_HPP_ #include #include #include #include #include #include #include #include #include "rcl_interfaces/msg/parameter_descriptor.hpp" #include "rclcpp/callback_group.hpp" #include "rclcpp/create_client.hpp" #include "rclcpp/create_generic_publisher.hpp" #include "rclcpp/create_generic_subscription.hpp" #include "rclcpp/create_publisher.hpp" #include "rclcpp/create_service.hpp" #include "rclcpp/create_subscription.hpp" #include "rclcpp/parameter.hpp" #include "rclcpp/publisher_options.hpp" #include "rclcpp/qos.hpp" #include "rclcpp/subscription_options.hpp" #include "rclcpp/type_support_decl.hpp" #include "rmw/types.h" #include "rclcpp_lifecycle/lifecycle_node.hpp" #include "rclcpp_lifecycle/lifecycle_publisher.hpp" #include "rclcpp_lifecycle/visibility_control.h" namespace rclcpp_lifecycle { template std::shared_ptr> LifecycleNode::create_publisher( const std::string & topic_name, const rclcpp::QoS & qos, const rclcpp::PublisherOptionsWithAllocator & options) { using PublisherT = rclcpp_lifecycle::LifecyclePublisher; auto pub = rclcpp::create_publisher( *this, topic_name, qos, options); this->add_managed_entity(pub); return pub; } // TODO(karsten1987): Create LifecycleSubscriber template< typename MessageT, typename CallbackT, typename AllocatorT, typename SubscriptionT, typename MessageMemoryStrategyT> std::shared_ptr LifecycleNode::create_subscription( const std::string & topic_name, const rclcpp::QoS & qos, CallbackT && callback, const rclcpp::SubscriptionOptionsWithAllocator & options, typename MessageMemoryStrategyT::SharedPtr msg_mem_strat) { return rclcpp::create_subscription( *this, topic_name, qos, std::forward(callback), options, msg_mem_strat); } template typename rclcpp::WallTimer::SharedPtr LifecycleNode::create_wall_timer( std::chrono::duration period, CallbackT callback, rclcpp::CallbackGroup::SharedPtr group) { return rclcpp::create_wall_timer( period, std::move(callback), group, this->node_base_.get(), this->node_timers_.get()); } template typename rclcpp::GenericTimer::SharedPtr LifecycleNode::create_timer( std::chrono::duration period, CallbackT callback, rclcpp::CallbackGroup::SharedPtr group) { return rclcpp::create_timer( this->get_clock(), period, std::move(callback), group, this->node_base_.get(), this->node_timers_.get()); } template typename rclcpp::Client::SharedPtr LifecycleNode::create_client( const std::string & service_name, const rmw_qos_profile_t & qos_profile, rclcpp::CallbackGroup::SharedPtr group) { return rclcpp::create_client( node_base_, node_graph_, node_services_, service_name, qos_profile, group); } template typename rclcpp::Client::SharedPtr LifecycleNode::create_client( const std::string & service_name, const rclcpp::QoS & qos, rclcpp::CallbackGroup::SharedPtr group) { return rclcpp::create_client( node_base_, node_graph_, node_services_, service_name, qos, group); } template typename rclcpp::Service::SharedPtr LifecycleNode::create_service( const std::string & service_name, CallbackT && callback, const rmw_qos_profile_t & qos_profile, rclcpp::CallbackGroup::SharedPtr group) { return rclcpp::create_service( node_base_, node_services_, service_name, std::forward(callback), qos_profile, group); } template typename rclcpp::Service::SharedPtr LifecycleNode::create_service( const std::string & service_name, CallbackT && callback, const rclcpp::QoS & qos, rclcpp::CallbackGroup::SharedPtr group) { return rclcpp::create_service( node_base_, node_services_, service_name, std::forward(callback), qos, group); } template std::shared_ptr LifecycleNode::create_generic_publisher( const std::string & topic_name, const std::string & topic_type, const rclcpp::QoS & qos, const rclcpp::PublisherOptionsWithAllocator & options) { return rclcpp::create_generic_publisher( node_topics_, // TODO(karsten1987): LifecycleNode is currently not supporting subnamespaces // see https://github.com/ros2/rclcpp/issues/1614 topic_name, topic_type, qos, options ); } template std::shared_ptr LifecycleNode::create_generic_subscription( const std::string & topic_name, const std::string & topic_type, const rclcpp::QoS & qos, std::function)> callback, const rclcpp::SubscriptionOptionsWithAllocator & options) { return rclcpp::create_generic_subscription( node_topics_, // TODO(karsten1987): LifecycleNode is currently not supporting subnamespaces // see https://github.com/ros2/rclcpp/issues/1614 topic_name, topic_type, qos, std::move(callback), options ); } template auto LifecycleNode::declare_parameter( const std::string & name, const ParameterT & default_value, const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor, bool ignore_override) { return this->declare_parameter( name, rclcpp::ParameterValue(default_value), parameter_descriptor, ignore_override ).get(); } template auto LifecycleNode::declare_parameter( const std::string & name, const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor, bool ignore_override) { // get advantage of parameter value template magic to get // the correct rclcpp::ParameterType from ParameterT rclcpp::ParameterValue value{ParameterT{}}; return this->declare_parameter( name, value.get_type(), parameter_descriptor, ignore_override ).get(); } template std::vector LifecycleNode::declare_parameters( const std::string & namespace_, const std::map & parameters) { std::vector result; std::string normalized_namespace = namespace_.empty() ? "" : (namespace_ + "."); std::transform( parameters.begin(), parameters.end(), std::back_inserter(result), [this, &normalized_namespace](auto element) { return this->declare_parameter(normalized_namespace + element.first, element.second); } ); return result; } template std::vector LifecycleNode::declare_parameters( const std::string & namespace_, const std::map< std::string, std::pair > & parameters) { std::vector result; std::string normalized_namespace = namespace_.empty() ? "" : (namespace_ + "."); std::transform( parameters.begin(), parameters.end(), std::back_inserter(result), [this, &normalized_namespace](auto element) { return static_cast( this->declare_parameter( normalized_namespace + element.first, element.second.first, element.second.second) ); } ); return result; } template bool LifecycleNode::get_parameter(const std::string & name, ParameterT & parameter) const { rclcpp::Parameter param(name, parameter); bool result = get_parameter(name, param); parameter = param.get_value(); return result; } // this is a partially-specialized version of get_parameter above, // where our concrete type for ParameterT is std::map, but the to-be-determined // type is the value in the map. template bool LifecycleNode::get_parameters( const std::string & prefix, std::map & values) const { std::map params; bool result = node_parameters_->get_parameters_by_prefix(prefix, params); if (result) { for (const auto & param : params) { values[param.first] = param.second.get_value(); } } return result; } template bool LifecycleNode::get_parameter_or( const std::string & name, ParameterT & value, const ParameterT & alternative_value) const { bool got_parameter = get_parameter(name, value); if (!got_parameter) { value = alternative_value; } return got_parameter; } } // namespace rclcpp_lifecycle #endif // RCLCPP_LIFECYCLE__LIFECYCLE_NODE_IMPL_HPP_