42 for (
int i = 0;
i < I.size();
i++)
51 for (
int i = 0;
i < I.size();
i++)
59 for (
int i = 0;
i < I.size();
i++)
68 for (
int i = 0;
i < I.size();
i++)
76 for (
int i = 0;
i < I.size();
i++)
85 for (
int i = 0;
i < I.size();
i++)
93 Values::ConstFiltered<Point2> points = values.
filter<
Point2>();
95 for(
const auto& key_value: points)
96 result.row(j++) = key_value.value;
102 Values::ConstFiltered<Point3> points = values.
filter<
Point3>();
105 for(
const auto& key_value: points)
106 result.row(j++) = key_value.value;
117 Values::ConstFiltered<Pose2> poses = values.
filter<
Pose2>();
120 for(
const auto& key_value: poses)
121 result.row(j++) << key_value.value.x(), key_value.value.y(), key_value.value.theta();
132 Values::ConstFiltered<Pose3> poses = values.
filter<
Pose3>();
135 for(
const auto& key_value: poses) {
136 result.row(j).segment(0, 3) << key_value.value.rotation().matrix().row(0);
137 result.row(j).segment(3, 3) << key_value.value.rotation().matrix().row(1);
138 result.row(j).segment(6, 3) << key_value.value.rotation().matrix().row(2);
139 result.row(j).tail(3) = key_value.value.translation();
159 Vector3(sigmaT, sigmaT, sigmaR));
161 for(
const auto& key_value: values.
filter<
Pose2>()) {
180 throw std::invalid_argument(
"insertBackProjections: Z must be 2*K");
181 if (Z.cols() != J.size())
182 throw std::invalid_argument(
183 "insertBackProjections: J and Z must have same number of entries");
184 for (
int k = 0; k < Z.cols(); k++) {
196 throw std::invalid_argument(
"addMeasurements: Z must be 2*K");
197 if (Z.cols() != J.size())
198 throw std::invalid_argument(
199 "addMeasurements: J and Z must have same number of entries");
200 for (
int k = 0; k < Z.cols(); k++) {
203 Point2(
Z(0, k),
Z(1, k)), model, i,
Key(
J(k)), K, body_P_sensor));
219 boost::shared_ptr<const GenericProjectionFactor<Pose3, Point3> >
p =
245 }
catch (
const std::exception& e1) {
250 }
catch (
const std::exception& e2) {
253 std::cerr <<
"Values[key] is neither Pose2 nor Point2, so skip" << std::endl;
275 return ssBuffer_.str();
280 std::cout.rdbuf(coutBuffer_);
gtsam::enable_if_t< needs_eigen_aligned_allocator< T >::value, boost::shared_ptr< T > > make_shared(Args &&...args)
void perturbPose2(Values &values, double sigmaT, double sigmaR, int32_t seed=42u)
Perturb all Pose2 values using normally distributed noise.
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
Point3 backproject(const Point2 &p, double depth, OptionalJacobian< 3, 6 > Dresult_dpose=boost::none, OptionalJacobian< 3, 2 > Dresult_dp=boost::none, OptionalJacobian< 3, 1 > Dresult_ddepth=boost::none, OptionalJacobian< 3, DimK > Dresult_dcal=boost::none) const
backproject a 2-dimensional point to a 3-dimensional point at given depth
noiseModel::Diagonal::shared_ptr model
void insert(Key j, const Value &val)
void insertBackprojections(Values &values, const PinholeCamera< Cal3_S2 > &camera, const Vector &J, const Matrix &Z, double depth)
Insert a number of initial point values by backprojecting.
static const double sigma
void perturbPoint2(Values &values, double sigma, int32_t seed=42u)
Perturb all Point2 values using normally distributed noise.
KeySet createKeySet(const Vector &I)
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
Matrix reprojectionErrors(const NonlinearFactorGraph &graph, const Values &values)
Calculate the errors of all projection factors in a graph.
Matrix extractPose3(const Values &values)
Extract all Pose3 values into a single matrix [r11 r12 r13 r21 r22 r23 r31 r32 r33 x y z]...
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
void insertProjectionFactors(NonlinearFactorGraph &graph, Key i, const Vector &J, const Matrix &Z, const SharedNoiseModel &model, const Cal3_S2::shared_ptr K, const Pose3 &body_P_sensor=Pose3())
Insert multiple projection factors for a single pose key.
NonlinearFactorGraph graph
Matrix extractPoint2(const Values &values)
Extract all Point2 values into a single matrix [x y].
Base class for all pinhole cameras.
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Class compose(const Class &g) const
void perturbPoint3(Values &values, double sigma, int32_t seed=42u)
Perturb all Point3 values using normally distributed noise.
const ValueType at(Key j) const
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
boost::shared_ptr< This > shared_ptr
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Values allPose3s(const Values &values)
Extract all Pose3 values.
sampling from a NoiseModel
Values allPose2s(const Values &values)
Extract all Pose3 values.
Key symbol(unsigned char c, std::uint64_t j)
JacobiRotation< float > J
Matrix extractPose2(const Values &values)
Extract all Pose2 values into a single matrix [x y theta].
boost::shared_ptr< Diagonal > shared_ptr
Basic bearing factor from 2D measurement.
GTSAM_EXPORT Point2 transformFrom(const Point2 &point, OptionalJacobian< 2, 3 > Dpose=boost::none, OptionalJacobian< 2, 2 > Dpoint=boost::none) const
std::string str() const
return the string
Non-linear factor base classes.
FastList< Key > createKeyList(const Vector &I)
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
KeyVector createKeyVector(const Vector &I)
boost::shared_ptr< Isotropic > shared_ptr
void update(Key j, const Value &val)
~RedirectCout()
destructor – redirect stdout buffer to its original buffer
Annotation indicating that a class derives from another given type.
Values localToWorld(const Values &local, const Pose2 &base, const KeyVector user_keys=KeyVector())
Convert from local to world coordinates.
std::streambuf * coutBuffer_
std::stringstream ssBuffer_
static const CalibratedCamera camera(kDefaultPose)
boost::shared_ptr< Cal3_S2 > shared_ptr
RedirectCout()
constructor – redirect stdout buffer to a stringstream buffer
std::uint64_t Key
Integer nonlinear key type.
Vector unwhitenedError(const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const override
Matrix extractPoint3(const Values &values)
Extract all Point3 values into a single matrix [x y z].
noiseModel::Base::shared_ptr SharedNoiseModel
The most common 5DOF 3D->2D calibration.
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Filtered< Value > filter(const boost::function< bool(Key)> &filterFcn)
Vector sample() const
sample from distribution