Merge in alignment-related changes from 'origin/fix/msvc2017'
parent
ce5072c7bb
commit
b8f3cd0f13
|
|
@ -209,6 +209,12 @@ public:
|
||||||
v << v1, v2;
|
v << v1, v2;
|
||||||
return v;
|
return v;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html
|
||||||
|
enum { NeedsToAlign = (sizeof(M1) % 16) == 0 || (sizeof(M2) % 16) == 0
|
||||||
|
};
|
||||||
|
public:
|
||||||
|
EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
|
||||||
};
|
};
|
||||||
|
|
||||||
// Define any direct product group to be a model of the multiplicative Group concept
|
// Define any direct product group to be a model of the multiplicative Group concept
|
||||||
|
|
|
||||||
|
|
@ -229,10 +229,6 @@ private:
|
||||||
void serialize(Archive & ar, const unsigned int /*version*/) {
|
void serialize(Archive & ar, const unsigned int /*version*/) {
|
||||||
ar & BOOST_SERIALIZATION_NVP(pose_);
|
ar & BOOST_SERIALIZATION_NVP(pose_);
|
||||||
}
|
}
|
||||||
|
|
||||||
public:
|
|
||||||
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
|
|
||||||
|
|
||||||
};
|
};
|
||||||
// end of class PinholeBase
|
// end of class PinholeBase
|
||||||
|
|
||||||
|
|
@ -416,9 +412,6 @@ private:
|
||||||
}
|
}
|
||||||
|
|
||||||
/// @}
|
/// @}
|
||||||
|
|
||||||
public:
|
|
||||||
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
|
|
||||||
};
|
};
|
||||||
|
|
||||||
// manifold traits
|
// manifold traits
|
||||||
|
|
|
||||||
|
|
@ -157,28 +157,28 @@ struct traits<const Point3> : public internal::VectorSpace<Point3> {};
|
||||||
|
|
||||||
// Convenience typedef
|
// Convenience typedef
|
||||||
typedef std::pair<Point3, Point3> Point3Pair;
|
typedef std::pair<Point3, Point3> Point3Pair;
|
||||||
std::ostream &operator<<(std::ostream &os, const gtsam::Point3Pair &p);
|
GTSAM_EXPORT std::ostream &operator<<(std::ostream &os, const gtsam::Point3Pair &p);
|
||||||
|
|
||||||
/// distance between two points
|
/// distance between two points
|
||||||
double distance3(const Point3& p1, const Point3& q,
|
GTSAM_EXPORT double distance3(const Point3& p1, const Point3& q,
|
||||||
OptionalJacobian<1, 3> H1 = boost::none,
|
OptionalJacobian<1, 3> H1 = boost::none,
|
||||||
OptionalJacobian<1, 3> H2 = boost::none);
|
OptionalJacobian<1, 3> H2 = boost::none);
|
||||||
|
|
||||||
/// Distance of the point from the origin, with Jacobian
|
/// Distance of the point from the origin, with Jacobian
|
||||||
double norm3(const Point3& p, OptionalJacobian<1, 3> H = boost::none);
|
GTSAM_EXPORT double norm3(const Point3& p, OptionalJacobian<1, 3> H = boost::none);
|
||||||
|
|
||||||
/// normalize, with optional Jacobian
|
/// normalize, with optional Jacobian
|
||||||
Point3 normalize(const Point3& p, OptionalJacobian<3, 3> H = boost::none);
|
GTSAM_EXPORT Point3 normalize(const Point3& p, OptionalJacobian<3, 3> H = boost::none);
|
||||||
|
|
||||||
/// cross product @return this x q
|
/// cross product @return this x q
|
||||||
Point3 cross(const Point3& p, const Point3& q,
|
GTSAM_EXPORT Point3 cross(const Point3& p, const Point3& q,
|
||||||
OptionalJacobian<3, 3> H_p = boost::none,
|
OptionalJacobian<3, 3> H_p = boost::none,
|
||||||
OptionalJacobian<3, 3> H_q = boost::none);
|
OptionalJacobian<3, 3> H_q = boost::none);
|
||||||
|
|
||||||
/// dot product
|
/// dot product
|
||||||
double dot(const Point3& p, const Point3& q,
|
GTSAM_EXPORT double dot(const Point3& p, const Point3& q,
|
||||||
OptionalJacobian<1, 3> H_p = boost::none,
|
OptionalJacobian<1, 3> H_p = boost::none,
|
||||||
OptionalJacobian<1, 3> H_q = boost::none);
|
OptionalJacobian<1, 3> H_q = boost::none);
|
||||||
|
|
||||||
template <typename A1, typename A2>
|
template <typename A1, typename A2>
|
||||||
struct Range;
|
struct Range;
|
||||||
|
|
|
||||||
|
|
@ -278,6 +278,12 @@ private:
|
||||||
ar & BOOST_SERIALIZATION_NVP(t_);
|
ar & BOOST_SERIALIZATION_NVP(t_);
|
||||||
ar & BOOST_SERIALIZATION_NVP(r_);
|
ar & BOOST_SERIALIZATION_NVP(r_);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#ifdef GTSAM_TYPEDEF_POINTS_TO_VECTORS
|
||||||
|
public:
|
||||||
|
// Make sure Pose2 is aligned if it contains a Vector2
|
||||||
|
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
|
||||||
|
#endif
|
||||||
}; // Pose2
|
}; // Pose2
|
||||||
|
|
||||||
/** specialization for pose2 wedge function (generic template in Lie.h) */
|
/** specialization for pose2 wedge function (generic template in Lie.h) */
|
||||||
|
|
|
||||||
|
|
@ -327,9 +327,11 @@ public:
|
||||||
}
|
}
|
||||||
/// @}
|
/// @}
|
||||||
|
|
||||||
public:
|
#ifdef GTSAM_USE_QUATERNIONS
|
||||||
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
|
// Align if we are using Quaternions
|
||||||
|
public:
|
||||||
|
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
|
||||||
|
#endif
|
||||||
};
|
};
|
||||||
// Pose3 class
|
// Pose3 class
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -508,9 +508,11 @@ namespace gtsam {
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
public:
|
#ifdef GTSAM_USE_QUATERNIONS
|
||||||
|
// only align if quaternion, Matrix3 has no alignment requirements
|
||||||
|
public:
|
||||||
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
|
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
|
||||||
|
#endif
|
||||||
};
|
};
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
|
|
||||||
|
|
@ -129,6 +129,9 @@ private:
|
||||||
ar & BOOST_SERIALIZATION_NVP(nZ_);
|
ar & BOOST_SERIALIZATION_NVP(nZ_);
|
||||||
ar & BOOST_SERIALIZATION_NVP(bRef_);
|
ar & BOOST_SERIALIZATION_NVP(bRef_);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
public:
|
||||||
|
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
|
||||||
};
|
};
|
||||||
|
|
||||||
/// traits
|
/// traits
|
||||||
|
|
@ -213,6 +216,9 @@ private:
|
||||||
ar & BOOST_SERIALIZATION_NVP(nZ_);
|
ar & BOOST_SERIALIZATION_NVP(nZ_);
|
||||||
ar & BOOST_SERIALIZATION_NVP(bRef_);
|
ar & BOOST_SERIALIZATION_NVP(bRef_);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
public:
|
||||||
|
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
|
||||||
};
|
};
|
||||||
|
|
||||||
/// traits
|
/// traits
|
||||||
|
|
|
||||||
|
|
@ -122,6 +122,11 @@ namespace gtsam {
|
||||||
boost::serialization::base_object<Base>(*this));
|
boost::serialization::base_object<Base>(*this));
|
||||||
ar & BOOST_SERIALIZATION_NVP(measured_);
|
ar & BOOST_SERIALIZATION_NVP(measured_);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html
|
||||||
|
enum { NeedsToAlign = (sizeof(VALUE) % 16) == 0 };
|
||||||
|
public:
|
||||||
|
EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
|
||||||
}; // \class BetweenFactor
|
}; // \class BetweenFactor
|
||||||
|
|
||||||
/// traits
|
/// traits
|
||||||
|
|
|
||||||
|
|
@ -104,6 +104,11 @@ namespace gtsam {
|
||||||
boost::serialization::base_object<Base>(*this));
|
boost::serialization::base_object<Base>(*this));
|
||||||
ar & BOOST_SERIALIZATION_NVP(prior_);
|
ar & BOOST_SERIALIZATION_NVP(prior_);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html
|
||||||
|
enum { NeedsToAlign = (sizeof(T) % 16) == 0 };
|
||||||
|
public:
|
||||||
|
EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
|
||||||
};
|
};
|
||||||
|
|
||||||
} /// namespace gtsam
|
} /// namespace gtsam
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue