Program Listing for File SubscriberHistory.h

Return to documentation for file (/tmp/ws/src/fastrtps/include/fastrtps/subscriber/SubscriberHistory.h)

// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima).
//
// 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 SUBSCRIBERHISTORY_H_
#define SUBSCRIBERHISTORY_H_
#ifndef DOXYGEN_SHOULD_SKIP_THIS_PUBLIC

#include <fastdds/dds/topic/TopicDataType.hpp>
#include <fastdds/rtps/resources/ResourceManagement.h>
#include <fastrtps/qos/ReaderQos.h>
#include <fastdds/rtps/history/ReaderHistory.h>
#include <fastrtps/qos/QosPolicies.h>
#include <fastrtps/common/KeyedChanges.h>
#include <fastrtps/subscriber/SampleInfo.h>
#include <fastrtps/attributes/TopicAttributes.h>

#include <chrono>
#include <functional>

namespace eprosima {
namespace fastrtps {

class SubscriberHistory : public rtps::ReaderHistory
{
public:

    SubscriberHistory(
            const TopicAttributes& topic_att,
            fastdds::dds::TopicDataType* type,
            const fastrtps::ReaderQos& qos,
            uint32_t payloadMax,
            rtps::MemoryManagementPolicy_t mempolicy);

    ~SubscriberHistory() override;

    iterator remove_change_nts(
            const_iterator removal,
            bool release = true) override;

    bool can_change_be_added_nts(
            const rtps::GUID_t& writer_guid,
            uint32_t total_payload_size,
            size_t unknown_missing_changes_up_to,
            bool& will_never_be_accepted) const override;

    bool received_change(
            rtps::CacheChange_t* change,
            size_t unknown_missing_changes_up_to) override;

    bool completed_change(
            rtps::CacheChange_t* change) override;

    bool readNextData(
            void* data,
            SampleInfo_t* info,
            std::chrono::steady_clock::time_point& max_blocking_time);

    bool takeNextData(
            void* data,
            SampleInfo_t* info,
            std::chrono::steady_clock::time_point& max_blocking_time);

    bool get_first_untaken_info(
            SampleInfo_t* info);

    bool remove_change_sub(
            rtps::CacheChange_t* change);

    bool remove_change_sub(
            rtps::CacheChange_t* change,
            iterator& it);

    bool set_next_deadline(
            const rtps::InstanceHandle_t& handle,
            const std::chrono::steady_clock::time_point& next_deadline_us);

    bool get_next_deadline(
            rtps::InstanceHandle_t& handle,
            std::chrono::steady_clock::time_point& next_deadline_us);

private:

    using t_m_Inst_Caches = std::map<rtps::InstanceHandle_t, KeyedChanges>;

    t_m_Inst_Caches keyed_changes_;
    std::chrono::steady_clock::time_point next_deadline_us_;
    HistoryQosPolicy history_qos_;
    ResourceLimitsQosPolicy resource_limited_qos_;
    TopicAttributes topic_att_;
    fastdds::dds::TopicDataType* type_;
    fastrtps::ReaderQos qos_;

    void* get_key_object_;

    std::function<bool(rtps::CacheChange_t*, size_t)> receive_fn_;

    std::function<bool(rtps::CacheChange_t*)> complete_fn_;

    bool find_key(
            rtps::CacheChange_t* a_change,
            t_m_Inst_Caches::iterator& map_it);

    bool find_key_for_change(
            rtps::CacheChange_t* a_change,
            t_m_Inst_Caches::iterator& map_it);

    bool received_change_keep_all_no_key(
            rtps::CacheChange_t* change,
            size_t unknown_missing_changes_up_to);

    bool received_change_keep_last_no_key(
            rtps::CacheChange_t* change,
            size_t unknown_missing_changes_up_to);

    bool received_change_keep_all_with_key(
            rtps::CacheChange_t* change,
            size_t unknown_missing_changes_up_to);

    bool received_change_keep_last_with_key(
            rtps::CacheChange_t* change,
            size_t unknown_missing_changes_up_to);

    bool completed_change_keep_all_with_key(
            rtps::CacheChange_t* change);

    bool completed_change_keep_last_with_key(
            rtps::CacheChange_t* change);

    bool add_received_change(
            rtps::CacheChange_t* a_change);

    bool add_received_change_with_key(
            rtps::CacheChange_t* a_change,
            std::vector<rtps::CacheChange_t*>& instance_changes);

    bool deserialize_change(
            rtps::CacheChange_t* change,
            uint32_t ownership_strength,
            void* data,
            SampleInfo_t* info);
};

} // namespace fastrtps
} // namespace eprosima

#endif // ifndef DOXYGEN_SHOULD_SKIP_THIS_PUBLIC

#endif /* SUBSCRIBERHISTORY_H_ */