From 810acf29c923824d751d976c80521720e9518ac3 Mon Sep 17 00:00:00 2001
From: Joan Sola <jsola@iri.upc.edu>
Date: Mon, 26 Feb 2018 13:16:44 +0100
Subject: [PATCH] Remove getJacobianMethod() overrriden from the base class

---
 src/constraint_AHP.h                  | 10 ----------
 src/constraint_block_absolute.h       |  5 -----
 src/constraint_container.h            | 10 ----------
 src/constraint_corner_2D.h            | 10 ----------
 src/constraint_epipolar.h             |  1 +
 src/constraint_fix_bias.h             | 10 ----------
 src/constraint_gps_2D.h               | 10 ----------
 src/constraint_gps_pseudorange_2D.h   | 10 ----------
 src/constraint_gps_pseudorange_3D.h   | 11 -----------
 src/constraint_imu.h                  |  9 ---------
 src/constraint_odom_2D.h              |  7 -------
 src/constraint_odom_2D_analytic.h     | 10 ----------
 src/constraint_odom_3D.h              |  2 --
 src/constraint_point_2D.h             | 10 ----------
 src/constraint_point_to_line_2D.h     | 10 ----------
 src/constraint_pose_2D.h              | 10 ----------
 src/constraint_pose_3D.h              |  5 -----
 src/constraint_quaternion_absolute.h  |  5 -----
 src/constraint_relative_2D_analytic.h |  6 ------
 19 files changed, 1 insertion(+), 150 deletions(-)

diff --git a/src/constraint_AHP.h b/src/constraint_AHP.h
index 8062eb19e..d70ddd065 100644
--- a/src/constraint_AHP.h
+++ b/src/constraint_AHP.h
@@ -51,11 +51,6 @@ class ConstraintAHP : public ConstraintAutodiff<ConstraintAHP, 2, 3, 4, 3, 4, 4>
                          const T* const _lmk_hmg,
                          T* _residuals) const;
 
-        /** \brief Returns the jacobians computation method
-         **/
-        virtual JacobianMethod getJacobianMethod() const override;
-
-
         // Static creator method
         static ConstraintAHPPtr create(const FeatureBasePtr&   _ftr_ptr,
                                        const LandmarkAHPPtr&   _lmk_ahp_ptr,
@@ -190,11 +185,6 @@ inline bool ConstraintAHP::operator ()(const T* const _current_frame_p,
     return true;
 }
 
-inline wolf::JacobianMethod ConstraintAHP::getJacobianMethod() const
-{
-    return JAC_AUTO;
-}
-
 inline wolf::ConstraintAHPPtr ConstraintAHP::create(const FeatureBasePtr&   _ftr_ptr,
                                                     const LandmarkAHPPtr&   _lmk_ahp_ptr,
                                                     const ProcessorBasePtr& _processor_ptr,
diff --git a/src/constraint_block_absolute.h b/src/constraint_block_absolute.h
index 737de58a8..a02fcc237 100644
--- a/src/constraint_block_absolute.h
+++ b/src/constraint_block_absolute.h
@@ -33,11 +33,6 @@ class ConstraintBlockAbsolute: public ConstraintAutodiff<ConstraintBlockAbsolute
         template<typename T>
         bool operator ()(const T* const _sb, T* _residuals) const;
 
-        virtual JacobianMethod getJacobianMethod() const override
-        {
-            return JAC_AUTO;
-        }
-
 };
 
 template<typename T>
diff --git a/src/constraint_container.h b/src/constraint_container.h
index 6c7ca7df1..e4c9e66c0 100644
--- a/src/constraint_container.h
+++ b/src/constraint_container.h
@@ -116,16 +116,6 @@ class ConstraintContainer: public ConstraintAutodiff<ConstraintContainer,3,2,1,2
 			return true;
 		}
 
