.. _program_listing_file__tmp_ws_src_twist_mux_include_twist_mux_topic_handle.hpp: Program Listing for File topic_handle.hpp ========================================= |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/twist_mux/include/twist_mux/topic_handle.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp // Copyright 2020 PAL Robotics S.L. // // Redistribution and use in source and binary forms, with or without // modification, are permitted provided that the following conditions are met: // // * Redistributions of source code must retain the above copyright // notice, this list of conditions and the following disclaimer. // // * Redistributions in binary form must reproduce the above copyright // notice, this list of conditions and the following disclaimer in the // documentation and/or other materials provided with the distribution. // // * Neither the name of the PAL Robotics S.L. nor the names of its // contributors may be used to endorse or promote products derived from // this software without specific prior written permission. // // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE // POSSIBILITY OF SUCH DAMAGE. /* * @author Enrique Fernandez * @author Siegfried Gevatter * @author Jeremie Deray * @author Brighten Lee */ #ifndef TWIST_MUX__TOPIC_HANDLE_HPP_ #define TWIST_MUX__TOPIC_HANDLE_HPP_ #include #include #include #include #include #include #include #include namespace twist_mux { template class TopicHandle_ { public: // Not copy constructible TopicHandle_(TopicHandle_ &) = delete; TopicHandle_(const TopicHandle_ &) = delete; // Not copy assignable TopicHandle_ & operator=(TopicHandle_ &) = delete; TopicHandle_ & operator=(const TopicHandle_ &) = delete; typedef int priority_type; TopicHandle_( const std::string & name, const std::string & topic, const rclcpp::Duration & timeout, priority_type priority, TwistMux * mux) : name_(name), topic_(topic), timeout_(timeout), priority_(clamp(priority, priority_type(0), priority_type(255))), mux_(mux), stamp_(0) { RCLCPP_INFO( mux_->get_logger(), "Topic handler '%s' subscribed to topic '%s': timeout = %s , priority = %d.", name_.c_str(), topic_.c_str(), ((timeout_.seconds() > 0) ? std::to_string(timeout_.seconds()) + "s" : "None").c_str(), static_cast(priority_)); } virtual ~TopicHandle_() = default; bool hasExpired() const { return (timeout_.seconds() > 0.0) && ( (mux_->now().seconds() - stamp_.seconds()) > timeout_.seconds()); } const std::string & getName() const { return name_; } const std::string & getTopic() const { return topic_; } const rclcpp::Duration & getTimeout() const { return timeout_; } const priority_type & getPriority() const { return priority_; } const T & getStamp() const { return stamp_; } const T & getMessage() const { return msg_; } protected: std::string name_; std::string topic_; typename rclcpp::Subscription::SharedPtr subscriber_; rclcpp::Duration timeout_; priority_type priority_; protected: TwistMux * mux_; rclcpp::Time stamp_; T msg_; }; class VelocityTopicHandle : public TopicHandle_ { private: typedef TopicHandle_ base_type; // https://index.ros.org/doc/ros2/About-Quality-of-Service-Settings // rmw_qos_profile_t twist_qos_profile = rmw_qos_profile_sensor_data; public: typedef typename base_type::priority_type priority_type; VelocityTopicHandle( const std::string & name, const std::string & topic, const rclcpp::Duration & timeout, priority_type priority, TwistMux * mux) : base_type(name, topic, timeout, priority, mux) { subscriber_ = mux_->create_subscription( topic_, rclcpp::SystemDefaultsQoS(), std::bind(&VelocityTopicHandle::callback, this, std::placeholders::_1)); // subscriber_ = nh_.create_subscription( // topic_, twist_qos_profile, // std::bind(&VelocityTopicHandle::callback, this, std::placeholders::_1)); } bool isMasked(priority_type lock_priority) const { // std::cout << hasExpired() << " / " << (getPriority() < lock_priority) << std::endl; return hasExpired() || (getPriority() < lock_priority); } void callback(const geometry_msgs::msg::Twist::ConstSharedPtr msg) { stamp_ = mux_->now(); msg_ = *msg; // Check if this twist has priority. // Note that we have to check all the locks because they might time out // and since we have several topics we must look for the highest one in // all the topic list; so far there's no O(1) solution. if (mux_->hasPriority(*this)) { mux_->publishTwist(msg); } } }; class LockTopicHandle : public TopicHandle_ { private: typedef TopicHandle_ base_type; // https://index.ros.org/doc/ros2/About-Quality-of-Service-Settings // rmw_qos_profile_t lock_qos_profile = rmw_qos_profile_sensor_data; public: typedef typename base_type::priority_type priority_type; LockTopicHandle( const std::string & name, const std::string & topic, const rclcpp::Duration & timeout, priority_type priority, TwistMux * mux) : base_type(name, topic, timeout, priority, mux) { subscriber_ = mux_->create_subscription( topic_, rclcpp::SystemDefaultsQoS(), std::bind(&LockTopicHandle::callback, this, std::placeholders::_1)); } bool isLocked() const { return hasExpired() || getMessage().data; } void callback(const std_msgs::msg::Bool::ConstSharedPtr msg) { stamp_ = mux_->now(); msg_ = *msg; } }; } // namespace twist_mux #endif // TWIST_MUX__TOPIC_HANDLE_HPP_