Program Listing for File relative_constraint.hpp

Return to documentation for file (/tmp/ws/src/fuse/fuse_constraints/include/fuse_constraints/relative_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_CONSTRAINTS__RELATIVE_CONSTRAINT_HPP_
#define FUSE_CONSTRAINTS__RELATIVE_CONSTRAINT_HPP_

#include <ceres/cost_function.h>

#include <ostream>
#include <string>
#include <vector>

#include <fuse_core/constraint.hpp>
#include <fuse_core/eigen.hpp>
#include <fuse_core/fuse_macros.hpp>
#include <fuse_core/serialization.hpp>
#include <fuse_core/uuid.hpp>
#include <fuse_variables/acceleration_angular_2d_stamped.hpp>
#include <fuse_variables/acceleration_linear_2d_stamped.hpp>
#include <fuse_variables/orientation_2d_stamped.hpp>
#include <fuse_variables/position_2d_stamped.hpp>
#include <fuse_variables/position_3d_stamped.hpp>
#include <fuse_variables/velocity_angular_2d_stamped.hpp>
#include <fuse_variables/velocity_linear_2d_stamped.hpp>

#include <boost/serialization/access.hpp>
#include <boost/serialization/base_object.hpp>
#include <boost/serialization/export.hpp>


namespace fuse_constraints
{

template<class Variable>
class RelativeConstraint : public fuse_core::Constraint
{
public:
  FUSE_CONSTRAINT_DEFINITIONS(RelativeConstraint<Variable>)


  RelativeConstraint() = default;

  RelativeConstraint(
    const std::string & source,
    const Variable & variable1,
    const Variable & variable2,
    const fuse_core::VectorXd & delta,
    const fuse_core::MatrixXd & covariance);

  RelativeConstraint(
    const std::string & source,
    const Variable & variable1,
    const Variable & variable2,
    const fuse_core::VectorXd & delta,
    const fuse_core::MatrixXd & covariance,
    const std::vector<size_t> & indices);

  virtual ~RelativeConstraint() = default;

  const fuse_core::VectorXd & delta() const {return delta_;}

  const fuse_core::MatrixXd & sqrtInformation() const {return sqrt_information_;}

  fuse_core::MatrixXd covariance() const;

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

  ceres::CostFunction * costFunction() const override;

protected:
  fuse_core::VectorXd delta_;
  fuse_core::MatrixXd sqrt_information_;

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

  template<class Archive>
  void serialize(Archive & archive, const unsigned int /* version */)
  {
    archive & boost::serialization::base_object<fuse_core::Constraint>(*this);
    archive & delta_;
    archive & sqrt_information_;
  }
};

// Define unique names for the different variations of the absolute constraint
using RelativeAccelerationAngular2DStampedConstraint =
  RelativeConstraint<fuse_variables::AccelerationAngular2DStamped>;
using RelativeAccelerationLinear2DStampedConstraint =
  RelativeConstraint<fuse_variables::AccelerationLinear2DStamped>;
using RelativeOrientation2DStampedConstraint =
  RelativeConstraint<fuse_variables::Orientation2DStamped>;
using RelativePosition2DStampedConstraint = RelativeConstraint<fuse_variables::Position2DStamped>;
using RelativePosition3DStampedConstraint = RelativeConstraint<fuse_variables::Position3DStamped>;
using RelativeVelocityAngular2DStampedConstraint =
  RelativeConstraint<fuse_variables::VelocityAngular2DStamped>;
using RelativeVelocityLinear2DStampedConstraint =
  RelativeConstraint<fuse_variables::VelocityLinear2DStamped>;
}  // namespace fuse_constraints

// Include the template implementation
#include <fuse_constraints/relative_constraint_impl.hpp>

BOOST_CLASS_EXPORT_KEY(fuse_constraints::RelativeAccelerationAngular2DStampedConstraint);
BOOST_CLASS_EXPORT_KEY(fuse_constraints::RelativeAccelerationLinear2DStampedConstraint);
BOOST_CLASS_EXPORT_KEY(fuse_constraints::RelativeOrientation2DStampedConstraint);
BOOST_CLASS_EXPORT_KEY(fuse_constraints::RelativePosition2DStampedConstraint);
BOOST_CLASS_EXPORT_KEY(fuse_constraints::RelativePosition3DStampedConstraint);
BOOST_CLASS_EXPORT_KEY(fuse_constraints::RelativeVelocityAngular2DStampedConstraint);
BOOST_CLASS_EXPORT_KEY(fuse_constraints::RelativeVelocityLinear2DStampedConstraint);

#endif  // FUSE_CONSTRAINTS__RELATIVE_CONSTRAINT_HPP_