-    /** \brief Returns the jacobians computation method
-     *
-     * Returns the jacobians computation method
-     *
-     **/
-    virtual JacobianMethod getJacobianMethod() const override
-    {
-      return JAC_AUTO;
-    }
-
 
   public:
     static ConstraintBasePtr create(const FeatureBasePtr& _feature_ptr,
diff --git a/src/constraint_corner_2D.h b/src/constraint_corner_2D.h
index 0096e438d..922d17d5a 100644
--- a/src/constraint_corner_2D.h
+++ b/src/constraint_corner_2D.h
@@ -34,16 +34,6 @@ class ConstraintCorner2D: public ConstraintAutodiff<ConstraintCorner2D, 3,2,1,2,
     bool operator ()(const T* const _robotP, const T* const _robotO, const T* const _landmarkP,
                      const T* const _landmarkO, T* _residuals) const;
 
-    /** \brief Returns the jacobians computation method
-     *
-     * Returns the jacobians computation method
-     *
-     **/
-    virtual JacobianMethod getJacobianMethod() const override
-    {
-      return JAC_AUTO;
-    }
-
     static ConstraintBasePtr create(const FeatureBasePtr& _feature_ptr, const NodeBasePtr& _correspondant_ptr, const ProcessorBasePtr& _processor_ptr = nullptr)
     {
       return std::make_shared<ConstraintCorner2D>(_feature_ptr, std::static_pointer_cast<LandmarkCorner2D>(_correspondant_ptr), _processor_ptr);
diff --git a/src/constraint_epipolar.h b/src/constraint_epipolar.h
index fe184fed3..948a162be 100644
--- a/src/constraint_epipolar.h
+++ b/src/constraint_epipolar.h
@@ -27,6 +27,7 @@ class ConstraintEpipolar : public ConstraintBase
         /** Returns a residual vector and a vector of Jacobian matrix corresponding to each state block evaluated in the point provided in _states_ptr
          **/
         virtual void evaluate(const std::vector<const Scalar*>& _states_ptr, Eigen::VectorXs& residual_, std::vector<Eigen::MatrixXs>& jacobians_) const override {};
+
         /** \brief Returns the jacobians computation method
          **/
         virtual JacobianMethod getJacobianMethod() const override {return JAC_ANALYTIC;}
diff --git a/src/constraint_fix_bias.h b/src/constraint_fix_bias.h
index acaac249a..407d368bb 100644
--- a/src/constraint_fix_bias.h
+++ b/src/constraint_fix_bias.h
@@ -33,16 +33,6 @@ class ConstraintFixBias: public ConstraintAutodiff<ConstraintFixBias,6,3,3>
         template<typename T>
         bool operator ()(const T* const _ab, const T* const _wb, T* _residuals) const;
 
-        /** \brief Returns the jacobians computation method
-         *
-         * Returns the jacobians computation method
-         *
-         **/
-        virtual JacobianMethod getJacobianMethod() const override
-        {
-            return JAC_AUTO;
-        }
-
 };
 
 template<typename T>
diff --git a/src/constraint_gps_2D.h b/src/constraint_gps_2D.h
index 5efd4007f..d8b5efda4 100644
--- a/src/constraint_gps_2D.h
+++ b/src/constraint_gps_2D.h
@@ -26,16 +26,6 @@ class ConstraintGPS2D : public ConstraintAutodiff<ConstraintGPS2D, 2, 2>
         template<typename T>
         bool operator ()(const T* const _x, T* _residuals) const;
 
-        /** \brief Returns the jacobians computation method
-         *
-         * Returns the jacobians computation method
-         *
-         **/
-        virtual JacobianMethod getJacobianMethod() const override
-        {
-            return JAC_AUTO;
-        }
-
 };
 
 template<typename T>
diff --git a/src/constraint_gps_pseudorange_2D.h b/src/constraint_gps_pseudorange_2D.h
index 087335589..d8fc23256 100644
--- a/src/constraint_gps_pseudorange_2D.h
+++ b/src/constraint_gps_pseudorange_2D.h
@@ -54,16 +54,6 @@ class ConstraintGPSPseudorange2D : public ConstraintAutodiff<ConstraintGPSPseudo
                         const T* const _bias, const T* const _map_p, const T* const _map_o,
                         T* _residual) const;
 
-        /** \brief Returns the jacobians computation method
-        *
-        * Returns the jacobians computation method
-        *
-        **/
-        virtual JacobianMethod getJacobianMethod() const override
-        {
-            return JAC_AUTO;
-        }
-
     protected:
         Eigen::Vector3s sat_position_;
         Scalar pseudorange_;
diff --git a/src/constraint_gps_pseudorange_3D.h b/src/constraint_gps_pseudorange_3D.h
index 47e4d95ff..58f471aa3 100644
--- a/src/constraint_gps_pseudorange_3D.h
+++ b/src/constraint_gps_pseudorange_3D.h
@@ -53,17 +53,6 @@ class ConstraintGPSPseudorange3D: public ConstraintAutodiff<ConstraintGPSPseudor
                         const T* const _bias, const T* const _init_vehicle_p, const T* const _init_vehicle_o,
                         T* _residual) const;
 
