Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix MSVC / Windows Build of GTSAM_UNSTABLE #1102

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion gtsam/geometry/PinholeCamera.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ namespace gtsam {
* \nosubgrouping
*/
template<typename Calibration>
class GTSAM_EXPORT PinholeCamera: public PinholeBaseK<Calibration> {
class PinholeCamera: public PinholeBaseK<Calibration> {

public:

Expand Down
2 changes: 1 addition & 1 deletion gtsam/geometry/PinholePose.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ namespace gtsam {
* \nosubgrouping
*/
template<typename CALIBRATION>
class GTSAM_EXPORT PinholeBaseK: public PinholeBase {
class PinholeBaseK: public PinholeBase {

private:

Expand Down
12 changes: 6 additions & 6 deletions gtsam/nonlinear/NonlinearFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -282,7 +282,7 @@ class GTSAM_EXPORT NoiseModelFactor: public NonlinearFactor {
* which are objects in non-linear manifolds (Lie groups).
*/
template<class VALUE>
class GTSAM_EXPORT NoiseModelFactor1: public NoiseModelFactor {
class NoiseModelFactor1: public NoiseModelFactor {

public:

Expand Down Expand Up @@ -366,7 +366,7 @@ class GTSAM_EXPORT NoiseModelFactor1: public NoiseModelFactor {
/** A convenient base class for creating your own NoiseModelFactor with 2
* variables. To derive from this class, implement evaluateError(). */
template<class VALUE1, class VALUE2>
class GTSAM_EXPORT NoiseModelFactor2: public NoiseModelFactor {
class NoiseModelFactor2: public NoiseModelFactor {

public:

Expand Down Expand Up @@ -441,7 +441,7 @@ class GTSAM_EXPORT NoiseModelFactor2: public NoiseModelFactor {
/** A convenient base class for creating your own NoiseModelFactor with 3
* variables. To derive from this class, implement evaluateError(). */
template<class VALUE1, class VALUE2, class VALUE3>
class GTSAM_EXPORT NoiseModelFactor3: public NoiseModelFactor {
class NoiseModelFactor3: public NoiseModelFactor {

public:

Expand Down Expand Up @@ -518,7 +518,7 @@ class GTSAM_EXPORT NoiseModelFactor3: public NoiseModelFactor {
/** A convenient base class for creating your own NoiseModelFactor with 4
* variables. To derive from this class, implement evaluateError(). */
template<class VALUE1, class VALUE2, class VALUE3, class VALUE4>
class GTSAM_EXPORT NoiseModelFactor4: public NoiseModelFactor {
class NoiseModelFactor4: public NoiseModelFactor {

public:

Expand Down Expand Up @@ -599,7 +599,7 @@ class GTSAM_EXPORT NoiseModelFactor4: public NoiseModelFactor {
/** A convenient base class for creating your own NoiseModelFactor with 5
* variables. To derive from this class, implement evaluateError(). */
template<class VALUE1, class VALUE2, class VALUE3, class VALUE4, class VALUE5>
class GTSAM_EXPORT NoiseModelFactor5: public NoiseModelFactor {
class NoiseModelFactor5: public NoiseModelFactor {

public:

Expand Down Expand Up @@ -684,7 +684,7 @@ class GTSAM_EXPORT NoiseModelFactor5: public NoiseModelFactor {
/** A convenient base class for creating your own NoiseModelFactor with 6
* variables. To derive from this class, implement evaluateError(). */
template<class VALUE1, class VALUE2, class VALUE3, class VALUE4, class VALUE5, class VALUE6>
class GTSAM_EXPORT NoiseModelFactor6: public NoiseModelFactor {
class NoiseModelFactor6: public NoiseModelFactor {

public:

Expand Down
2 changes: 1 addition & 1 deletion gtsam/slam/SmartFactorBase.h
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ namespace gtsam {
* @tparam CAMERA should behave like a PinholeCamera.
*/
template<class CAMERA>
class GTSAM_EXPORT SmartFactorBase: public NonlinearFactor {
class SmartFactorBase: public NonlinearFactor {

private:
typedef NonlinearFactor Base;
Expand Down
2 changes: 1 addition & 1 deletion gtsam_unstable/slam/SmartStereoProjectionFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ typedef SmartProjectionParams SmartStereoProjectionParams;
* If you'd like to store poses in values instead of cameras, use
* SmartStereoProjectionPoseFactor instead
*/
class GTSAM_UNSTABLE_EXPORT SmartStereoProjectionFactor
class SmartStereoProjectionFactor
: public SmartFactorBase<StereoCamera> {
private:

Expand Down