Program Listing for File constraint.hpp

Return to documentation for file (/tmp/ws/src/fuse/fuse_core/include/fuse_core/constraint.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__CONSTRAINT_HPP_
#define FUSE_CORE__CONSTRAINT_HPP_

#include <ceres/cost_function.h>
#include <ceres/loss_function.h>

#include <initializer_list>
#include <iostream>
#include <memory>
#include <ostream>
#include <string>
#include <utility>
#include <vector>

#include <boost/serialization/access.hpp>
#include <boost/serialization/vector.hpp>
#include <boost/type_index/stl_type_index.hpp>
#include <fuse_core/fuse_macros.hpp>
#include <fuse_core/loss.hpp>
#include <fuse_core/serialization.hpp>
#include <fuse_core/uuid.hpp>

#define FUSE_CONSTRAINT_CLONE_DEFINITION(...) \
  fuse_core::Constraint::UniquePtr clone() const override \
  { \
    return __VA_ARGS__::make_unique(*this); \
  }

#define FUSE_CONSTRAINT_SERIALIZE_DEFINITION(...) \
  void serialize(fuse_core::BinaryOutputArchive & archive) const override \
  { \
    archive << *this; \
  }  /* NOLINT */ \
  void serialize(fuse_core::TextOutputArchive & archive) const override \
  { \
    archive << *this; \
  }  /* NOLINT */ \
  void deserialize(fuse_core::BinaryInputArchive & archive) override \
  { \
    archive >> *this; \
  }  /* NOLINT */ \
  void deserialize(fuse_core::TextInputArchive & archive) override \
  { \
    archive >> *this; \
  }

#define FUSE_CONSTRAINT_TYPE_DEFINITION(...) \
  struct detail \
  { \
    static std::string type() \
    { \
      return boost::typeindex::stl_type_index::type_id<__VA_ARGS__>().pretty_name(); \
    }  /* NOLINT */ \
  };  /* NOLINT */ \
  std::string type() const override \
  { \
    return detail::type(); \
  }

#define FUSE_CONSTRAINT_DEFINITIONS(...) \
  FUSE_SMART_PTR_DEFINITIONS(__VA_ARGS__) \
  FUSE_CONSTRAINT_TYPE_DEFINITION(__VA_ARGS__) \
  FUSE_CONSTRAINT_CLONE_DEFINITION(__VA_ARGS__) \
  FUSE_CONSTRAINT_SERIALIZE_DEFINITION(__VA_ARGS__)

#define FUSE_CONSTRAINT_DEFINITIONS_WITH_EIGEN(...) \
  FUSE_SMART_PTR_DEFINITIONS_WITH_EIGEN(__VA_ARGS__) \
  FUSE_CONSTRAINT_TYPE_DEFINITION(__VA_ARGS__) \
  FUSE_CONSTRAINT_CLONE_DEFINITION(__VA_ARGS__) \
  FUSE_CONSTRAINT_SERIALIZE_DEFINITION(__VA_ARGS__)


namespace fuse_core
{

class Constraint
{
public:
  FUSE_SMART_PTR_ALIASES_ONLY(Constraint)


  Constraint() = default;

  Constraint(const std::string & source, std::initializer_list<UUID> variable_uuid_list);

  template<typename VariableUuidIterator>
  Constraint(const std::string & source, VariableUuidIterator first, VariableUuidIterator last);

  virtual ~Constraint() = default;

  virtual std::string type() const = 0;

  const UUID & uuid() const {return uuid_;}

  const std::string & source() const {return source_;}

  virtual void print(std::ostream & stream = std::cout) const = 0;

  virtual ceres::CostFunction * costFunction() const = 0;

  Loss::SharedPtr loss() const
  {
    return loss_;
  }

  void loss(Loss::SharedPtr loss)
  {
    loss_ = std::move(loss);
  }

  ceres::LossFunction * lossFunction() const
  {
    return loss_ ? loss_->lossFunction() : nullptr;
  }

  virtual Constraint::UniquePtr clone() const = 0;

  const std::vector<UUID> & variables() const {return variables_;}

  virtual void serialize(fuse_core::BinaryOutputArchive & /* archive */) const = 0;

  virtual void serialize(fuse_core::TextOutputArchive & /* archive */) const = 0;

  virtual void deserialize(fuse_core::BinaryInputArchive & /* archive */) = 0;

  virtual void deserialize(fuse_core::TextInputArchive & /* archive */) = 0;

private:
  std::string source_;
  UUID uuid_;
  std::vector<UUID> variables_;
  std::shared_ptr<Loss> loss_{nullptr};

  // Allow Boost Serialization access to private methods
  friend class boost::serialization::access;

  template<class Archive>
  void serialize(Archive & archive, const unsigned int /* version */)
  {
    archive & source_;
    archive & uuid_;
    archive & variables_;
    archive & loss_;
  }
};

std::ostream & operator<<(std::ostream & stream, const Constraint & constraint);


template<typename VariableUuidIterator>
Constraint::Constraint(
  const std::string & source, VariableUuidIterator first,
  VariableUuidIterator last)
: source_(source),
  uuid_(uuid::generate()),
  variables_(first, last)
{
}

}  // namespace fuse_core

#endif  // FUSE_CORE__CONSTRAINT_HPP_