-
-        /** \brief Returns the jacobians computation method
-        *
-        * Returns the jacobians computation method
-        *
-        **/
-        virtual JacobianMethod getJacobianMethod() const override
-        {
-            return JAC_AUTO;
-        }
-
     protected:
         Eigen::Vector3s sat_position_;
         Scalar pseudorange_;
diff --git a/src/constraint_imu.h b/src/constraint_imu.h
index dd83a1b09..72deeb9a7 100644
--- a/src/constraint_imu.h
+++ b/src/constraint_imu.h
@@ -72,8 +72,6 @@ class ConstraintIMU : public ConstraintAutodiff<ConstraintIMU, 15, 3, 4, 3, 6, 3
                       const Eigen::MatrixBase<D1> &     _wb2,
                       Eigen::MatrixBase<D3> &           _res) const;
 
-        virtual JacobianMethod getJacobianMethod() const override;
-
         /* Function expectation(...)
          * params :
          * Vector3s _p1 : position in imu frame
@@ -450,13 +448,6 @@ inline void ConstraintIMU::expectation(const Eigen::MatrixBase<D1> &        _p1,
     imu::betweenStates(_p1, _q1, _v1, _p2, _q2, _v2, _dt, _pe, _qe, _ve);
 }
 
-inline JacobianMethod ConstraintIMU::getJacobianMethod() const
-{
-    return JAC_AUTO;
-}
-
-
-
 
 } // namespace wolf
 
diff --git a/src/constraint_odom_2D.h b/src/constraint_odom_2D.h
index 3e6659633..decbf0e1f 100644
--- a/src/constraint_odom_2D.h
+++ b/src/constraint_odom_2D.h
@@ -37,13 +37,6 @@ class ConstraintOdom2D : public ConstraintAutodiff<ConstraintOdom2D, 3, 2, 1, 2,
         bool operator ()(const T* const _p1, const T* const _o1, const T* const _p2, const T* const _o2,
                          T* _residuals) const;
 
-        /** \brief Returns the jacobians computation method
-         **/
-        virtual JacobianMethod getJacobianMethod() const override
-        {
-            return JAC_AUTO;
-        }
-
     public:
         static wolf::ConstraintBasePtr create(const FeatureBasePtr& _feature_ptr, const NodeBasePtr& _correspondant_ptr, const ProcessorBasePtr& _processor_ptr)
         {
diff --git a/src/constraint_odom_2D_analytic.h b/src/constraint_odom_2D_analytic.h
index 5ae0f4f48..dd35bfec7 100644
--- a/src/constraint_odom_2D_analytic.h
+++ b/src/constraint_odom_2D_analytic.h
@@ -90,16 +90,6 @@ class ConstraintOdom2DAnalytic : public ConstraintRelative2DAnalytic
 //
 //            jacobians[3] << 0, 0, 1;
 //            jacobians[3] = getMeasurementSquareRootInformationUpper() * jacobians[0];
-//        }
-//
-//        /** \brief Returns the jacobians computation method
-//         *
-//         * Returns the jacobians computation method
-//         *
-//         **/
-//        virtual JacobianMethod getJacobianMethod() const
-//        {
-//            return AUTO;
 //        }
 
 
diff --git a/src/constraint_odom_3D.h b/src/constraint_odom_3D.h
index f733ff5ed..4973dc489 100644
--- a/src/constraint_odom_3D.h
+++ b/src/constraint_odom_3D.h
@@ -28,8 +28,6 @@ class ConstraintOdom3D : public ConstraintAutodiff<ConstraintOdom3D,6,3,4,3,4>
 
         virtual ~ConstraintOdom3D() = default;
 
-        JacobianMethod getJacobianMethod() const override {return JAC_AUTO;}
-
         template<typename T>
                 bool operator ()(const T* const _p_current,
                                  const T* const _q_current,
diff --git a/src/constraint_point_2D.h b/src/constraint_point_2D.h
index 7370ca7fc..c001fb553 100644
--- a/src/constraint_point_2D.h
+++ b/src/constraint_point_2D.h
@@ -84,16 +84,6 @@ class ConstraintPoint2D: public ConstraintAutodiff<ConstraintPoint2D, 2,2,1,2,1,
     template <typename T>
     bool operator ()(const T* const _robotP, const T* const _robotO, const T* const _landmarkOriginP, const T* const _landmarkOriginO, const T* const _landmarkPoint, T* _residuals) const;
 
-    /** \brief Returns the jacobians computation method
-         *
-         * Returns the jacobians computation method
-         *
-         **/
-    virtual JacobianMethod getJacobianMethod() const override
-    {
-      return JAC_AUTO;
-    }
-
     /** \brief Returns a reference to the feature measurement
          **/
     virtual const Eigen::VectorXs& getMeasurement() const override
diff --git a/src/constraint_point_to_line_2D.h b/src/constraint_point_to_line_2D.h
index eeaa84188..be69caa7e 100644
--- a/src/constraint_point_to_line_2D.h
+++ b/src/constraint_point_to_line_2D.h
@@ -75,16 +75,6 @@ class ConstraintPointToLine2D: public ConstraintAutodiff<ConstraintPointToLine2D
     template <typename T>
     bool operator ()(const T* const _robotP, const T* const _robotO, const T* const _landmarkOriginPosition, const T* const _landmarkOriginOrientation, const T* const _landmarkPoint, const T* const _landmarkPointAux, T* _residuals) const;
 
-    /** \brief Returns the jacobians computation method
-         *
-         * Returns the jacobians computation method
-         *
-         **/
-    virtual JacobianMethod getJacobianMethod() const override
-    {
-      return JAC_AUTO;
-    }
-
     /** \brief Returns a reference to the feature measurement
          **/
     virtual const Eigen::VectorXs& getMeasurement() const override
diff --git a/src/constraint_pose_2D.h b/src/constraint_pose_2D.h
index c971f72f9..7ddc7478c 100644
--- a/src/constraint_pose_2D.h
+++ b/src/constraint_pose_2D.h
@@ -30,16 +30,6 @@ class ConstraintPose2D: public ConstraintAutodiff<ConstraintPose2D,3,2,1>
         template<typename T>
         bool operator ()(const T* const _p, const T* const _o, T* _residuals) const;
 
-        /** \brief Returns the jacobians computation method
-         *
-         * Returns the jacobians computation method
-         *
-         **/
-        virtual JacobianMethod getJacobianMethod() const override
-        {
-            return JAC_AUTO;
-        }
-
 };
 
 template<typename T>
diff --git a/src/constraint_pose_3D.h b/src/constraint_pose_3D.h
index d0132756a..31221af3e 100644
--- a/src/constraint_pose_3D.h
+++ b/src/constraint_pose_3D.h
@@ -28,11 +28,6 @@ class ConstraintPose3D: public ConstraintAutodiff<ConstraintPose3D,6,3,4>
         template<typename T>
         bool operator ()(const T* const _p, const T* const _o, T* _residuals) const;
 
-        virtual JacobianMethod getJacobianMethod() const override
-        {
-            return JAC_AUTO;
-        }
-
 };
 
 template<typename T>
