Program Listing for File graph.hpp

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

#include <ceres/covariance.h>
#include <ceres/problem.h>
#include <ceres/solver.h>

#include <memory>
#include <numeric>
#include <ostream>
#include <string>
#include <utility>
#include <vector>

#include <boost/core/demangle.hpp>
#include <boost/range/any_range.hpp>
#include <boost/serialization/access.hpp>
#include <boost/type_index/stl_type_index.hpp>
#include <fuse_core/constraint.hpp>
#include <fuse_core/fuse_macros.hpp>
#include <fuse_core/serialization.hpp>
#include <fuse_core/transaction.hpp>
#include <fuse_core/uuid.hpp>
#include <fuse_core/variable.hpp>
#include <rclcpp/duration.hpp>

#define FUSE_GRAPH_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_GRAPH_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_GRAPH_DEFINITIONS(...) \
  FUSE_SMART_PTR_DEFINITIONS(__VA_ARGS__) \
  FUSE_GRAPH_TYPE_DEFINITION(__VA_ARGS__) \
  FUSE_GRAPH_SERIALIZE_DEFINITION(__VA_ARGS__)


namespace fuse_core
{

class Graph
{
public:
  FUSE_SMART_PTR_ALIASES_ONLY(Graph)


  using const_constraint_range = boost::any_range<const Constraint, boost::forward_traversal_tag>;

  using const_variable_range = boost::any_range<const Variable, boost::forward_traversal_tag>;

  Graph() = default;

  virtual ~Graph() = default;

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

  virtual void clear() = 0;

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

  virtual bool constraintExists(const UUID & constraint_uuid) const = 0;

  virtual bool addConstraint(Constraint::SharedPtr constraint) = 0;

  virtual bool removeConstraint(const UUID & constraint_uuid) = 0;

  virtual const Constraint & getConstraint(const UUID & constraint_uuid) const = 0;

  virtual const_constraint_range getConstraints() const = 0;

  virtual const_constraint_range getConnectedConstraints(const UUID & variable_uuid) const = 0;

  virtual bool variableExists(const UUID & variable_uuid) const = 0;

  virtual bool addVariable(Variable::SharedPtr variable) = 0;

  virtual bool removeVariable(const UUID & variable_uuid) = 0;

  virtual const Variable & getVariable(const UUID & variable_uuid) const = 0;

  virtual const_variable_range getVariables() const = 0;

  virtual const_variable_range getConnectedVariables(const UUID & constraint_uuid) const;

  virtual void holdVariable(const UUID & variable_uuid, bool hold_constant = true) = 0;

  virtual bool isVariableOnHold(const UUID & variable_uuid) const = 0;

  virtual void getCovariance(
    const std::vector<std::pair<UUID, UUID>> & covariance_requests,
    std::vector<std::vector<double>> & covariance_matrices,
    const ceres::Covariance::Options & options = ceres::Covariance::Options(),
    const bool use_tangent_space = true) const = 0;

  void update(const Transaction & transaction);

  virtual ceres::Solver::Summary optimize(
    const ceres::Solver::Options & options = ceres::Solver::Options()) = 0;

  virtual ceres::Solver::Summary optimizeFor(
    const rclcpp::Duration & max_optimization_time,
    const ceres::Solver::Options & options = ceres::Solver::Options(),
    rclcpp::Clock clock = rclcpp::Clock(RCL_STEADY_TIME)) = 0;  // NOTE(CH3): We need to copy
                                                                // because clock.now() is non-const

  virtual bool evaluate(
    double * cost, std::vector<double> * residuals = nullptr,
    std::vector<double> * gradient = nullptr,
    const ceres::Problem::EvaluateOptions & options = ceres::Problem::EvaluateOptions()) const = 0;

  struct ConstraintCost
  {
    double cost {};
    double loss {};
    std::vector<double> residuals;
  };

  template<class UuidForwardIterator, class OutputIterator>
  void getConstraintCosts(
    UuidForwardIterator first,
    UuidForwardIterator last,
    OutputIterator output);

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

  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:
  // Allow Boost Serialization access to private methods
  friend class boost::serialization::access;

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

std::ostream & operator<<(std::ostream & stream, const Graph & graph);


template<class UuidForwardIterator, class OutputIterator>
void Graph::getConstraintCosts(
  UuidForwardIterator first,
  UuidForwardIterator last,
  OutputIterator output)
{
  // @todo(swilliams) When I eventually refactor the Graph class to implement more of the
  //                  requirements in the base class, it should be possible to make better use of
  //                  the Problem object and avoid creating and deleting the cost and loss
  //                  functions.
  while (first != last) {
    // Get the next requested constraint
    const auto & constraint = getConstraint(*first);
    // Collect all of the involved variables
    auto parameter_blocks = std::vector<const double *>();
    parameter_blocks.reserve(constraint.variables().size());
    for (auto variable_uuid : constraint.variables()) {
      const auto & variable = getVariable(variable_uuid);
      parameter_blocks.push_back(variable.data());
    }
    // Compute the residuals for this constraint using the cost function
    auto cost_function = std::unique_ptr<ceres::CostFunction>(constraint.costFunction());
    auto cost = ConstraintCost();
    cost.residuals.resize(cost_function->num_residuals());
    cost_function->Evaluate(parameter_blocks.data(), cost.residuals.data(), nullptr);
    // Compute the combined cost
    cost.cost =
      std::sqrt(
      std::inner_product(
        cost.residuals.begin(), cost.residuals.end(),
        cost.residuals.begin(), 0.0));
    // Apply the loss function, if one is configured
    auto loss_function = std::unique_ptr<ceres::LossFunction>(constraint.lossFunction());
    if (loss_function) {
      double loss_result[3];  // The Loss function returns the loss-adjusted cost plus the first and
                              // second derivative
      loss_function->Evaluate(cost.cost, loss_result);
      cost.loss = loss_result[0];
    } else {
      cost.loss = cost.cost;
    }
    // Add the final cost to the output
    *output++ = std::move(cost);
    ++first;
  }
}

}  // namespace fuse_core

#endif  // FUSE_CORE__GRAPH_HPP_