added Cal3_S2 header and Frank's recommendations
parent
d9923fc3cc
commit
8fdbf2fa6e
|
@ -19,6 +19,7 @@
|
|||
#include <gtsam/inference/Symbol.h>
|
||||
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
|
||||
#include <gtsam/geometry/PinholeCamera.h>
|
||||
#include <gtsam/geometry/Cal3_S2.h>
|
||||
#include <boost/make_shared.hpp>
|
||||
|
||||
using namespace gtsam;
|
||||
|
|
|
@ -5,6 +5,7 @@
|
|||
*/
|
||||
|
||||
#include <gtsam/geometry/PinholeCamera.h>
|
||||
#include <gtsam/geometry/Cal3_S2.h>
|
||||
#include <gtsam/nonlinear/ISAM2.h>
|
||||
#include <gtsam/slam/BetweenFactor.h>
|
||||
#include <gtsam/slam/SmartProjectionPoseFactor.h>
|
||||
|
|
|
@ -1,5 +1,6 @@
|
|||
|
||||
#include <gtsam/geometry/PinholeCamera.h>
|
||||
#include <gtsam/geometry/Cal3_S2.h>
|
||||
#include <gtsam/inference/Symbol.h>
|
||||
#include <gtsam/navigation/ImuBias.h>
|
||||
#include <gtsam/navigation/ImuFactor.h>
|
||||
|
@ -34,7 +35,7 @@ int main(int argc, char* argv[]) {
|
|||
double radius = 30;
|
||||
const Point3 up(0, 0, 1), target(0, 0, 0);
|
||||
const Point3 position(radius, 0, 0);
|
||||
const PinholeCamera<Cal3_S2> camera = PinholeCamera<Cal3_S2>::Lookat(position, target, up);
|
||||
const auto camera = PinholeCamera<Cal3_S2>::Lookat(position, target, up);
|
||||
const auto pose_0 = camera.pose();
|
||||
|
||||
// Now, create a constant-twist scenario that makes the camera orbit the
|
||||
|
|
|
@ -356,9 +356,11 @@ TEST(RangeFactor, Point3) {
|
|||
/* ************************************************************************* */
|
||||
// Do tests with PinholeCamera<Cal3_S2>
|
||||
TEST( RangeFactor, Camera) {
|
||||
RangeFactor<PinholeCamera<Cal3_S2>,Point3> factor1(poseKey, pointKey, measurement, model);
|
||||
RangeFactor<PinholeCamera<Cal3_S2>,Pose3> factor2(poseKey, pointKey, measurement, model);
|
||||
RangeFactor<PinholeCamera<Cal3_S2>,PinholeCamera<Cal3_S2>> factor3(poseKey, pointKey, measurement, model);
|
||||
using Camera = PinholeCamera<Cal3_S2>;
|
||||
|
||||
RangeFactor<Camera, Point3> factor1(poseKey, pointKey, measurement, model);
|
||||
RangeFactor<Camera, Pose3> factor2(poseKey, pointKey, measurement, model);
|
||||
RangeFactor<Camera, Camera> factor3(poseKey, pointKey, measurement, model);
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
|
|
Loading…
Reference in New Issue