47 std::vector<std::shared_ptr<Cal3_S2Stereo>>
K_all_;
68 static const int DimPose = 6;
71 typedef std::vector<MatrixZD, Eigen::aligned_allocator<MatrixZD> >
FBlocks;
91 const Key& body_P_cam_key,
92 const std::shared_ptr<Cal3_S2Stereo>&
K);
103 void add(
const std::vector<StereoPoint2>& measurements,
105 const std::vector<std::shared_ptr<Cal3_S2Stereo>>& Ks);
117 void add(
const std::vector<StereoPoint2>& measurements,
119 const std::shared_ptr<Cal3_S2Stereo>&
K);
134 return body_P_cam_keys_;
143 inline std::vector<std::shared_ptr<Cal3_S2Stereo>>
calibration()
const {
167 throw(
"computeJacobiansWithTriangulatedPoint");
169 size_t numViews = measured_.size();
170 E = Matrix::Zero(3 * numViews, 3);
171 b = Vector::Zero(3 * numViews);
172 Matrix dPoseCam_dPoseBody_i, dPoseCam_dPoseExt_i, dProject_dPoseCam_i, Ei;
174 for (
size_t i = 0;
i < numViews;
i++) {
178 w_P_body.
compose(body_P_cam, dPoseCam_dPoseBody_i, dPoseCam_dPoseExt_i),
182 camera.project(*result_, dProject_dPoseCam_i, Ei) - measured_.at(
i));
184 J.block<
ZDim, 6>(0, 0) = dProject_dPoseCam_i * dPoseCam_dPoseBody_i;
185 J.block<
ZDim, 6>(0, 6) = dProject_dPoseCam_i * dPoseCam_dPoseExt_i;
189 J.block<1, 12>(1, 0) = Matrix::Zero(1, 12);
190 Ei.block<1, 3>(1, 0) = Matrix::Zero(1, 3);
191 reprojectionError_i =
StereoPoint2(reprojectionError_i.uL(), 0.0,
192 reprojectionError_i.v());
197 b.segment<ZDim>(
row) = -reprojectionError_i.vector();
198 E.block<3, 3>(
row, 0) = Ei;
205 const Values& values,
const double lambda = 0.0,
bool diagonalDamping =
211 size_t nrUniqueKeys = keys_.size();
215 std::vector < Matrix > Gs(nrUniqueKeys * (nrUniqueKeys + 1) / 2);
216 std::vector<Vector> gs(nrUniqueKeys);
218 if (this->measured_.size() != cameras(values).size())
219 throw std::runtime_error(
"SmartStereoProjectionHessianFactor: this->" 220 "measured_.size() inconsistent with input");
227 m = Matrix::Zero(DimPose, DimPose);
229 v = Vector::Zero(DimPose);
230 return std::make_shared < RegularHessianFactor<DimPose>
231 > (keys_, Gs, gs, 0.0);
238 computeJacobiansAndCorrectForMissingMeasurements(Fs, E, b, values);
241 noiseModel_->WhitenSystem(E, b);
242 for (
size_t i = 0;
i < Fs.size();
i++)
243 Fs[
i] = noiseModel_->Whiten(Fs[
i]);
247 Cameras::ComputePointCovariance <3> (
P,
E,
lambda, diagonalDamping);
251 for (
size_t i = 0; i < world_P_body_keys_.size(); i++) {
252 nonuniqueKeys.push_back(world_P_body_keys_.at(i));
253 nonuniqueKeys.push_back(body_P_cam_keys_.at(i));
257 Cameras::SchurComplementAndRearrangeBlocks<3,DimBlock,DimPose>(Fs,
E,
P,
b,
258 nonuniqueKeys, keys_);
260 return std::make_shared < RegularHessianFactor<DimPose>
261 > (keys_, augmentedHessianUniqueKeys);
270 const Values& values,
const double lambda = 0.0)
const {
272 switch (params_.linearizationMode) {
274 return createHessianFactor(values,
lambda);
276 throw std::runtime_error(
277 "SmartStereoProjectionFactorPP: unknown linearization mode");
284 return linearizeDamped(values);
288 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 289 friend class boost::serialization::access; 291 template<
class ARCHIVE>
292 void serialize(ARCHIVE& ar,
const unsigned int ) {
293 ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
294 ar & BOOST_SERIALIZATION_NVP(K_all_);
303 SmartStereoProjectionFactorPP> {
void print(const Matrix &A, const string &s, ostream &stream)
static const int ZDim
Measurement dimension (Point2)
const KeyVector & getExtrinsicPoseKeys() const
equals
const MATRIX::ConstRowXpr row(const MATRIX &A, size_t j)
std::string serialize(const T &input)
serializes to a string
const ValueType at(Key j) const
CameraSet< Camera > Cameras
Smart stereo factor on StereoCameras (pose)
#define EIGEN_MAKE_ALIGNED_OPERATOR_NEW
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
static const int DimBlock
static const KeyFormatter DefaultKeyFormatter
static const SmartProjectionParams params
std::vector< std::shared_ptr< Cal3_S2Stereo > > calibration() const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef SmartStereoProjectionFactor Base
shorthand for base class type
std::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
std::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)
Array< int, Dynamic, 1 > v
Array< double, 1, 3 > e(1./3., 0.5, 2.)
std::shared_ptr< GaussianFactor > linearizeDamped(const Values &values, const double lambda=0.0) const
KeyVector body_P_cam_keys_
The keys corresponding to the extrinsic pose calibration for each view (pose that transform from came...
TriangulationResult triangulateSafe(const CameraSet< CAMERA > &cameras, const typename CAMERA::MeasurementVector &measured, const TriangulationParameters ¶ms)
triangulateSafe: extensive checking of the outcome
JacobiRotation< float > J
std::vector< std::shared_ptr< Cal3_S2Stereo > > K_all_
shared pointer to calibration object (one for each camera)
Class compose(const Class &g) const
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
cout<< "The eigenvalues of A are:"<< endl<< ces.eigenvalues()<< endl;cout<< "The matrix of eigenvectors, V, is:"<< endl<< ces.eigenvectors()<< endl<< endl;complex< float > lambda
std::shared_ptr< GaussianFactor > linearize(const Values &values) const override
linearize
Eigen::Matrix< double, ZDim, DimBlock > MatrixZD
graph add(PriorFactor< Pose2 >(1, priorMean, priorNoise))
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
The matrix class, also used for vectors and row-vectors.
static const CalibratedCamera camera(kDefaultPose)
std::vector< MatrixZD, Eigen::aligned_allocator< MatrixZD > > FBlocks
SmartStereoProjectionFactorPP This
shorthand for this class
std::uint64_t Key
Integer nonlinear key type.
noiseModel::Base::shared_ptr SharedNoiseModel
void computeJacobiansAndCorrectForMissingMeasurements(FBlocks &Fs, Matrix &E, Vector &b, const Values &values) const
SmartProjectionParams SmartStereoProjectionParams
KeyVector world_P_body_keys_
The keys corresponding to the pose of the body (with respect to an external world frame) for each vie...