Program Listing for File transaction.hpp
↰ Return to documentation for file (/tmp/ws/src/fuse/fuse_core/include/fuse_core/transaction.hpp
)
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2018, Locus Robotics
* All rights reserved.
*
* 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 copyright holder 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.
*/
#ifndef FUSE_CORE__TRANSACTION_HPP_
#define FUSE_CORE__TRANSACTION_HPP_
#include <iostream>
#include <ostream>
#include <set>
#include <vector>
#include <boost/archive/binary_oarchive.hpp>
#include <boost/range/any_range.hpp>
#include <boost/serialization/access.hpp>
#include <boost/serialization/set.hpp>
#include <boost/serialization/shared_ptr.hpp>
#include <boost/serialization/vector.hpp>
#include <fuse_core/constraint.hpp>
#include <fuse_core/fuse_macros.hpp>
#include <fuse_core/serialization.hpp>
#include <fuse_core/uuid.hpp>
#include <fuse_core/variable.hpp>
namespace fuse_core
{
class Transaction
{
public:
FUSE_SMART_PTR_DEFINITIONS(Transaction)
using const_constraint_range = boost::any_range<const Constraint, boost::forward_traversal_tag>;
using const_stamp_range = boost::any_range<const rclcpp::Time, boost::forward_traversal_tag>;
using const_uuid_range = boost::any_range<const UUID, boost::forward_traversal_tag>;
using const_variable_range = boost::any_range<const Variable, boost::forward_traversal_tag>;
const rclcpp::Time & stamp() const {return stamp_;}
void stamp(const rclcpp::Time & stamp) {stamp_ = stamp;}
const_stamp_range involvedStamps() const {return involved_stamps_;}
const rclcpp::Time & minStamp() const;
const rclcpp::Time & maxStamp() const;
const_constraint_range addedConstraints() const;
const_uuid_range removedConstraints() const {return removed_constraints_;}
const_variable_range addedVariables() const;
const_uuid_range removedVariables() const {return removed_variables_;}
bool empty() const;
void addInvolvedStamp(const rclcpp::Time & stamp);
void addConstraint(Constraint::SharedPtr constraint, bool overwrite = false);
void removeConstraint(const UUID & constraint_uuid);
void addVariable(Variable::SharedPtr variable, bool overwrite = false);
void removeVariable(const UUID & variable_uuid);
void merge(const Transaction & other, bool overwrite = false);
void print(std::ostream & stream = std::cout) const;
Transaction::UniquePtr clone() const;
void serialize(fuse_core::BinaryOutputArchive & /* archive */) const;
void serialize(fuse_core::TextOutputArchive & /* archive */) const;
void deserialize(fuse_core::BinaryInputArchive & /* archive */);
void deserialize(fuse_core::TextInputArchive & /* archive */);
private:
rclcpp::Time stamp_{0, 0, RCL_ROS_TIME};
std::vector<Constraint::SharedPtr> added_constraints_;
std::vector<Variable::SharedPtr> added_variables_;
std::set<rclcpp::Time> involved_stamps_;
std::vector<UUID> removed_constraints_;
std::vector<UUID> removed_variables_;
// Allow Boost Serialization access to private methods
friend class boost::serialization::access;
template<class Archive>
void serialize(Archive & archive, const unsigned int /* version */)
{
archive & stamp_;
archive & added_constraints_;
archive & added_variables_;
archive & involved_stamps_;
archive & removed_constraints_;
archive & removed_variables_;
}
};
std::ostream & operator<<(std::ostream & stream, const Transaction & transaction);
} // namespace fuse_core
#endif // FUSE_CORE__TRANSACTION_HPP_