fixed dllexport issues in nonlinear, only tests failing

release/4.3a0
Varun Agrawal 2022-02-17 09:56:32 -05:00
parent 865a7bac77
commit 2e5bdcd5e7
2 changed files with 19 additions and 20 deletions

View File

@ -56,7 +56,7 @@ namespace gtsam {
* MultiplyFunctor(multiplier));
*/
template <typename R, typename T>
class GTSAM_EXPORT FunctorizedFactor : public NoiseModelFactor1<T> {
class FunctorizedFactor : public NoiseModelFactor1<T> {
private:
using Base = NoiseModelFactor1<T>;
@ -155,7 +155,7 @@ FunctorizedFactor<R, T> MakeFunctorizedFactor(Key key, const R &z,
* @param T2: The second argument type for the functor.
*/
template <typename R, typename T1, typename T2>
class GTSAM_EXPORT FunctorizedFactor2 : public NoiseModelFactor2<T1, T2> {
class FunctorizedFactor2 : public NoiseModelFactor2<T1, T2> {
private:
using Base = NoiseModelFactor2<T1, T2>;

View File

@ -23,14 +23,14 @@ namespace gtsam {
* This factor does have the ability to perform relinearization under small-angle and
* linearity assumptions if a linearization point is added.
*/
class LinearContainerFactor : public NonlinearFactor {
class GTSAM_EXPORT LinearContainerFactor : public NonlinearFactor {
protected:
GaussianFactor::shared_ptr factor_;
boost::optional<Values> linearizationPoint_;
/** direct copy constructor */
GTSAM_EXPORT LinearContainerFactor(const GaussianFactor::shared_ptr& factor, const boost::optional<Values>& linearizationPoint);
LinearContainerFactor(const GaussianFactor::shared_ptr& factor, const boost::optional<Values>& linearizationPoint);
// Some handy typedefs
typedef NonlinearFactor Base;
@ -44,13 +44,13 @@ public:
LinearContainerFactor() {}
/** Primary constructor: store a linear factor with optional linearization point */
GTSAM_EXPORT LinearContainerFactor(const JacobianFactor& factor, const Values& linearizationPoint = Values());
LinearContainerFactor(const JacobianFactor& factor, const Values& linearizationPoint = Values());
/** Primary constructor: store a linear factor with optional linearization point */
GTSAM_EXPORT LinearContainerFactor(const HessianFactor& factor, const Values& linearizationPoint = Values());
LinearContainerFactor(const HessianFactor& factor, const Values& linearizationPoint = Values());
/** Constructor from shared_ptr */
GTSAM_EXPORT LinearContainerFactor(const GaussianFactor::shared_ptr& factor, const Values& linearizationPoint = Values());
LinearContainerFactor(const GaussianFactor::shared_ptr& factor, const Values& linearizationPoint = Values());
// Access
@ -59,10 +59,10 @@ public:
// Testable
/** print */
GTSAM_EXPORT void print(const std::string& s = "", const KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const override;
void print(const std::string& s = "", const KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const override;
/** Check if two factors are equal */
GTSAM_EXPORT bool equals(const NonlinearFactor& f, double tol = 1e-9) const override;
bool equals(const NonlinearFactor& f, double tol = 1e-9) const override;
// NonlinearFactor
@ -74,10 +74,10 @@ public:
*
* @return nonlinear error if linearizationPoint present, zero otherwise
*/
GTSAM_EXPORT double error(const Values& c) const override;
double error(const Values& c) const override;
/** get the dimension of the factor: rows of linear factor */
GTSAM_EXPORT size_t dim() const override;
size_t dim() const override;
/** Extract the linearization point used in recalculating error */
const boost::optional<Values>& linearizationPoint() const { return linearizationPoint_; }
@ -98,17 +98,17 @@ public:
* TODO: better approximation of relinearization
* TODO: switchable modes for approximation technique
*/
GTSAM_EXPORT GaussianFactor::shared_ptr linearize(const Values& c) const override;
GaussianFactor::shared_ptr linearize(const Values& c) const override;
/**
* Creates an anti-factor directly
*/
GTSAM_EXPORT GaussianFactor::shared_ptr negateToGaussian() const;
GaussianFactor::shared_ptr negateToGaussian() const;
/**
* Creates the equivalent anti-factor as another LinearContainerFactor.
*/
GTSAM_EXPORT NonlinearFactor::shared_ptr negateToNonlinear() const;
NonlinearFactor::shared_ptr negateToNonlinear() const;
/**
* Creates a shared_ptr clone of the factor - needs to be specialized to allow
@ -140,25 +140,24 @@ public:
/**
* Simple checks whether this is a Jacobian or Hessian factor
*/
GTSAM_EXPORT bool isJacobian() const;
GTSAM_EXPORT bool isHessian() const;
bool isJacobian() const;
bool isHessian() const;
/** Casts to JacobianFactor */
GTSAM_EXPORT boost::shared_ptr<JacobianFactor> toJacobian() const;
boost::shared_ptr<JacobianFactor> toJacobian() const;
/** Casts to HessianFactor */
GTSAM_EXPORT boost::shared_ptr<HessianFactor> toHessian() const;
boost::shared_ptr<HessianFactor> toHessian() const;
/**
* Utility function for converting linear graphs to nonlinear graphs
* consisting of LinearContainerFactors.
*/
GTSAM_EXPORT
static NonlinearFactorGraph ConvertLinearGraph(const GaussianFactorGraph& linear_graph,
const Values& linearizationPoint = Values());
protected:
GTSAM_EXPORT void initializeLinearizationPoint(const Values& linearizationPoint);
void initializeLinearizationPoint(const Values& linearizationPoint);
private:
/** Serialization function */