2020-06-20 06:46:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/**
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 *  @file   PoseToPointFactor.hpp
							 | 
						
					
						
							
								
									
										
										
										
											2021-12-08 12:45:28 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								 *  @brief  This factor can be used to model relative position measurements
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 *  from a (2D or 3D) pose to a landmark
							 | 
						
					
						
							
								
									
										
										
										
											2020-06-20 06:46:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 *  @author David Wisth
							 | 
						
					
						
							
								
									
										
										
										
											2021-12-08 12:45:28 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								 *  @author Luca Carlone
							 | 
						
					
						
							
								
									
										
										
										
											2020-06-20 06:46:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 **/
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#pragma once
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2021-12-08 12:45:28 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/geometry/Point2.h>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/geometry/Pose2.h>
							 | 
						
					
						
							
								
									
										
										
										
											2020-06-20 06:46:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/geometry/Point3.h>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/geometry/Pose3.h>
							 | 
						
					
						
							
								
									
										
										
										
											2020-06-20 07:45:24 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/nonlinear/NonlinearFactor.h>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <ostream>
							 | 
						
					
						
							
								
									
										
										
										
											2020-06-20 06:46:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								namespace gtsam {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/**
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * A class for a measurement between a pose and a point.
							 | 
						
					
						
							
								
									
										
										
										
											2022-07-23 19:04:42 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								 * @ingroup SLAM
							 | 
						
					
						
							
								
									
										
										
										
											2020-06-20 06:46:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 */
							 | 
						
					
						
							
								
									
										
										
										
											2021-12-08 12:45:28 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								template<typename POSE = Pose3, typename POINT = Point3>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								class PoseToPointFactor : public NoiseModelFactor2<POSE, POINT> {
							 | 
						
					
						
							
								
									
										
										
										
											2020-06-20 07:45:24 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								 private:
							 | 
						
					
						
							
								
									
										
										
										
											2020-06-20 06:46:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  typedef PoseToPointFactor This;
							 | 
						
					
						
							
								
									
										
										
										
											2021-12-08 12:45:28 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  typedef NoiseModelFactor2<POSE, POINT> Base;
							 | 
						
					
						
							
								
									
										
										
										
											2020-06-20 06:46:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2021-12-08 12:45:28 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  POINT measured_; /** the point measurement in local coordinates */
							 | 
						
					
						
							
								
									
										
										
										
											2020-06-20 06:46:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2020-06-20 07:45:24 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								 public:
							 | 
						
					
						
							
								
									
										
										
										
											2020-06-20 06:46:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // shorthand for a smart pointer to a factor
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  typedef boost::shared_ptr<PoseToPointFactor> shared_ptr;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /** default constructor - only use for serialization */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  PoseToPointFactor() {}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /** Constructor */
							 | 
						
					
						
							
								
									
										
										
										
											2021-12-08 12:45:28 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  PoseToPointFactor(Key key1, Key key2, const POINT& measured,
							 | 
						
					
						
							
								
									
										
										
										
											2020-06-20 07:45:24 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								                    const SharedNoiseModel& model)
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      : Base(model, key1, key2), measured_(measured) {}
							 | 
						
					
						
							
								
									
										
										
										
											2020-06-20 06:46:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  virtual ~PoseToPointFactor() {}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /** implement functions needed for Testable */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /** print */
							 | 
						
					
						
							
								
									
										
										
										
											2021-12-09 05:12:46 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  void print(const std::string& s, const KeyFormatter& keyFormatter =
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								                                       DefaultKeyFormatter) const override {
							 | 
						
					
						
							
								
									
										
										
										
											2020-06-20 07:45:24 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    std::cout << s << "PoseToPointFactor(" << keyFormatter(this->key1()) << ","
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								              << keyFormatter(this->key2()) << ")\n"
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								              << "  measured: " << measured_.transpose() << std::endl;
							 | 
						
					
						
							
								
									
										
										
										
											2020-06-20 06:46:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    this->noiseModel_->print("  noise model: ");
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /** equals */
							 | 
						
					
						
							
								
									
										
										
										
											2021-12-09 05:12:46 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  bool equals(const NonlinearFactor& expected,
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								              double tol = 1e-9) const override {
							 | 
						
					
						
							
								
									
										
										
										
											2020-06-20 07:45:24 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    const This* e = dynamic_cast<const This*>(&expected);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    return e != nullptr && Base::equals(*e, tol) &&
							 | 
						
					
						
							
								
									
										
										
										
											2021-12-08 12:45:28 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								           traits<POINT>::Equals(this->measured_, e->measured_, tol);
							 | 
						
					
						
							
								
									
										
										
										
											2020-06-20 06:46:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2021-12-19 23:41:07 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  /// @return a deep copy of this factor
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  gtsam::NonlinearFactor::shared_ptr clone() const override {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    return boost::static_pointer_cast<gtsam::NonlinearFactor>(
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        gtsam::NonlinearFactor::shared_ptr(new This(*this)));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2020-06-20 06:46:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /** implement functions needed to derive from Factor */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /** vector of errors
							 | 
						
					
						
							
								
									
										
										
										
											2021-12-08 12:45:28 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								   * @brief Error = w_T_b.inverse()*w_P - measured_
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								   * @param w_T_b The pose of the body in world coordinates
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								   * @param w_P The estimated point location in world coordinates
							 | 
						
					
						
							
								
									
										
										
										
											2020-06-20 07:45:24 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								   *
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								   * Note: measured_ and the error are in local coordiantes.
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								   */
							 | 
						
					
						
							
								
									
										
										
										
											2021-12-09 02:17:35 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  Vector evaluateError(
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      const POSE& w_T_b, const POINT& w_P,
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      boost::optional<Matrix&> H1 = boost::none,
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      boost::optional<Matrix&> H2 = boost::none) const override {
							 | 
						
					
						
							
								
									
										
										
										
											2021-12-08 12:45:28 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    return w_T_b.transformTo(w_P, H1, H2) - measured_;
							 | 
						
					
						
							
								
									
										
										
										
											2020-06-20 06:46:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /** return the measured */
							 | 
						
					
						
							
								
									
										
										
										
											2021-12-08 12:45:28 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  const POINT& measured() const { return measured_; }
							 | 
						
					
						
							
								
									
										
										
										
											2020-06-20 06:46:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2020-06-20 07:45:24 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								 private:
							 | 
						
					
						
							
								
									
										
										
										
											2020-06-20 06:46:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /** Serialization function */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  friend class boost::serialization::access;
							 | 
						
					
						
							
								
									
										
										
										
											2020-06-20 07:45:24 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  template <class ARCHIVE>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    ar& boost::serialization::make_nvp(
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        "NoiseModelFactor2", boost::serialization::base_object<Base>(*this));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    ar& BOOST_SERIALIZATION_NVP(measured_);
							 | 
						
					
						
							
								
									
										
										
										
											2020-06-20 06:46:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2020-06-20 07:45:24 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								};  // \class PoseToPointFactor
							 | 
						
					
						
							
								
									
										
										
										
											2020-06-20 06:46:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2020-06-20 07:45:24 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								}  // namespace gtsam
							 |