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

Resolved several MSVC compiling errors #87

Merged
merged 7 commits into from
Jul 18, 2019
Merged
Show file tree
Hide file tree
Changes from 5 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
41 changes: 41 additions & 0 deletions Using-GTSAM-EXPORT.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
# Using GTSAM_EXPORT

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

wow, this doc is like a large Blog entry on the topic... good idea, @dellaert , @cntaylor ! 👍

To create a DLL in windows, the `GTSAM_EXPORT` keyword has been created and needs to be applied to different methods and classes in the code to expose this code outside of the DLL. However, there are several intricacies that make this more difficult than it sounds. In general, if you follow the following three rules, GTSAM_EXPORT should work properly. The rest of the document also describes (1) the common error message encountered when you are not following these rules and (2) the reasoning behind these usage rules.
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

the GTSAM_EXPORT keyword has been created

Should it be clearer mentioning that it is CMake the one who automatically defines this symbol (as far as I know) when building dynamic libs?


## Usage Rules
1. Put `GTSAM_EXPORT` in front of any function that you want exported in the DLL _if and only if_ that function is defined in a .cpp file, not just a .h file.
jlblancoc marked this conversation as resolved.
Show resolved Hide resolved
2. Use `GTSAM_EXPORT` in a class definition (i.e. `class GSTAM_EXPORT MyClass {...}`) only if:
* At least one of the functions inside that class is defined in a .cpp file and not just the .h file.
* You can `GTSAM_EXPORT` any class it inherits from as well. (Note that this implictly requires the class does not derive from a "header-only" class. Note that Eigen is a "header-only" library, so if your class derives from Eigen, _do not_ use `GTSAM_EXPORT` in the class definition!)
3. If you have defined a class using `GTSAM_EXPORT`, do not use `GTSAM_EXPORT` in any of its individual function declarations. (Note that you _can_ put `GTSAM_EXPORT` in the definition of individual functions within a class as long as you don't put `GTSAM_EXPORT` in the class definition.)
jlblancoc marked this conversation as resolved.
Show resolved Hide resolved

## When is GTSAM_EXPORT being used incorrectly
Unfortunately, using `GTSAM_EXPORT` incorrectly often does not cause a compiler or linker error in the library that is being compiled, but only when you try to use that DLL in a different library. For example, an error in gtsam/base will often show up when compiling the check_base_program or the MATLAB wrapper, but not when compiling/linking gtsam itself. The most common errors will say something like:

```
Error LNK2019 unresolved external symbol "public: void __cdecl gtsam::SO3::print(class std::basic_string<char,struct std::char_traits<char>,class std::allocator<char> > const &)const " (?print@SO3@gtsam@@QEBAXAEBV?$basic_string@DU?$char_traits@D@std@@V?$allocator@D@2@@std@@@Z) referenced in function "public: static void __cdecl gtsam::Testable<class gtsam::SO3>::Print(class gtsam::SO3 const &,class std::basic_string<char,struct std::char_traits<char>,class std::allocator<char> > const &)" (?Print@?$Testable@VSO3@gtsam@@@gtsam@@SAXAEBVSO3@2@AEBV?$basic_string@DU?$char_traits@D@std@@V?$allocator@D@2@@std@@@Z) check_geometry_program C:\AFIT\lib\gtsam\build\gtsam\geometry\tests\testSO3.obj
```

Sorry for the long error message there, but I want to quickly decode it to help understand what is going on. First, there is an unresolved symbol `gtsam::SO3::print`. This can occur because _either_ `GTSAM_EXPORT` was not added to the print function definition when it should have been, _OR_ because `GTSAM_EXPORT` was added to the print function definition when it is fully declared in the header. This error was detected while compiling `check_geometry_program` and pulling in `...\testSO3.obj`. Specifically, within the function call `gtsam::Testabl<class gtsam::SO3>::Print (...)`. Note that this error did _not_ occur when compiling the library that actually has SO3 inside of it.
jlblancoc marked this conversation as resolved.
Show resolved Hide resolved

## But Why?
To me, the behavior of GTSAM_EXPORT was very baffling. However, I believe it can be explained by understanding the rules that MSVC operates under.
jlblancoc marked this conversation as resolved.
Show resolved Hide resolved

First, we need to understand exactly what `GTSAM_EXPORT` does. When you use `GTSAM_EXPORT` on a function (or class) definition, it actually does two things. First, when you are building the library, it turns into a "dllexport" command, telling the compiler that this function should go into the DLL and be visible externally. When you pull in that same header for a different library, it switches to a "dllimport" command, telling the compiler it should find this function in a DLL somewhere. This leads to the first rule the compiler uses. (Note that I say "compiler rules" when the rules may actually be in the linker, but I am conflating the two terms here when I speak of the "compiler rules".)

***Compiler Rule #1*** If a `dllimport` command is used in defining a function or class, that function or class _must_ be found in a DLL.

Rule #1 doesn't seem very bad, until you combine it with rule #2

***Compiler Rule #2*** Anything defined in a header file is not included in a DLL.
Copy link
Member

@jlblancoc jlblancoc Jul 15, 2019

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Anything defined in a header file is not included in a DLL.

I'm not 100% sure of this... it is NOT exported if you mark it explicitly with inline. Otherwise, I'm not sure if there is a well-defined, standardized expected behavior (?).
(Edit: I mean, if one has:

class GTSAM_EXPORT Foo
{
public: 
 void doit(int &a) { a++; }
};

would doit() be exported? I think it will...
).

I'll kindly request the knowledge of @jolting here just in case he can help us to be accurate in the description...
@jolting

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Please note that my expertise on DLLimport/export is what I have learned playing with GTSAM for the last week or so getting it to compile and looking up things online. So, I am theorizing to the best of my knowledge, but I certainly am not an expert.

That said, I have seen several website mention that if you declare a function in a header inside a class definition, the compiler automatically makes it an "inline" function. If it was not inline and you included this class definition in more than one file, then you would get a "multiple definitions of the function 'doit'" error. So this one is essentially marked inline and will not be put in the DLL.

Once again, I should probably change "define" to declare. My im-precision may be causing confusion. :(

I guess it may be possible that a non-inline function is declared in a header file and included in the DLL, but that seems like a corner case (due to the "multiple instances" compilation problem inherent with non-inline functions) so I don't think we need to worry about that too much.


When these two rules are combined, you get some very confusing results. For example, a class which is completely defined in a header (e.g. LieMatrix) cannot use `GTSAM_EXPORT` in its definition. If LieMatrix is defined with `GTSAM_EXPORT`, then the compiler _must_ find LieMatrix in a DLL. Because LieMatrix is a header-only class, however, it can't find it, leading to a very confusing "I can't find this symbol" type of error. Note that the linker says it can't find the symbol even though the compiler found the header file that completely defines the class.

This leads to another compiler rule that finishes explaining the usage rules proposed above.

***Compiler Rule #3*** If a class is defined with `GTSAM_EXPORT`, then any classes it inherits from must be definable with a dllexport command as well.
jlblancoc marked this conversation as resolved.
Show resolved Hide resolved

One of the most immediate results of this compiler rule is that any class that inherits from an Eigen class _cannot_ be defined with `GTSAM_EXPORT`. Because Eigen is a header-only class, compiler rule #2 prohibits any Eigen class from being defined with a "dllexport" command. Therefore, no Eigen inherited classes can use `GTSAM_EXPORT` either. (Note that individual functions with an inherited class can be "exported." Just not the entire class.)
jlblancoc marked this conversation as resolved.
Show resolved Hide resolved

## Conclusion
Hopefully, this little document clarifies when `GTSAM_EXPORT` should and should not be used whenever future GTSAM code is being written. Following the usage rules above, I have been able to get all of the libraries, together with their test and wrapping libraries, to compile/link successfully.
2 changes: 1 addition & 1 deletion gtsam/base/Matrix.h
Original file line number Diff line number Diff line change
Expand Up @@ -299,7 +299,7 @@ GTSAM_EXPORT std::pair<Matrix,Matrix> qr(const Matrix& A);
* @param A is the input matrix, and is the output
* @param clear_below_diagonal enables zeroing out below diagonal
*/
void inplace_QR(Matrix& A);
GTSAM_EXPORT void inplace_QR(Matrix& A);

/**
* Imperative algorithm for in-place full elimination with
Expand Down
2 changes: 1 addition & 1 deletion gtsam/base/deprecated/LieMatrix.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ namespace gtsam {
* we can directly add double, Vector, and Matrix into values now, because of
* gtsam::traits.
*/
struct GTSAM_EXPORT LieMatrix : public Matrix {
struct LieMatrix : public Matrix {

/// @name Constructors
/// @{
Expand Down
2 changes: 1 addition & 1 deletion gtsam/base/deprecated/LieScalar.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ namespace gtsam {
* we can directly add double, Vector, and Matrix into values now, because of
* gtsam::traits.
*/
struct GTSAM_EXPORT LieScalar {
struct LieScalar {

enum { dimension = 1 };

Expand Down
2 changes: 1 addition & 1 deletion gtsam/base/deprecated/LieVector.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ namespace gtsam {
* we can directly add double, Vector, and Matrix into values now, because of
* gtsam::traits.
*/
struct GTSAM_EXPORT LieVector : public Vector {
struct LieVector : public Vector {

enum { dimension = Eigen::Dynamic };

Expand Down
16 changes: 8 additions & 8 deletions gtsam/geometry/Point2.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ namespace gtsam {
* @addtogroup geometry
* \nosubgrouping
*/
class GTSAM_EXPORT Point2 : public Vector2 {
class Point2 : public Vector2 {
private:

public:
Expand Down Expand Up @@ -66,10 +66,10 @@ class GTSAM_EXPORT Point2 : public Vector2 {
/// @{

/// print with optional string
void print(const std::string& s = "") const;
GTSAM_EXPORT void print(const std::string& s = "") const;

/// equals with an tolerance, prints out message if unequal
bool equals(const Point2& q, double tol = 1e-9) const;
GTSAM_EXPORT bool equals(const Point2& q, double tol = 1e-9) const;

/// @}
/// @name Group
Expand All @@ -86,10 +86,10 @@ class GTSAM_EXPORT Point2 : public Vector2 {
Point2 unit() const { return *this/norm(); }

/** norm of point, with derivative */
double norm(OptionalJacobian<1,2> H = boost::none) const;
GTSAM_EXPORT double norm(OptionalJacobian<1,2> H = boost::none) const;

/** distance between two points */
double distance(const Point2& p2, OptionalJacobian<1,2> H1 = boost::none,
GTSAM_EXPORT double distance(const Point2& p2, OptionalJacobian<1,2> H1 = boost::none,
OptionalJacobian<1,2> H2 = boost::none) const;

/// @}
Expand Down Expand Up @@ -124,9 +124,9 @@ class GTSAM_EXPORT Point2 : public Vector2 {
static Vector2 Logmap(const Point2& p) { return p;}
static Point2 Expmap(const Vector2& v) { return Point2(v);}
inline double dist(const Point2& p2) const {return distance(p2);}
static boost::optional<Point2> CircleCircleIntersection(double R_d, double r_d, double tol = 1e-9);
static std::list<Point2> CircleCircleIntersection(Point2 c1, Point2 c2, boost::optional<Point2> fh);
static std::list<Point2> CircleCircleIntersection(Point2 c1, double r1, Point2 c2, double r2, double tol = 1e-9);
GTSAM_EXPORT static boost::optional<Point2> CircleCircleIntersection(double R_d, double r_d, double tol = 1e-9);
GTSAM_EXPORT static std::list<Point2> CircleCircleIntersection(Point2 c1, Point2 c2, boost::optional<Point2> fh);
GTSAM_EXPORT static std::list<Point2> CircleCircleIntersection(Point2 c1, double r1, Point2 c2, double r2, double tol = 1e-9);
/// @}
#endif

Expand Down
20 changes: 10 additions & 10 deletions gtsam/geometry/Point3.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ namespace gtsam {
* @addtogroup geometry
* \nosubgrouping
*/
class GTSAM_EXPORT Point3 : public Vector3 {
class Point3 : public Vector3 {

public:

Expand All @@ -63,10 +63,10 @@ class GTSAM_EXPORT Point3 : public Vector3 {
/// @{

/** print with optional string */
void print(const std::string& s = "") const;
GTSAM_EXPORT void print(const std::string& s = "") const;

/** equals with an tolerance */
bool equals(const Point3& p, double tol = 1e-9) const;
GTSAM_EXPORT bool equals(const Point3& p, double tol = 1e-9) const;

/// @}
/// @name Group
Expand All @@ -80,21 +80,21 @@ class GTSAM_EXPORT Point3 : public Vector3 {
/// @{

/** distance between two points */
double distance(const Point3& p2, OptionalJacobian<1, 3> H1 = boost::none,
GTSAM_EXPORT double distance(const Point3& p2, OptionalJacobian<1, 3> H1 = boost::none,
OptionalJacobian<1, 3> H2 = boost::none) const;

/** Distance of the point from the origin, with Jacobian */
double norm(OptionalJacobian<1,3> H = boost::none) const;
GTSAM_EXPORT double norm(OptionalJacobian<1,3> H = boost::none) const;

/** normalize, with optional Jacobian */
Point3 normalized(OptionalJacobian<3, 3> H = boost::none) const;
GTSAM_EXPORT Point3 normalized(OptionalJacobian<3, 3> H = boost::none) const;

/** cross product @return this x q */
Point3 cross(const Point3 &q, OptionalJacobian<3, 3> H_p = boost::none, //
GTSAM_EXPORT Point3 cross(const Point3 &q, OptionalJacobian<3, 3> H_p = boost::none, //
OptionalJacobian<3, 3> H_q = boost::none) const;

/** dot product @return this * q*/
double dot(const Point3 &q, OptionalJacobian<1, 3> H_p = boost::none, //
GTSAM_EXPORT double dot(const Point3 &q, OptionalJacobian<1, 3> H_p = boost::none, //
OptionalJacobian<1, 3> H_q = boost::none) const;

/// @}
Expand Down Expand Up @@ -130,9 +130,9 @@ class GTSAM_EXPORT Point3 : public Vector3 {
static Point3 Expmap(const Vector3& v) { return Point3(v);}
inline double dist(const Point3& q) const { return (q - *this).norm(); }
Point3 normalize(OptionalJacobian<3, 3> H = boost::none) const { return normalized(H);}
Point3 add(const Point3& q, OptionalJacobian<3, 3> H1 = boost::none,
GTSAM_EXPORT Point3 add(const Point3& q, OptionalJacobian<3, 3> H1 = boost::none,
OptionalJacobian<3, 3> H2 = boost::none) const;
Point3 sub(const Point3& q, OptionalJacobian<3, 3> H1 = boost::none,
GTSAM_EXPORT Point3 sub(const Point3& q, OptionalJacobian<3, 3> H1 = boost::none,
OptionalJacobian<3, 3> H2 = boost::none) const;
/// @}
#endif
Expand Down
38 changes: 19 additions & 19 deletions gtsam/geometry/Pose2.h
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ namespace gtsam {
* @addtogroup geometry
* \nosubgrouping
*/
class GTSAM_EXPORT Pose2: public LieGroup<Pose2, 3> {
class Pose2: public LieGroup<Pose2, 3> {

public:

Expand Down Expand Up @@ -97,10 +97,10 @@ class GTSAM_EXPORT Pose2: public LieGroup<Pose2, 3> {
/// @{

/** print with optional string */
void print(const std::string& s = "") const;
GTSAM_EXPORT void print(const std::string& s = "") const;

/** assert equality up to a tolerance */
bool equals(const Pose2& pose, double tol = 1e-9) const;
GTSAM_EXPORT bool equals(const Pose2& pose, double tol = 1e-9) const;

/// @}
/// @name Group
Expand All @@ -110,7 +110,7 @@ class GTSAM_EXPORT Pose2: public LieGroup<Pose2, 3> {
inline static Pose2 identity() { return Pose2(); }

/// inverse
Pose2 inverse() const;
GTSAM_EXPORT Pose2 inverse() const;

/// compose syntactic sugar
inline Pose2 operator*(const Pose2& p2) const {
Expand All @@ -122,16 +122,16 @@ class GTSAM_EXPORT Pose2: public LieGroup<Pose2, 3> {
/// @{

///Exponential map at identity - create a rotation from canonical coordinates \f$ [T_x,T_y,\theta] \f$
static Pose2 Expmap(const Vector3& xi, ChartJacobian H = boost::none);
GTSAM_EXPORT static Pose2 Expmap(const Vector3& xi, ChartJacobian H = boost::none);

///Log map at identity - return the canonical coordinates \f$ [T_x,T_y,\theta] \f$ of this rotation
static Vector3 Logmap(const Pose2& p, ChartJacobian H = boost::none);
GTSAM_EXPORT static Vector3 Logmap(const Pose2& p, ChartJacobian H = boost::none);

/**
* Calculate Adjoint map
* Ad_pose is 3*3 matrix that when applied to twist xi \f$ [T_x,T_y,\theta] \f$, returns Ad_pose(xi)
*/
Matrix3 AdjointMap() const;
GTSAM_EXPORT Matrix3 AdjointMap() const;

/// Apply AdjointMap to twist xi
inline Vector3 Adjoint(const Vector3& xi) const {
Expand All @@ -141,7 +141,7 @@ class GTSAM_EXPORT Pose2: public LieGroup<Pose2, 3> {
/**
* Compute the [ad(w,v)] operator for SE2 as in [Kobilarov09siggraph], pg 19
*/
static Matrix3 adjointMap(const Vector3& v);
GTSAM_EXPORT static Matrix3 adjointMap(const Vector3& v);

/**
* Action of the adjointMap on a Lie-algebra vector y, with optional derivatives
Expand Down Expand Up @@ -177,15 +177,15 @@ class GTSAM_EXPORT Pose2: public LieGroup<Pose2, 3> {
}

/// Derivative of Expmap
static Matrix3 ExpmapDerivative(const Vector3& v);
GTSAM_EXPORT static Matrix3 ExpmapDerivative(const Vector3& v);

/// Derivative of Logmap
static Matrix3 LogmapDerivative(const Pose2& v);
GTSAM_EXPORT static Matrix3 LogmapDerivative(const Pose2& v);

// Chart at origin, depends on compile-time flag SLOW_BUT_CORRECT_EXPMAP
struct ChartAtOrigin {
static Pose2 Retract(const Vector3& v, ChartJacobian H = boost::none);
static Vector3 Local(const Pose2& r, ChartJacobian H = boost::none);
GTSAM_EXPORT static Pose2 Retract(const Vector3& v, ChartJacobian H = boost::none);
GTSAM_EXPORT static Vector3 Local(const Pose2& r, ChartJacobian H = boost::none);
};

using LieGroup<Pose2, 3>::inverse; // version with derivative
Expand All @@ -195,12 +195,12 @@ class GTSAM_EXPORT Pose2: public LieGroup<Pose2, 3> {
/// @{

/** Return point coordinates in pose coordinate frame */
Point2 transformTo(const Point2& point,
GTSAM_EXPORT Point2 transformTo(const Point2& point,
OptionalJacobian<2, 3> Dpose = boost::none,
OptionalJacobian<2, 2> Dpoint = boost::none) const;

/** Return point coordinates in global frame */
Point2 transformFrom(const Point2& point,
GTSAM_EXPORT Point2 transformFrom(const Point2& point,
OptionalJacobian<2, 3> Dpose = boost::none,
OptionalJacobian<2, 2> Dpoint = boost::none) const;

Expand Down Expand Up @@ -233,30 +233,30 @@ class GTSAM_EXPORT Pose2: public LieGroup<Pose2, 3> {
inline const Rot2& rotation() const { return r_; }

//// return transformation matrix
Matrix3 matrix() const;
GTSAM_EXPORT Matrix3 matrix() const;

/**
* Calculate bearing to a landmark
* @param point 2D location of landmark
* @return 2D rotation \f$ \in SO(2) \f$
*/
Rot2 bearing(const Point2& point,
GTSAM_EXPORT Rot2 bearing(const Point2& point,
OptionalJacobian<1, 3> H1=boost::none, OptionalJacobian<1, 2> H2=boost::none) const;

/**
* Calculate bearing to another pose
* @param point SO(2) location of other pose
* @return 2D rotation \f$ \in SO(2) \f$
*/
Rot2 bearing(const Pose2& pose,
GTSAM_EXPORT Rot2 bearing(const Pose2& pose,
OptionalJacobian<1, 3> H1=boost::none, OptionalJacobian<1, 3> H2=boost::none) const;

/**
* Calculate range to a landmark
* @param point 2D location of landmark
* @return range (double)
*/
double range(const Point2& point,
GTSAM_EXPORT double range(const Point2& point,
OptionalJacobian<1, 3> H1=boost::none,
OptionalJacobian<1, 2> H2=boost::none) const;

Expand All @@ -265,7 +265,7 @@ class GTSAM_EXPORT Pose2: public LieGroup<Pose2, 3> {
* @param point 2D location of other pose
* @return range (double)
*/
double range(const Pose2& point,
GTSAM_EXPORT double range(const Pose2& point,
OptionalJacobian<1, 3> H1=boost::none,
OptionalJacobian<1, 3> H2=boost::none) const;

Expand Down
12 changes: 6 additions & 6 deletions gtsam/geometry/SO3.h
Original file line number Diff line number Diff line change
Expand Up @@ -62,13 +62,13 @@ class SO3: public Matrix3, public LieGroup<SO3, 3> {
}

/// Static, named constructor TODO think about relation with above
static SO3 AxisAngle(const Vector3& axis, double theta);
GTSAM_EXPORT static SO3 AxisAngle(const Vector3& axis, double theta);

/// @}
/// @name Testable
/// @{

void print(const std::string& s) const;
GTSAM_EXPORT void print(const std::string& s) const;

bool equals(const SO3 & R, double tol) const {
return equal_with_abs_tol(*this, R, tol);
Expand Down Expand Up @@ -96,19 +96,19 @@ class SO3: public Matrix3, public LieGroup<SO3, 3> {
* Exponential map at identity - create a rotation from canonical coordinates
* \f$ [R_x,R_y,R_z] \f$ using Rodrigues' formula
*/
static SO3 Expmap(const Vector3& omega, ChartJacobian H = boost::none);
GTSAM_EXPORT static SO3 Expmap(const Vector3& omega, ChartJacobian H = boost::none);

/// Derivative of Expmap
static Matrix3 ExpmapDerivative(const Vector3& omega);
GTSAM_EXPORT static Matrix3 ExpmapDerivative(const Vector3& omega);

/**
* Log map at identity - returns the canonical coordinates
* \f$ [R_x,R_y,R_z] \f$ of this rotation
*/
static Vector3 Logmap(const SO3& R, ChartJacobian H = boost::none);
GTSAM_EXPORT static Vector3 Logmap(const SO3& R, ChartJacobian H = boost::none);

/// Derivative of Logmap
static Matrix3 LogmapDerivative(const Vector3& omega);
GTSAM_EXPORT static Matrix3 LogmapDerivative(const Vector3& omega);

Matrix3 AdjointMap() const {
return *this;
Expand Down
2 changes: 1 addition & 1 deletion gtsam/geometry/tests/testCalibratedCamera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -206,7 +206,7 @@ TEST( CalibratedCamera, DBackprojectFromCamera)
static Point3 backproject(const Pose3& pose, const Point2& point, const double& depth) {
return CalibratedCamera(pose).backproject(point, depth);
}
TEST( PinholePose, Dbackproject)
TEST( PinholePose, DbackprojectCalibCamera)
{
Matrix36 Dpose;
Matrix31 Ddepth;
Expand Down
Loading