Namespaces | Typedefs | Functions | Variables
smartFactorScenarios.h File Reference
#include <gtsam/geometry/Cal3Bundler.h>
#include <gtsam/geometry/Cal3_S2.h>
#include <gtsam/geometry/SphericalCamera.h>
#include <gtsam/slam/GeneralSFMFactor.h>
#include <gtsam/slam/SmartProjectionFactor.h>
#include <gtsam/slam/SmartProjectionPoseFactor.h>
#include "../SmartProjectionRigFactor.h"
Include dependency graph for smartFactorScenarios.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

 bundler
 
 bundlerPose
 
 sphericalCamera
 
 vanilla
 
 vanillaPose
 
 vanillaPose2
 

Typedefs

typedef PinholeCamera< Cal3_S2vanilla::Camera
 
typedef PinholePose< Cal3_S2vanillaPose::Camera
 
typedef PinholePose< Cal3_S2vanillaPose2::Camera
 
typedef PinholeCamera< Cal3Bundlerbundler::Camera
 
typedef PinholePose< Cal3BundlerbundlerPose::Camera
 
typedef SphericalCamera sphericalCamera::Camera
 
typedef CameraSet< CameravanillaPose::Cameras
 
typedef CameraSet< CameravanillaPose2::Cameras
 
typedef CameraSet< Camerabundler::Cameras
 
typedef CameraSet< CamerabundlerPose::Cameras
 
typedef CameraSet< CamerasphericalCamera::Cameras
 
typedef GeneralSFMFactor< Camera, Point3vanilla::SFMFactor
 
typedef GeneralSFMFactor< Camera, Point3bundler::SFMFactor
 
typedef SmartProjectionFactor< Cameravanilla::SmartFactor
 
typedef SmartProjectionPoseFactor< Cal3_S2vanillaPose::SmartFactor
 
typedef SmartProjectionPoseFactor< Cal3_S2vanillaPose2::SmartFactor
 
typedef SmartProjectionFactor< Camerabundler::SmartFactor
 
typedef SmartProjectionPoseFactor< Cal3BundlerbundlerPose::SmartFactor
 
typedef SmartProjectionRigFactor< CamerasphericalCamera::SmartFactorP
 
typedef SmartProjectionRigFactor< CameravanillaPose::SmartRigFactor
 
typedef SmartProjectionRigFactor< CameravanillaPose2::SmartRigFactor
 
typedef SmartProjectionRigFactor< CamerabundlerPose::SmartRigFactor
 

Functions

static const Camera vanilla::cam1 (level_pose, K2)
 
static const Camera vanillaPose::cam1 (level_pose, sharedK)
 
static const Camera vanillaPose2::cam1 (level_pose, sharedK2)
 
static const Camera bundler::cam1 (level_pose, K)
 
static const Camera bundlerPose::cam1 (level_pose, sharedBundlerK)
 
static const Camera sphericalCamera::cam1 (level_pose)
 
static const Camera vanilla::cam2 (pose_right, K2)
 
static const Camera vanillaPose::cam2 (pose_right, sharedK)
 
static const Camera vanillaPose2::cam2 (pose_right, sharedK2)
 
static const Camera bundler::cam2 (pose_right, K)
 
static const Camera bundlerPose::cam2 (pose_right, sharedBundlerK)
 
static const Camera sphericalCamera::cam2 (pose_right)
 
static const Camera vanilla::cam3 (pose_above, K2)
 
static const Camera vanillaPose::cam3 (pose_above, sharedK)
 
static const Camera vanillaPose2::cam3 (pose_above, sharedK2)
 
static const Camera bundler::cam3 (pose_above, K)
 
static const Camera bundlerPose::cam3 (pose_above, sharedBundlerK)
 
static const Camera sphericalCamera::cam3 (pose_above)
 
static const EmptyCal::shared_ptr sphericalCamera::emptyK (new EmptyCal())
 
static const Cal3_S2 vanilla::K (fov, w, h)
 
static const Cal3Bundler bundler::K (500, 1e-3, 1e-3, 0, 0)
 
static const Cal3_S2 vanilla::K2 (1500, 1200, 0, w, h)
 
static const Camera vanilla::level_camera (level_pose, K2)
 
static const Camera vanillaPose::level_camera (level_pose, sharedK)
 
static const Camera vanillaPose2::level_camera (level_pose, sharedK2)
 
static const Camera bundler::level_camera (level_pose, K)
 
static const Camera bundlerPose::level_camera (level_pose, sharedBundlerK)
 
static const Camera sphericalCamera::level_camera (level_pose)
 
static const Camera vanilla::level_camera_right (pose_right, K2)
 
static const Camera vanillaPose::level_camera_right (pose_right, sharedK)
 
static const Camera vanillaPose2::level_camera_right (pose_right, sharedK2)
 
static const Camera bundler::level_camera_right (pose_right, K)
 
static const Camera bundlerPose::level_camera_right (pose_right, sharedBundlerK)
 
static const Camera sphericalCamera::level_camera_right (pose_right)
 
template<class CAMERA >
CAMERA perturbCameraPose (const CAMERA &camera)
 
template<class CAMERA >
void projectToMultipleCameras (const CAMERA &cam1, const CAMERA &cam2, const CAMERA &cam3, Point3 landmark, typename CAMERA::MeasurementVector &measurements_cam)
 
static const std::shared_ptr< Cal3BundlerbundlerPose::sharedBundlerK (new Cal3Bundler(500, 1e-3, 1e-3, 1000, 2000))
 
static const Cal3_S2::shared_ptr vanillaPose::sharedK (new Cal3_S2(fov, w, h))
 
static const Cal3_S2::shared_ptr vanillaPose2::sharedK2 (new Cal3_S2(1500, 1200, 0, 640, 480))
 

Variables

static const Point2 vanilla::level_uv = level_camera.project(landmark1)
 
static const Point2 bundler::level_uv = level_camera.project(landmark1)
 
static const Point2 vanilla::level_uv_right = level_camera_right.project(landmark1)
 
static const Point2 bundler::level_uv_right = level_camera_right.project(landmark1)
 
static const SmartProjectionParams vanilla::params
 
static const Pose3 bundler::pose1 = level_pose
 

Function Documentation

◆ perturbCameraPose()

template<class CAMERA >
CAMERA perturbCameraPose ( const CAMERA &  camera)

Definition at line 153 of file smartFactorScenarios.h.

◆ projectToMultipleCameras()

template<class CAMERA >
void projectToMultipleCameras ( const CAMERA &  cam1,
const CAMERA &  cam2,
const CAMERA &  cam3,
Point3  landmark,
typename CAMERA::MeasurementVector &  measurements_cam 
)

Definition at line 162 of file smartFactorScenarios.h.



gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:40:54