43 template<
class GEOMETRY_TYPE>
49 "landmark not added");
60 Eigen::Vector2d measurement;
61 multiFramePtr->getKeypoint(camIdx, keypointIdx, measurement);
62 Eigen::Matrix2d information = Eigen::Matrix2d::Identity();
64 multiFramePtr->getKeypointSize(camIdx, keypointIdx, size);
65 information *= 64.0 / (size * size);
72 multiFramePtr->template geometryAs<GEOMETRY_TYPE>(camIdx),
73 camIdx, measurement, information));
75 ::ceres::ResidualBlockId retVal =
mapPtr_->addResidualBlock(
78 mapPtr_->parameterBlockPtr(poseId),
79 mapPtr_->parameterBlockPtr(landmarkId),
81 statesMap_.at(poseId).sensors.at(SensorStates::Camera).at(camIdx).at(
82 CameraSensorStates::T_SCi).id));
86 std::pair<okvis::KeypointIdentifier, uint64_t>(
87 kid, reinterpret_cast<uint64_t>(retVal)));
std::map< uint64_t, States > statesMap_
Buffer for currently considered states.
Definition: Estimator.hpp:555
std::shared_ptr< okvis::ceres::Map > mapPtr_
The underlying okvis::Map.
Definition: Estimator.hpp:557
Unique identifier for a keypoint.
Definition: FrameTypedefs.hpp:58
okvis::PointMap landmarksMap_
Contains all the current landmarks (synched after optimisation).
Definition: Estimator.hpp:563
std::shared_ptr< MultiFrame > MultiFramePtr
For convenience.
Definition: MultiFrame.hpp:272
std::map< uint64_t, okvis::MultiFramePtr > multiFramePtrMap_
remember all needed okvis::MultiFrame.
Definition: Estimator.hpp:556
The 2D keypoint reprojection error.
Definition: ReprojectionError.hpp:56
bool isLandmarkAdded(uint64_t landmarkId) const
Checks whether the landmark is added to the estimator.
Definition: Estimator.hpp:218
::ceres::ResidualBlockId addObservation(uint64_t landmarkId, uint64_t poseId, size_t camIdx, size_t keypointIdx)
Add an observation to a landmark.
std::shared_ptr< ::ceres::LossFunction > cauchyLossFunctionPtr_
Cauchy loss.
Definition: Estimator.hpp:572
#define OKVIS_ASSERT_TRUE_DBG(exceptionType, condition, message)
Definition: assert_macros.hpp:211