diff --git a/src/constraint_quaternion_absolute.h b/src/constraint_quaternion_absolute.h
index 8fba0ebbb..884815461 100644
--- a/src/constraint_quaternion_absolute.h
+++ b/src/constraint_quaternion_absolute.h
@@ -35,11 +35,6 @@ class ConstraintQuaternionAbsolute: public ConstraintAutodiff<ConstraintQuaterni
         template<typename T>
         bool operator ()(const T* const _o, T* _residuals) const;
 
-        virtual JacobianMethod getJacobianMethod() const override
-        {
-            return JAC_AUTO;
-        }
-
 };
 
 template<typename T>
diff --git a/src/constraint_relative_2D_analytic.h b/src/constraint_relative_2D_analytic.h
index d52cb5876..5d2aadb7e 100644
--- a/src/constraint_relative_2D_analytic.h
+++ b/src/constraint_relative_2D_analytic.h
@@ -91,12 +91,6 @@ class ConstraintRelative2DAnalytic : public ConstraintAnalytic
          **/
         virtual void evaluatePureJacobians(std::vector<Eigen::MatrixXs>& jacobians) const override;
 
-        /** \brief Returns the jacobians computation method
-         **/
-        virtual JacobianMethod getJacobianMethod() const override
-        {
-            return JAC_AUTO;
-        }
 };
 
 
-- 
GitLab