Rename factor
parent
1837745568
commit
5f667b4425
|
@ -253,6 +253,24 @@ class EssentialTransferFactorK
|
|||
TransferEdges<EM>(edge1, edge2),
|
||||
triplets_(triplets) {}
|
||||
|
||||
/**
|
||||
* @brief Constructor that accepts a vector of point triplets.
|
||||
*
|
||||
* @note Calibrations are assumed all same, using given key `keyK`.
|
||||
*
|
||||
* @param edge1 First EdgeKey specifying E1: (a, c) or (c, a)
|
||||
* @param edge2 Second EdgeKey specifying E2: (b, c) or (c, b)
|
||||
* @param keyK Calibration key for all views.
|
||||
* @param triplets A vector of triplets containing (pa, pb, pc)
|
||||
* @param model An optional SharedNoiseModel
|
||||
*/
|
||||
EssentialTransferFactorK(EdgeKey edge1, EdgeKey edge2, Key keyK,
|
||||
const std::vector<Triplet>& triplets,
|
||||
const SharedNoiseModel& model = nullptr)
|
||||
: Base(model, edge1, edge2, keyK, keyK, keyK),
|
||||
TransferEdges<EM>(edge1, edge2),
|
||||
triplets_(triplets) {}
|
||||
|
||||
/// Transfer points pa and pb to view c and evaluate error.
|
||||
Vector2 TransferError(const Matrix3& Eca, const K& Ka, const Point2& pa,
|
||||
const Matrix3& Ecb, const K& Kb, const Point2& pb,
|
||||
|
|
|
@ -98,8 +98,11 @@ virtual class EssentialTransferFactor : gtsam::NoiseModelFactor {
|
|||
template <K = {gtsam::Cal3_S2, gtsam::Cal3f, gtsam::Cal3Bundler}>
|
||||
virtual class EssentialTransferFactorK : gtsam::NoiseModelFactor {
|
||||
EssentialTransferFactorK(gtsam::EdgeKey edge1, gtsam::EdgeKey edge2,
|
||||
const std::vector<std::tuple<gtsam::Point2, gtsam::Point2, gtsam::Point2>>& triplets,
|
||||
const gtsam::noiseModel::Base* model = nullptr);
|
||||
const std::vector<std::tuple<gtsam::Point2, gtsam::Point2, gtsam::Point2>>& triplets,
|
||||
const gtsam::noiseModel::Base* model = nullptr);
|
||||
EssentialTransferFactorK(gtsam::EdgeKey edge1, gtsam::EdgeKey edge2, size_t keyK,
|
||||
const std::vector<std::tuple<gtsam::Point2, gtsam::Point2, gtsam::Point2>>& triplets,
|
||||
const gtsam::noiseModel::Base* model = nullptr);
|
||||
};
|
||||
|
||||
#include <gtsam/sfm/ShonanFactor.h>
|
||||
|
|
|
@ -154,7 +154,7 @@ TEST(TransferFactor, MultipleTuples) {
|
|||
}
|
||||
|
||||
//*************************************************************************
|
||||
// Test for EssentialTransferFactor
|
||||
// Test for EssentialTransferFactorK
|
||||
TEST(EssentialTransferFactor, Jacobians) {
|
||||
using namespace fixture;
|
||||
|
||||
|
|
Loading…
Reference in New Issue