Program Listing for File variable_stamp_index.hpp

Return to documentation for file (/tmp/ws/src/fuse/fuse_optimizers/include/fuse_optimizers/variable_stamp_index.hpp)

/*
 * Software License Agreement (BSD License)
 *
 *  Copyright (c) 2019, 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_OPTIMIZERS__VARIABLE_STAMP_INDEX_HPP_
#define FUSE_OPTIMIZERS__VARIABLE_STAMP_INDEX_HPP_

#include <unordered_map>
#include <unordered_set>

#include <fuse_core/fuse_macros.hpp>
#include <fuse_core/transaction.hpp>
#include <fuse_core/uuid.hpp>

#include <rclcpp/time.hpp>


namespace fuse_optimizers
{
class VariableStampIndex
{
public:
  FUSE_SMART_PTR_DEFINITIONS(VariableStampIndex)


  VariableStampIndex() = default;

  virtual ~VariableStampIndex() = default;

  bool empty() const {return variables_.empty() && constraints_.empty();}

  size_t size() const {return variables_.size();}

  void clear()
  {
    stamped_index_.clear();
    variables_.clear();
    constraints_.clear();
  }

  rclcpp::Time currentStamp() const;

  void addNewTransaction(const fuse_core::Transaction & transaction);

  void addMarginalTransaction(const fuse_core::Transaction & transaction);

  template<typename OutputUuidIterator>
  void query(const rclcpp::Time & stamp, OutputUuidIterator result) const
  {
    // First get all of the stamped variables greater than or equal to the input stamp
    std::unordered_set<fuse_core::UUID> recent_variable_uuids;
    for (const auto & variable_stamp_pair : stamped_index_) {
      if (variable_stamp_pair.second >= stamp) {
        recent_variable_uuids.insert(variable_stamp_pair.first);
      }
    }

    // Now find all of the variables connected to the recent variables
    std::unordered_set<fuse_core::UUID> connected_variable_uuids;
    for (const auto & recent_variable_uuid : recent_variable_uuids) {
      // Add the recent variable to ensure connected_variable_uuids is a superset of
      // recent_variable_uuids
      connected_variable_uuids.insert(recent_variable_uuid);

      const auto variables_iter = variables_.find(recent_variable_uuid);
      if (variables_iter != variables_.end()) {
        for (const auto & connected_constraint_uuid : variables_iter->second) {
          const auto constraints_iter = constraints_.find(connected_constraint_uuid);
          if (constraints_iter != constraints_.end()) {
            for (const auto & connected_variable_uuid : constraints_iter->second) {
              connected_variable_uuids.insert(connected_variable_uuid);
            }
          }
        }
      }
    }

    // Return the set of variables that are not connected
    for (const auto & variable : variables_) {
      if (connected_variable_uuids.find(variable.first) == connected_variable_uuids.end()) {
        *result = variable.first;
        ++result;
      }
    }
  }

protected:
  using StampedMap = std::unordered_map<fuse_core::UUID, rclcpp::Time>;
  StampedMap stamped_index_;

  using VariableToConstraintsMap = std::unordered_map<fuse_core::UUID,
      std::unordered_set<fuse_core::UUID>>;
  VariableToConstraintsMap variables_;

  using ConstraintToVariablesMap = std::unordered_map<fuse_core::UUID,
      std::unordered_set<fuse_core::UUID>>;
  ConstraintToVariablesMap constraints_;

  void applyAddedConstraints(const fuse_core::Transaction & transaction);

  void applyAddedVariables(const fuse_core::Transaction & transaction);

  void applyRemovedConstraints(const fuse_core::Transaction & transaction);

  void applyRemovedVariables(const fuse_core::Transaction & transaction);
};

}  // namespace fuse_optimizers

#endif  // FUSE_OPTIMIZERS__VARIABLE_STAMP_INDEX_HPP_