Program Listing for File unicycle_2d_state_kinematic_constraint.hpp

Return to documentation for file (/tmp/ws/src/fuse/fuse_models/include/fuse_models/unicycle_2d_state_kinematic_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_MODELS__UNICYCLE_2D_STATE_KINEMATIC_CONSTRAINT_HPP_
#define FUSE_MODELS__UNICYCLE_2D_STATE_KINEMATIC_CONSTRAINT_HPP_

#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_linear_2d_stamped.hpp>
#include <fuse_variables/orientation_2d_stamped.hpp>
#include <fuse_variables/position_2d_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_models
{

class Unicycle2DStateKinematicConstraint : public fuse_core::Constraint
{
public:
  FUSE_CONSTRAINT_DEFINITIONS_WITH_EIGEN(Unicycle2DStateKinematicConstraint)


  Unicycle2DStateKinematicConstraint() = default;

  Unicycle2DStateKinematicConstraint(
    const std::string & source,
    const fuse_variables::Position2DStamped & position1,
    const fuse_variables::Orientation2DStamped & yaw1,
    const fuse_variables::VelocityLinear2DStamped & linear_velocity1,
    const fuse_variables::VelocityAngular2DStamped & yaw_velocity1,
    const fuse_variables::AccelerationLinear2DStamped & linear_acceleration1,
    const fuse_variables::Position2DStamped & position2,
    const fuse_variables::Orientation2DStamped & yaw2,
    const fuse_variables::VelocityLinear2DStamped & linear_velocity2,
    const fuse_variables::VelocityAngular2DStamped & yaw_velocity2,
    const fuse_variables::AccelerationLinear2DStamped & linear_acceleration2,
    const fuse_core::Matrix8d & covariance);

  virtual ~Unicycle2DStateKinematicConstraint() = default;

  double dt() const {return dt_;}

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

  fuse_core::Matrix8d covariance() const
  {
    return (sqrt_information_.transpose() * sqrt_information_).inverse();
  }

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

  ceres::CostFunction * costFunction() const override;

protected:
  double dt_;
  fuse_core::Matrix8d 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 & dt_;
    archive & sqrt_information_;
  }
};

}  // namespace fuse_models

BOOST_CLASS_EXPORT_KEY(fuse_models::Unicycle2DStateKinematicConstraint);

#endif  // FUSE_MODELS__UNICYCLE_2D_STATE_KINEMATIC_CONSTRAINT_HPP_