Skip to content

Commit

Permalink
fix ros gtsam 4.2a9 build
Browse files Browse the repository at this point in the history
  • Loading branch information
borongyuan committed Aug 7, 2023
1 parent a94a4c9 commit 9ffe5dc
Show file tree
Hide file tree
Showing 9 changed files with 26 additions and 26 deletions.
4 changes: 2 additions & 2 deletions corelib/src/optimizer/OptimizerGTSAM.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -527,7 +527,7 @@ std::map<int, Transform> OptimizerGTSAM::optimize(
{
float x,y,z,roll,pitch,yaw;
std::map<int, Transform> tmpPoses;
#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3)
#if GTSAM_VERSION_NUMERIC >= 40200
for(gtsam::Values::deref_iterator iter=optimizer->values().begin(); iter!=optimizer->values().end(); ++iter)
#else
for(gtsam::Values::const_iterator iter=optimizer->values().begin(); iter!=optimizer->values().end(); ++iter)
Expand Down Expand Up @@ -634,7 +634,7 @@ std::map<int, Transform> OptimizerGTSAM::optimize(
optimizer->iterations(), optimizer->error(), graph.error(initialEstimate), graph.error(optimizer->values()), timer.ticks());

float x,y,z,roll,pitch,yaw;
#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3)
#if GTSAM_VERSION_NUMERIC >= 40200
for(gtsam::Values::deref_iterator iter=optimizer->values().begin(); iter!=optimizer->values().end(); ++iter)
#else
for(gtsam::Values::const_iterator iter=optimizer->values().begin(); iter!=optimizer->values().end(); ++iter)
Expand Down
20 changes: 10 additions & 10 deletions corelib/src/optimizer/gtsam/GravityFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -63,14 +63,14 @@ class GravityFactor {

/** vector of errors */
Vector attitudeError(const Rot3& p,
#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3)
#if GTSAM_VERSION_NUMERIC >= 40300
OptionalJacobian<2,3> H = {}) const;
#else
OptionalJacobian<2,3> H = boost::none) const;
#endif

/** Serialization function */
#if defined(GTSAM_ENABLE_BOOST_SERIALIZATION) || GTSAM_VERSION_MAJOR < 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR < 3)
#if defined(GTSAM_ENABLE_BOOST_SERIALIZATION) || GTSAM_VERSION_NUMERIC < 40300
friend class boost::serialization::access;
template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
Expand All @@ -91,7 +91,7 @@ class Rot3GravityFactor: public NoiseModelFactor1<Rot3>, public GravityFactor {
public:

/// shorthand for a smart pointer to a factor
#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3)
#if GTSAM_VERSION_NUMERIC >= 40300
typedef std::shared_ptr<Rot3GravityFactor> shared_ptr;
#else
typedef boost::shared_ptr<Rot3GravityFactor> shared_ptr;
Expand Down Expand Up @@ -121,7 +121,7 @@ class Rot3GravityFactor: public NoiseModelFactor1<Rot3>, public GravityFactor {

/// @return a deep copy of this factor
virtual gtsam::NonlinearFactor::shared_ptr clone() const {
#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3)
#if GTSAM_VERSION_NUMERIC >= 40300
return std::static_pointer_cast<gtsam::NonlinearFactor>(
#else
return boost::static_pointer_cast<gtsam::NonlinearFactor>(
Expand All @@ -138,7 +138,7 @@ class Rot3GravityFactor: public NoiseModelFactor1<Rot3>, public GravityFactor {

/** vector of errors */
virtual Vector evaluateError(const Rot3& nRb, //
#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3)
#if GTSAM_VERSION_NUMERIC >= 40300
OptionalMatrixType H = OptionalNone) const {
#else
boost::optional<Matrix&> H = boost::none) const {
Expand All @@ -153,7 +153,7 @@ class Rot3GravityFactor: public NoiseModelFactor1<Rot3>, public GravityFactor {
}

private:
#if defined(GTSAM_ENABLE_BOOST_SERIALIZATION) || GTSAM_VERSION_MAJOR < 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR < 3)
#if defined(GTSAM_ENABLE_BOOST_SERIALIZATION) || GTSAM_VERSION_NUMERIC < 40300
/** Serialization function */
friend class boost::serialization::access;
template<class ARCHIVE>
Expand Down Expand Up @@ -182,7 +182,7 @@ class Pose3GravityFactor: public NoiseModelFactor1<Pose3>,
public:

/// shorthand for a smart pointer to a factor
#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3)
#if GTSAM_VERSION_NUMERIC >= 40300
typedef std::shared_ptr<Pose3GravityFactor> shared_ptr;
#else
typedef boost::shared_ptr<Pose3GravityFactor> shared_ptr;
Expand Down Expand Up @@ -211,7 +211,7 @@ class Pose3GravityFactor: public NoiseModelFactor1<Pose3>,

/// @return a deep copy of this factor
virtual gtsam::NonlinearFactor::shared_ptr clone() const {
#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3)
#if GTSAM_VERSION_NUMERIC >= 40300
return std::static_pointer_cast<gtsam::NonlinearFactor>(
#else
return boost::static_pointer_cast<gtsam::NonlinearFactor>(
Expand All @@ -228,7 +228,7 @@ class Pose3GravityFactor: public NoiseModelFactor1<Pose3>,

/** vector of errors */
virtual Vector evaluateError(const Pose3& nTb, //
#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3)
#if GTSAM_VERSION_NUMERIC >= 40300
OptionalMatrixType H = OptionalNone) const {
#else
boost::optional<Matrix&> H = boost::none) const {
Expand All @@ -249,7 +249,7 @@ class Pose3GravityFactor: public NoiseModelFactor1<Pose3>,
}

private:
#if defined(GTSAM_ENABLE_BOOST_SERIALIZATION) || GTSAM_VERSION_MAJOR < 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR < 3)
#if defined(GTSAM_ENABLE_BOOST_SERIALIZATION) || GTSAM_VERSION_NUMERIC < 40300
/** Serialization function */
friend class boost::serialization::access;
template<class ARCHIVE>
Expand Down
2 changes: 1 addition & 1 deletion corelib/src/optimizer/gtsam/XYFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ class XYFactor: public gtsam::NoiseModelFactor1<VALUE> {
// @param p the pose in Pose2
// @param H the optional Jacobian matrix, which use boost optional and has default null pointer
gtsam::Vector evaluateError(const VALUE& p,
#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3)
#if GTSAM_VERSION_NUMERIC >= 40300
OptionalMatrixType H = OptionalNone) const {
#else
boost::optional<gtsam::Matrix&> H = boost::none) const {
Expand Down
4 changes: 2 additions & 2 deletions corelib/src/optimizer/gtsam/XYZFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ class XYZFactor: public gtsam::NoiseModelFactor1<VALUE> {
// @param p the pose in Pose
// @param H the optional Jacobian matrix, which use boost optional and has default null pointer
gtsam::Vector evaluateError(const gtsam::Pose3& p,
#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3)
#if GTSAM_VERSION_NUMERIC >= 40300
OptionalMatrixType H = OptionalNone) const {
#else
boost::optional<gtsam::Matrix&> H = boost::none) const {
Expand All @@ -54,7 +54,7 @@ class XYZFactor: public gtsam::NoiseModelFactor1<VALUE> {
return (gtsam::Vector3() << p.x() - mx_, p.y() - my_, p.z() - mz_).finished();
}
gtsam::Vector evaluateError(const gtsam::Point3& p,
#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3)
#if GTSAM_VERSION_NUMERIC >= 40300
OptionalMatrixType H = OptionalNone) const {
#else
boost::optional<gtsam::Matrix&> H = boost::none) const {
Expand Down
2 changes: 1 addition & 1 deletion corelib/src/optimizer/vertigo/gtsam/DerivedValue.h
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ class DerivedValue : public gtsam::Value {
/**
* Clone this value (normal clone on the heap, delete with 'delete' operator)
*/
#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3)
#if GTSAM_VERSION_NUMERIC >= 40300
virtual std::shared_ptr<gtsam::Value> clone() const {
return std::make_shared<DERIVED>(static_cast<const DERIVED&>(*this));
}
Expand Down
4 changes: 2 additions & 2 deletions corelib/src/optimizer/vertigo/gtsam/betweenFactorMaxMix.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
#include <Eigen/Eigen>
#include <gtsam/config.h>

#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR==4 && GTSAM_VERSION_MINOR>=1)
#if GTSAM_VERSION_NUMERIC >= 40100
namespace gtsam {
gtsam::Matrix inverse(const gtsam::Matrix & matrix)
{
Expand Down Expand Up @@ -49,7 +49,7 @@ namespace vertigo {
double nu1 = 1.0/sqrt(gtsam::inverse(info1).determinant());
double l1 = nu1 * exp(-0.5*m1);

#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR==4 && GTSAM_VERSION_MINOR>=1)
#if GTSAM_VERSION_NUMERIC >= 40100
double m2 = nullHypothesisModel->squaredMahalanobisDistance(error);
#else
double m2 = nullHypothesisModel->distance(error);
Expand Down
4 changes: 2 additions & 2 deletions corelib/src/optimizer/vertigo/gtsam/betweenFactorSwitchable.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ namespace vertigo {
betweenFactor(key1, key2, measured, model) {};

gtsam::Vector evaluateError(const VALUE& p1, const VALUE& p2, const SwitchVariableLinear& s,
#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3)
#if GTSAM_VERSION_NUMERIC >= 40300
OptionalMatrixType H1 = OptionalNone,
OptionalMatrixType H2 = OptionalNone,
OptionalMatrixType H3 = OptionalNone) const
Expand Down Expand Up @@ -70,7 +70,7 @@ namespace vertigo {
betweenFactor(key1, key2, measured, model) {};

gtsam::Vector evaluateError(const VALUE& p1, const VALUE& p2, const SwitchVariableSigmoid& s,
#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3)
#if GTSAM_VERSION_NUMERIC >= 40300
OptionalMatrixType H1 = OptionalNone,
OptionalMatrixType H2 = OptionalNone,
OptionalMatrixType H3 = OptionalNone) const
Expand Down
6 changes: 3 additions & 3 deletions corelib/src/optimizer/vertigo/gtsam/switchVariableLinear.h
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ namespace vertigo {

/** between operation */
inline SwitchVariableLinear between(const SwitchVariableLinear& l2,
#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3)
#if GTSAM_VERSION_NUMERIC >= 40300
OptionalMatrixType H1=OptionalNone,
OptionalMatrixType H2=OptionalNone) const {
#else
Expand Down Expand Up @@ -121,15 +121,15 @@ template<> struct traits<vertigo::SwitchVariableLinear> {
typedef OptionalJacobian<3, 3> ChartJacobian;
typedef gtsam::Vector TangentVector;
static TangentVector Local(const vertigo::SwitchVariableLinear& origin, const vertigo::SwitchVariableLinear& other,
#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3)
#if GTSAM_VERSION_NUMERIC >= 40300
ChartJacobian Horigin = {}, ChartJacobian Hother = {}) {
#else
ChartJacobian Horigin = boost::none, ChartJacobian Hother = boost::none) {
#endif
return origin.localCoordinates(other);
}
static vertigo::SwitchVariableLinear Retract(const vertigo::SwitchVariableLinear& g, const TangentVector& v,
#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3)
#if GTSAM_VERSION_NUMERIC >= 40300
ChartJacobian H1 = {}, ChartJacobian H2 = {}) {
#else
ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none) {
Expand Down
6 changes: 3 additions & 3 deletions corelib/src/optimizer/vertigo/gtsam/switchVariableSigmoid.h
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ namespace vertigo {

/** between operation */
inline SwitchVariableSigmoid between(const SwitchVariableSigmoid& l2,
#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3)
#if GTSAM_VERSION_NUMERIC >= 40300
OptionalMatrixType H1=OptionalNone,
OptionalMatrixType H2=OptionalNone) const {
#else
Expand Down Expand Up @@ -122,15 +122,15 @@ template<> struct traits<vertigo::SwitchVariableSigmoid> {
typedef OptionalJacobian<3, 3> ChartJacobian;
typedef gtsam::Vector TangentVector;
static TangentVector Local(const vertigo::SwitchVariableSigmoid& origin, const vertigo::SwitchVariableSigmoid& other,
#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3)
#if GTSAM_VERSION_NUMERIC >= 40300
ChartJacobian Horigin = {}, ChartJacobian Hother = {}) {
#else
ChartJacobian Horigin = boost::none, ChartJacobian Hother = boost::none) {
#endif
return origin.localCoordinates(other);
}
static vertigo::SwitchVariableSigmoid Retract(const vertigo::SwitchVariableSigmoid& g, const TangentVector& v,
#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3)
#if GTSAM_VERSION_NUMERIC >= 40300
ChartJacobian H1 = {}, ChartJacobian H2 = {}) {
#else
ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none) {
Expand Down

0 comments on commit 9ffe5dc

Please sign in to comment.