43template <
class CAMERA>
49 typedef typename CAMERA::CalibrationType CALIBRATION;
69 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
82 typedef Eigen::Matrix<double, ZDim, DimBlock>
84 typedef std::vector<MatrixZD, Eigen::aligned_allocator<MatrixZD>>
99 const boost::shared_ptr<Cameras>&
cameraRig,
103 if (Base::params_.degeneracyMode != gtsam::ZERO_ON_DEGENERACY)
104 throw std::runtime_error(
105 "SmartProjectionRigFactor: "
106 "degeneracyMode must be set to ZERO_ON_DEGENERACY");
107 if (Base::params_.linearizationMode != gtsam::HESSIAN)
108 throw std::runtime_error(
109 "SmartProjectionRigFactor: "
110 "linearizationMode must be set to HESSIAN");
129 const Key& world_P_body_key2,
const double& alpha,
130 const size_t& cameraId = 0) {
136 std::make_pair(world_P_body_key1, world_P_body_key2));
140 if (std::find(this->
keys_.begin(), this->keys_.end(), world_P_body_key1) ==
142 this->
keys_.push_back(world_P_body_key1);
143 if (std::find(this->
keys_.begin(), this->keys_.end(), world_P_body_key2) ==
145 this->
keys_.push_back(world_P_body_key2);
167 void add(
const Point2Vector& measurements,
169 const std::vector<double>&
alphas,
170 const FastVector<size_t>&
cameraIds = FastVector<size_t>()) {
175 throw std::runtime_error(
176 "SmartProjectionPoseFactorRollingShutter: "
177 "trying to add inconsistent inputs");
180 throw std::runtime_error(
181 "SmartProjectionPoseFactorRollingShutter: "
182 "camera rig includes multiple camera "
183 "but add did not input cameraIds");
185 for (
size_t i = 0; i < measurements.size(); i++) {
215 const std::string& s =
"",
216 const KeyFormatter& keyFormatter = DefaultKeyFormatter)
const override {
217 std::cout << s <<
"SmartProjectionPoseFactorRollingShutter: \n ";
218 for (
size_t i = 0; i <
cameraIds_.size(); i++) {
219 std::cout <<
"-- Measurement nr " << i << std::endl;
220 std::cout <<
" pose1 key: "
222 std::cout <<
" pose2 key: "
224 std::cout <<
" alpha: " <<
alphas_[i] << std::endl;
225 std::cout <<
"cameraId: " <<
cameraIds_[i] << std::endl;
226 (*cameraRig_)[
cameraIds_[i]].print(
"camera in rig:\n");
237 double keyPairsEqual =
true;
238 if (this->world_P_body_key_pairs_.size() ==
240 for (
size_t k = 0; k < this->world_P_body_key_pairs_.size(); k++) {
245 if (!(key1own == key1e) || !(key2own == key2e)) {
246 keyPairsEqual =
false;
251 keyPairsEqual =
false;
267 typename Base::Cameras
cameras;
268 for (
size_t i = 0; i < this->
measured_.size();
270 const Pose3& w_P_body1 =
272 const Pose3& w_P_body2 =
274 double interpolationFactor =
alphas_[i];
275 const Pose3& w_P_body =
276 interpolate<Pose3>(w_P_body1, w_P_body2, interpolationFactor);
278 const Pose3& body_P_cam = camera_i.pose();
279 const Pose3& w_P_cam = w_P_body.compose(body_P_cam);
281 make_shared<typename CAMERA::CalibrationType>(
282 camera_i.calibration()));
291 if (this->
active(values)) {
308 const Values& values)
const {
310 throw(
"computeJacobiansWithTriangulatedPoint");
312 size_t numViews = this->
measured_.size();
313 E = Matrix::Zero(2 * numViews,
315 b = Vector::Zero(2 * numViews);
317 Eigen::Matrix<double, ZDim, DimPose> dProject_dPoseCam;
318 Eigen::Matrix<double, DimPose, DimPose> dInterpPose_dPoseBody1,
319 dInterpPose_dPoseBody2, dPoseCam_dInterpPose;
320 Eigen::Matrix<double, ZDim, 3> Ei;
322 for (
size_t i = 0; i < numViews; i++) {
325 double interpolationFactor =
alphas_[i];
328 interpolate<Pose3>(w_P_body1, w_P_body2, interpolationFactor,
329 dInterpPose_dPoseBody1, dInterpPose_dPoseBody2);
331 auto body_P_cam = camera_i.pose();
332 auto w_P_cam = w_P_body.compose(body_P_cam, dPoseCam_dInterpPose);
336 Point2 reprojectionError_i =
337 Point2(camera.
project(*this->result_, dProject_dPoseCam, Ei) -
338 this->measured_.at(i));
339 Eigen::Matrix<double, ZDim, DimBlock> J;
340 J.block(0, 0,
ZDim, 6) =
341 dProject_dPoseCam * dPoseCam_dInterpPose *
342 dInterpPose_dPoseBody1;
343 J.block(0, 6,
ZDim, 6) =
344 dProject_dPoseCam * dPoseCam_dInterpPose *
345 dInterpPose_dPoseBody2;
350 b.segment<
ZDim>(
row) = -reprojectionError_i;
358 const Values& values,
const double& lambda = 0.0,
359 bool diagonalDamping =
false)
const {
363 size_t nrUniqueKeys =
371 std::vector<Matrix> Gs(nrUniqueKeys * (nrUniqueKeys + 1) / 2);
372 std::vector<Vector> gs(nrUniqueKeys);
376 throw std::runtime_error(
377 "SmartProjectionPoseFactorRollingShutter: "
378 "measured_.size() inconsistent with input");
386 for (Vector& v : gs) v = Vector::Zero(
DimPose);
387 return boost::make_shared<RegularHessianFactor<DimPose>>(this->
keys_,
390 throw std::runtime_error(
391 "SmartProjectionPoseFactorRollingShutter: "
392 "only supported degeneracy mode is ZERO_ON_DEGENERACY");
403 for (
size_t i = 0; i < Fs.size(); i++)
406 Matrix3 P = Base::Cameras::PointCov(E, lambda, diagonalDamping);
420 Base::Cameras::template SchurComplementAndRearrangeBlocks<3, 12, 6>(
421 Fs, E, P, b, nonuniqueKeys, this->
keys_);
423 return boost::make_shared<RegularHessianFactor<DimPose>>(
424 this->
keys_, augmentedHessianUniqueKeys);
435 const Values& values,
const double& lambda = 0.0)
const {
442 throw std::runtime_error(
443 "SmartProjectionPoseFactorRollingShutter: "
444 "unknown linearization mode");
450 const Values& values)
const override {
457 template <
class ARCHIVE>
458 void serialize(ARCHIVE& ar,
const unsigned int ) {
459 ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Base);
465template <
class CAMERA>
467 :
public Testable<SmartProjectionPoseFactorRollingShutter<CAMERA>> {};
Base class to create smart factors on poses or cameras.
Smart factor on cameras (pose + calibration)
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
const MATRIX::ConstRowXpr row(const MATRIX &A, size_t j)
Extracts a row view from a matrix that avoids a copy.
Definition: Matrix.h:225
Vector2 Point2
As of GTSAM 4, in order to make GTSAM more lean, it is now possible to just typedef Point2 to Vector2...
Definition: Point2.h:27
noiseModel::Base::shared_ptr SharedNoiseModel
Note, deliberately not in noiseModel namespace.
Definition: NoiseModel.h:736
bool equal(const T &obj1, const T &obj2, double tol)
Call equal on the object.
Definition: Testable.h:84
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:69
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:35
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
Definition: SymmetricBlockMatrix.h:52
A helper that implements the traits interface for GTSAM types.
Definition: Testable.h:151
A set of cameras, all with their own calibration.
Definition: CameraSet.h:35
Definition: PinholeCamera.h:33
Point2 project(const Point3 &pw, OptionalJacobian< 2, 6 > Dpose=boost::none, OptionalJacobian< 2, 3 > Dpoint=boost::none, OptionalJacobian< 2, DimK > Dcal=boost::none) const
project a 3D point from world coordinates into the image
Definition: PinholePose.h:118
This is the base class for all factor types.
Definition: Factor.h:56
KeyVector keys_
The keys involved in this factor.
Definition: Factor.h:73
Nonlinear factor base class.
Definition: NonlinearFactor.h:43
virtual bool active(const Values &) const
Checks whether a factor should be used based on a set of values.
Definition: NonlinearFactor.h:106
A non-templated config holding any types of Manifold-group elements.
Definition: Values.h:63
const ValueType at(Key j) const
Retrieve a variable by key j.
Definition: Values-inl.h:346
SharedIsotropic noiseModel_
As of Feb 22, 2015, the noise model is the same for all measurements and is isotropic.
Definition: SmartFactorBase.h:72
ZVector measured_
Measurements for each of the m views.
Definition: SmartFactorBase.h:79
const ZVector & measured() const
Return the 2D measurements (ZDim, in general).
Definition: SmartFactorBase.h:159
Definition: SmartFactorParams.h:42
LinearizationMode linearizationMode
How to linearize the factor.
Definition: SmartFactorParams.h:44
DegeneracyMode degeneracyMode
How to linearize the factor.
Definition: SmartFactorParams.h:45
SmartProjectionFactor: triangulates point and keeps an estimate of it around.
Definition: SmartProjectionFactor.h:45
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
Definition: SmartProjectionFactor.h:103
TriangulationResult result_
result from triangulateSafe
Definition: SmartProjectionFactor.h:63
TriangulationResult triangulateSafe(const Cameras &cameras) const
Call gtsam::triangulateSafe iff we need to re-triangulate.
Definition: SmartProjectionFactor.h:174
double totalReprojectionError(const Cameras &cameras, boost::optional< Point3 > externalPoint=boost::none) const
Calculate the error of the factor.
Definition: SmartProjectionFactor.h:411
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
Definition: SmartProjectionFactor.h:115
CAMERA Camera
shorthand for a set of cameras
Definition: SmartProjectionFactor.h:74
Definition: SmartProjectionPoseFactorRollingShutter.h:45
void computeJacobiansWithTriangulatedPoint(FBlocks &Fs, Matrix &E, Vector &b, const Values &values) const
Compute jacobian F, E and error vector at a given linearization point.
Definition: SmartProjectionPoseFactorRollingShutter.h:307
double error(const Values &values) const override
error calculates the error of the factor.
Definition: SmartProjectionPoseFactorRollingShutter.h:290
void add(const Point2Vector &measurements, const std::vector< std::pair< Key, Key > > &world_P_body_key_pairs, const std::vector< double > &alphas, const FastVector< size_t > &cameraIds=FastVector< size_t >())
Variant of the previous "add" function in which we include multiple measurements.
Definition: SmartProjectionPoseFactorRollingShutter.h:167
Base::Cameras cameras(const Values &values) const override
Collect all cameras involved in this factor.
Definition: SmartProjectionPoseFactorRollingShutter.h:266
static const int DimBlock
size of the variable stacking 2 poses from which the observation pose is interpolated
Definition: SmartProjectionPoseFactorRollingShutter.h:77
static const int DimPose
Pose3 dimension.
Definition: SmartProjectionPoseFactorRollingShutter.h:80
boost::shared_ptr< RegularHessianFactor< DimPose > > createHessianFactor(const Values &values, const double &lambda=0.0, bool diagonalDamping=false) const
linearize and return a Hessianfactor that is an approximation of error(p)
Definition: SmartProjectionPoseFactorRollingShutter.h:357
std::vector< double > alphas_
interpolation factor (one for each observation) to interpolate between pair of consecutive poses
Definition: SmartProjectionPoseFactorRollingShutter.h:58
const FastVector< size_t > & cameraIds() const
return the calibration object
Definition: SmartProjectionPoseFactorRollingShutter.h:207
const std::vector< double > & alphas() const
return the interpolation factors alphas
Definition: SmartProjectionPoseFactorRollingShutter.h:201
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
Definition: SmartProjectionPoseFactorRollingShutter.h:214
boost::shared_ptr< GaussianFactor > linearizeDamped(const Values &values, const double &lambda=0.0) const
Linearize to Gaussian Factor (possibly adding a damping factor Lambda for LM)
Definition: SmartProjectionPoseFactorRollingShutter.h:434
SmartProjectionPoseFactorRollingShutter(const SharedNoiseModel &sharedNoiseModel, const boost::shared_ptr< Cameras > &cameraRig, const SmartProjectionParams ¶ms=SmartProjectionParams())
Constructor.
Definition: SmartProjectionPoseFactorRollingShutter.h:97
const std::vector< std::pair< Key, Key > > & world_P_body_key_pairs() const
return (for each observation) the keys of the pair of poses from which we interpolate
Definition: SmartProjectionPoseFactorRollingShutter.h:196
FastVector< size_t > cameraIds_
vector of camera Ids (one for each observation, in the same order), identifying which camera took the...
Definition: SmartProjectionPoseFactorRollingShutter.h:66
boost::shared_ptr< typename Base::Cameras > cameraRig_
one or more cameras taking observations (fixed poses wrt body + fixed intrinsics)
Definition: SmartProjectionPoseFactorRollingShutter.h:62
boost::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
Definition: SmartProjectionPoseFactorRollingShutter.h:75
const boost::shared_ptr< Cameras > & cameraRig() const
return the calibration object
Definition: SmartProjectionPoseFactorRollingShutter.h:204
void add(const Point2 &measured, const Key &world_P_body_key1, const Key &world_P_body_key2, const double &alpha, const size_t &cameraId=0)
add a new measurement, with 2 pose keys, interpolation factor, and cameraId
Definition: SmartProjectionPoseFactorRollingShutter.h:128
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
Definition: SmartProjectionPoseFactorRollingShutter.h:232
friend class boost::serialization::access
Serialization function.
Definition: SmartProjectionPoseFactorRollingShutter.h:456
std::vector< std::pair< Key, Key > > world_P_body_key_pairs_
The keys of the pose of the body (with respect to an external world frame): two consecutive poses for...
Definition: SmartProjectionPoseFactorRollingShutter.h:54
static const int ZDim
Measurement dimension (Point2)
Definition: SmartProjectionPoseFactorRollingShutter.h:81
boost::shared_ptr< GaussianFactor > linearize(const Values &values) const override
linearize
Definition: SmartProjectionPoseFactorRollingShutter.h:449
SmartProjectionPoseFactorRollingShutter()
Default constructor, only for serialization.
Definition: SmartProjectionPoseFactorRollingShutter.h:88
~SmartProjectionPoseFactorRollingShutter() override=default
Virtual destructor.