25 #define VERBOSE_LEVEL(_LEVEL) if (m_verbose_level>=_LEVEL) std::cout
59 template <
class KF2KF_POSE_TYPE,
class LM_TYPE,
class OBS_TYPE,
class RBA_OPTIONS = RBA_OPTIONS_DEFAULT>
73 static const size_t LM_DIMS = LM_TYPE::LM_DIMS;
74 static const size_t OBS_DIMS = OBS_TYPE::OBS_DIMS;
87 typedef typename KF2KF_POSE_TYPE::pose_t
pose_t;
94 typedef typename kf2kf_pose_traits_t::pose_flag_t
pose_flag_t;
142 num_observations = 0;
144 num_kf2kf_edges_optimized = 0;
145 num_kf2lm_edges_optimized = 0;
146 num_total_scalar_optimized = 0;
147 num_span_tree_numeric_updates=0;
148 total_sqr_error_init=0.;
149 total_sqr_error_final=0.;
150 HAp_condition_number=0.;
151 optimized_k2k_edge_indices.clear();
152 optimized_landmark_indices.clear();
153 extra_results.clear();
168 created_edge_ids.clear();
169 optimize_results.
clear();
185 TNewKeyFrameInfo & out_new_kf_info,
186 const bool run_local_optimization =
true
198 optimize_k2k_edges(true),
199 optimize_landmarks(true),
200 max_visitable_kf_id( static_cast<
TKeyFrameID>(-1) ),
201 dont_optimize_landmarks_seen_less_than_n_times( 2 )
213 const unsigned int win_size,
214 TOptimizeExtraOutputInfo & out_info,
215 const TOptimizeLocalAreaParams ¶ms = TOptimizeLocalAreaParams(),
216 const std::vector<size_t> & observation_indices_to_optimize = std::vector<size_t>()
246 mrpt::opengl::CSetOfObjectsPtr out_scene,
247 mrpt::opengl::CSetOfObjectsPtr out_root_tree = mrpt::opengl::CSetOfObjectsPtr()
253 const std::string &targetFileName,
254 const bool all_landmarks =
false
279 template <
class POSE_GRAPH>
310 const pose_t &init_inv_pose_val =
pose_t() );
324 frameid2pose_map_t & span_tree,
325 const size_t max_depth = std::numeric_limits<size_t>::max(),
326 std::vector<bool> * aux_ws = NULL
341 std::vector<TKeyFrameID> & found_path)
const
352 class K2K_EDGE_VISITOR,
353 class K2F_EDGE_VISITOR
358 const bool rely_on_prebuilt_spanning_trees,
359 KF_VISITOR & kf_visitor,
360 FEAT_VISITOR & feat_visitor,
361 K2K_EDGE_VISITOR & k2k_edge_visitor,
362 K2F_EDGE_VISITOR & k2f_edge_visitor )
const;
421 typename OBS_TYPE::TObservationParams
sensor;
424 typename RBA_OPTIONS::sensor_pose_on_robot_t::parameters_t
sensor_pose;
427 typename RBA_OPTIONS::obs_noise_matrix_t::parameters_t
obs_noise;
455 template <
class HESS_Ap,
class HESS_f,
class HESS_Apf,
class JACOB_COLUMN_dh_dAp,
class JACOB_COLUMN_dh_df>
460 const std::vector<JACOB_COLUMN_dh_dAp*> & dh_dAp,
461 const std::vector<JACOB_COLUMN_dh_df*> & dh_df);
468 template <
class SPARSEBLOCKHESSIAN>
483 base_sorted_lst_t & obs_for_each_base_sorted,
484 std::map<TKeyFrameID,size_t> *out_obs_for_each_base =NULL )
const;
490 std::vector<TNewEdgeInfo> &new_k2k_edge_ids );
497 std::vector<TNewEdgeInfo> &new_k2k_edge_ids );
504 const std::vector<size_t> & run_k2k_edges,
505 const std::vector<size_t> & run_feat_ids_in,
507 const std::vector<size_t> & observation_indices_to_optimize = std::vector<size_t>()
554 const k2k_edge_t* edge,
const topo_dist_t cur_dist)
562 const k2k_edge_t* edge,
const topo_dist_t cur_dist)
567 k2k_edges_to_optimize.push_back(edge->
id);
585 lm_IDs_to_optimize.push_back(lm_ID);
618 const array_landmark_t * fixed_relative_position = NULL,
619 const array_landmark_t * unknown_relative_position_init_val = NULL
624 std::set<TKeyFrameID> & kfs_num_spantrees_to_update,
625 const std::vector<typename TSparseBlocksJacobians_dh_dAp::col_t*> &lst_JacobCols_dAp,
626 const std::vector<typename TSparseBlocksJacobians_dh_df::col_t*> &lst_JacobCols_df );
631 std::vector<typename TSparseBlocksJacobians_dh_dAp::col_t*> &lst_JacobCols_dAp,
632 std::vector<typename TSparseBlocksJacobians_dh_df::col_t*> &lst_JacobCols_df,
633 std::vector<const pose_flag_t*> * out_list_of_required_num_poses = NULL );
663 typename TSparseBlocksJacobians_dh_dAp::TEntry &jacob,
664 const k2f_edge_t & observation,
665 const k2k_edges_deque_t &k2k_edges,
666 std::vector<const pose_flag_t*> *out_list_of_required_num_poses)
const;
679 typename TSparseBlocksJacobians_dh_df::TEntry &jacob,
680 const k2f_edge_t & observation,
681 std::vector<const pose_flag_t*> *out_list_of_required_num_poses)
const;
690 const size_t _k2k_edge_id,
691 const pose_t * _pose_d1_wrt_obs,
692 const pose_t & _pose_base_wrt_d1,
693 const array_landmark_t & _xji_i,
694 const bool _is_inverse_dir,
695 const k2k_edges_deque_t &_k2k_edges,
696 const typename OBS_TYPE::TObservationParams & _sensor_params,
697 const typename RBA_OPTIONS::sensor_pose_on_robot_t::parameters_t & _sensor_pose
717 const typename RBA_OPTIONS::sensor_pose_on_robot_t::parameters_t &
sensor_pose;
723 const pose_t * _pose_base_wrt_obs,
724 const array_landmark_t & _xji_i,
725 const typename OBS_TYPE::TObservationParams & _sensor_params,
726 const typename RBA_OPTIONS::sensor_pose_on_robot_t::parameters_t & _sensor_pose
738 const typename RBA_OPTIONS::sensor_pose_on_robot_t::parameters_t &
sensor_pose;
753 Eigen::VectorXd & minus_grad,
754 const std::vector<typename TSparseBlocksJacobians_dh_dAp::col_t*> & sparse_jacobs_Ap,
755 const std::vector<typename TSparseBlocksJacobians_dh_df::col_t*> & sparse_jacobs_f,
756 const vector_residuals_t & residuals,
757 const std::map<size_t,size_t> &obs_global_idx2residual_idx
776 vector_residuals_t & residuals,
777 const std::vector<TObsUsed> & observations
781 static inline double huber_kernel(
double delta,
const double kernel_param)
RBA_OPTIONS::obs_noise_matrix_t::parameters_t obs_noise
Parameters related to the sensor noise covariance matrix.
The main class for the mrpt-srba: it defines a Relative Bundle-Adjustment (RBA) problem with (optiona...
static const size_t REL_POSE_DIMS
size_t sparse_hessian_update_numeric(SPARSEBLOCKHESSIAN &H) const
Rebuild the Hessian symbolic information from the internal pointers to blocks of Jacobians.
TAllParameters parameters
bool optimize_new_edges_alone
(Default:true) Before running a whole "local area" optimization, try to optimize new edges one by one...
Elemental observation data.
void compute_jacobian_dh_dp(typename TSparseBlocksJacobians_dh_dAp::TEntry &jacob, const k2f_edge_t &observation, const k2k_edges_deque_t &k2k_edges, std::vector< const pose_flag_t * > *out_list_of_required_num_poses) const
==================================================================== j,i lm_id,base_id h h l obs_fr...
A STL-like container which looks and behaves (almost exactly) like a std::map<> but is implemented as...
obs_traits_t::observation_t obs
Observation data.
const rba_problem_state_t & rba_state
TLandmarkID feat_id
Observed what.
RBA_OPTIONS rba_options_type
KF2KF_POSE_TYPE kf2kf_pose_type
virtual void edge_creation_policy(const TKeyFrameID new_kf_id, const typename traits_t::new_kf_observations_t &obs, std::vector< TNewEdgeInfo > &new_k2k_edge_ids)
Implements the edge-creation policy, by default depending on "parameters.edge_creation_policy" if the...
jacobian_traits< KF2KF_POSE_TYPE, LM_TYPE, OBS_TYPE > jacobian_traits_t
TObsUsed(const size_t obs_idx_, k2f_edge_t *const k2f_)
TKeyFrameID max_visitable_kf_id
While exploring around the root KF, stop the BFS when KF_ID>=this number (default:infinity) ...
observation_traits_t::vector_residuals_t vector_residuals_t
const rba_problem_state_t & get_rba_state() const
A set of object, which are referenced to the coordinates framework established in this object...
options::solver_LM_schur_dense_cholesky solver_t
Solver algorithm (Default: Lev-Marq, with Schur, with dense Cholesky)
double max_error_per_obs_to_stop
default: 1e-9
T square(const T x)
Inline function for the square of a number.
TKeyFrameID kf_id
The ID of the newly created KF.
TNumeric_dh_df_params(const pose_t *_pose_base_wrt_obs, const array_landmark_t &_xji_i, const typename OBS_TYPE::TObservationParams &_sensor_params, const typename RBA_OPTIONS::sensor_pose_on_robot_t::parameters_t &_sensor_pose)
bool compute_condition_number
Compute and return to the user the Hessian condition number of k2k edges (default=false) ...
bool visit_filter_k2k(const TKeyFrameID current_kf, const TKeyFrameID next_kf, const k2k_edge_t *edge, const topo_dist_t cur_dist)
uint64_t TLandmarkID
Numeric IDs for landmarks.
const RBA_OPTIONS::sensor_pose_on_robot_t::parameters_t & sensor_pose
topo_dist_t max_tree_depth
Maximum depth for maintained spanning trees.
bool show_unknown_feats_ids
TEdgeCreationPolicy
For usage in RbaEngine.parameters.
const bool is_inverse_dir
hessian_traits< KF2KF_POSE_TYPE, LM_TYPE, OBS_TYPE > hessian_traits_t
RBA_OPTIONS::sensor_pose_on_robot_t::parameters_t sensor_pose
Parameters related to the relative pose of sensors wrt the robot (if applicable)
Different parameters for the SRBA methods.
Usage: A possible type for RBA_OPTIONS::solver_t.
rba_problem_state_t::k2k_edges_deque_t k2k_edges_deque_t
A list (deque) of KF-to-KF edges (unknown relative poses).
const array_landmark_t & xji_i
mrpt::utils::CTimeLogger m_profiler
Profiler for all SRBA operations Enabled by default, can be disabled with enable_time_profiler(false)...
size_t obs_idx
Global index in all_observations.
double reprojection_residuals(vector_residuals_t &residuals, const std::vector< TObsUsed > &observations) const
reprojection_residuals
const k2k_edges_deque_t & get_k2k_edges() const
TOptimizeExtraOutputInfo optimize_results_stg1
Results from the least-squares optimization.
size_t recompute_all_Jacobians(std::vector< typename TSparseBlocksJacobians_dh_dAp::col_t * > &lst_JacobCols_dAp, std::vector< typename TSparseBlocksJacobians_dh_df::col_t * > &lst_JacobCols_df, std::vector< const pose_flag_t * > *out_list_of_required_num_poses=NULL)
Re-evaluate all Jacobians numerically using their symbolic info.
size_t id
0-based index of this edge, in the std::list "k2k_edges".
TSRBAParameters srba
Different parameters for the SRBA methods.
TOptimizeLocalAreaParams()
observation_traits< OBS_TYPE > observation_traits_t
Each of the observations used during the optimization.
bool draw_unknown_feats_ellipses
kf2kf_pose_traits_t::pose_flag_t pose_flag_t
KF2KF_POSE_TYPE::pose_t pose_t
The type of relative poses (e.g. mrpt::poses::CPose3D)
Keyframe-to-keyframe edge: an unknown of the problem.
TCovarianceRecoveryPolicy cov_recovery
Recover covariance? What method to use? (Default: crpLandmarksApprox)
double min_error_reduction_ratio_to_relinearize
default 0.01
uint64_t topo_dist_t
Unsigned integral type for topological distances in a graph/tree.
std::map< TLandmarkID, size_t > lm_times_seen
std::deque< new_kf_observation_t > new_kf_observations_t
A set of all the observations made from a new KF, as provided by the user.
const pose_t * pose_d1_wrt_obs
Usage: A possible type for RBA_OPTIONS::obs_noise_matrix_t.
TKeyFrameID alloc_keyframe()
Users normally won't need to call this directly.
bool visit_filter_k2f(const TKeyFrameID current_kf, const k2f_edge_t *edge, const topo_dist_t cur_dist)
kf2kf_pose_traits_t::TRelativePosesForEachTarget TRelativePosesForEachTarget
static void numeric_dh_df(const array_landmark_t &x, const TNumeric_dh_df_params ¶ms, array_obs_t &y)
Auxiliary method for numeric Jacobian: numerically evaluates the new observation "y" for a small incr...
TNumeric_dh_dAp_params(const size_t _k2k_edge_id, const pose_t *_pose_d1_wrt_obs, const pose_t &_pose_base_wrt_d1, const array_landmark_t &_xji_i, const bool _is_inverse_dir, const k2k_edges_deque_t &_k2k_edges, const typename OBS_TYPE::TObservationParams &_sensor_params, const typename RBA_OPTIONS::sensor_pose_on_robot_t::parameters_t &_sensor_pose)
void enable(bool enabled=true)
This class allows loading and storing values and vectors of different types from a configuration text...
static const size_t LM_DIMS
double max_rho
default: 1.0
kf2kf_pose_traits_t::array_pose_t array_pose_t
static void sparse_hessian_build_symbolic(HESS_Ap &HAp, HESS_f &Hf, HESS_Apf &HApf, const std::vector< JACOB_COLUMN_dh_dAp * > &dh_dAp, const std::vector< JACOB_COLUMN_dh_df * > &dh_df)
Rebuild the Hessian symbolic information from the given Jacobians.
void define_new_keyframe(const typename traits_t::new_kf_observations_t &obs, TNewKeyFrameInfo &out_new_kf_info, const bool run_local_optimization=true)
The most common entry point for SRBA: append a new keyframe (KF) to the map, automatically creates th...
const OBS_TYPE::TObservationParams & sensor_params
observation_traits_t::residual_t residual_t
TOpenGLRepresentationOptions()
double draw_unknown_feats_ellipses_quantiles
traits_t::keyframe_info keyframe_info
TCovarianceRecoveryPolicy
Covariances recovery from Hessian matrix policy, for usage in RbaEngine.parameters.
void optimize_local_area(const TKeyFrameID root_id, const unsigned int win_size, TOptimizeExtraOutputInfo &out_info, const TOptimizeLocalAreaParams ¶ms=TOptimizeLocalAreaParams(), const std::vector< size_t > &observation_indices_to_optimize=std::vector< size_t >())
Runs least-squares optimization for all the unknowns within a given topological distance to a given K...
Generic declaration, of which specializations are defined for each combination of LM+OBS type...
void compute_minus_gradient(Eigen::VectorXd &minus_grad, const std::vector< typename TSparseBlocksJacobians_dh_dAp::col_t * > &sparse_jacobs_Ap, const std::vector< typename TSparseBlocksJacobians_dh_df::col_t * > &sparse_jacobs_f, const vector_residuals_t &residuals, const std::map< size_t, size_t > &obs_global_idx2residual_idx) const
Useful data structures that depend of a combination of "OBSERVATION_TYPE"+"LANDMARK_PARAMETERIZATION_...
rba_joint_parameterization_traits_t< KF2KF_POSE_TYPE, LM_TYPE, OBS_TYPE > traits_t
Parameters for optimize_local_area()
#define MRPT_UNUSED_PARAM(a)
Can be used to avoid "not used parameters" warnings from the compiler.
const k2k_edges_deque_t & k2k_edges
KF2KF_POSE_TYPE::se_traits_t se_traits_t
The SE(2) or SE(3) traits struct (for Lie algebra log/exp maps, etc.)
Observations, as provided by the user.
std::map< TLandmarkID, TRelativeLandmarkPos > TRelativeLandmarkPosMap
An index of feature IDs and their relative locations.
Private aux structure for BFS searches.
rba_problem_state_t & get_rba_state()
landmark_traits_t::array_landmark_t array_landmark_t
k2k_edges_deque_t k2k_edges
(unknowns) All keyframe-to-keyframe edges
void get_global_graphslam_problem(POSE_GRAPH &global_graph, const ExportGraphSLAM_Params ¶ms=ExportGraphSLAM_Params()) const
Build a graph-slam problem suitable for recovering the (consistent) global pose (vs.
double max_lambda
default: 1e20
TOptimizeExtraOutputInfo optimize_results
Results from the least-squares optimization.
void(* feedback_user_iteration)(unsigned int iter, const double total_sq_err, const double mean_sqroot_error)
const TRelativeLandmarkPosMap & get_known_feats() const
bool use_robust_kernel_stage1
static const size_t OBS_DIMS
TRBA_Problem_state< KF2KF_POSE_TYPE, LM_TYPE, OBS_TYPE, RBA_OPTIONS > rba_problem_state_t
void enable_time_profiler(bool enable=true)
Enable or disables time profiling of all operations (default=enabled), which will be reported upon de...
RbaEngine()
Default constructor.
void visit_k2f(const TKeyFrameID current_kf, const k2f_edge_t *edge, const topo_dist_t cur_dist)
landmark_traits_t::TRelativeLandmarkPos TRelativeLandmarkPos
One landmark position (relative to its base KF)
bool save_graph_as_dot(const std::string &targetFileName, const bool all_landmarks=false) const
Exports all the keyframes (and optionally all landmarks) as a directed graph in DOT (graphviz) format...
TKeyFrameID root_kf_id
The KF to use as a root for the spanning tree to init global poses (default=0)
void make_ordered_list_base_kfs(const typename traits_t::new_kf_observations_t &obs, base_sorted_lst_t &obs_for_each_base_sorted, std::map< TKeyFrameID, size_t > *out_obs_for_each_base=NULL) const
Make a list of base KFs of my new observations, ordered in descending order by # of shared observatio...
const pose_t & pose_base_wrt_d1
static void numeric_dh_dAp(const array_pose_t &x, const TNumeric_dh_dAp_params ¶ms, array_obs_t &y)
Auxiliary method for numeric Jacobian: numerically evaluates the new observation "y" for a small incr...
virtual void saveToConfigFile(mrpt::utils::CConfigFileBase &out, const std::string §ion) const
See docs of mrpt::utils::CLoadableOptions.
VisitorOptimizeLocalArea(const rba_problem_state_t &rba_state_, const TOptimizeLocalAreaParams ¶ms_)
mrpt::aligned_containers< k2k_edge_t >::deque_t k2k_edges_deque_t
jacobian_traits< KF2KF_POSE_TYPE, LM_TYPE, OBS_TYPE >::TSparseBlocksJacobians_dh_df TSparseBlocksJacobians_dh_df
All the important data of a RBA problem at any given instant of time Operations on this structure are...
size_t span_tree_max_depth
Maximum spanning tree depth for reconstructing relative poses (default=-1 : infinity) ...
std::vector< size_t > k2k_edges_to_optimize
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
traits_t::new_kf_observations_t new_kf_observations_t
size_t min_obs_to_loop_closure
Default:6, reduce to 1 for relative graph-slam.
void compute_jacobian_dh_df(typename TSparseBlocksJacobians_dh_df::TEntry &jacob, const k2f_edge_t &observation, std::vector< const pose_flag_t * > *out_list_of_required_num_poses) const
==================================================================== j,i lm_id,base_id h h l obs_fr...
bool draw_unknown_feats
Draw features with non-fixed rel.pos as well?
void visit_k2k(const TKeyFrameID current_kf, const TKeyFrameID next_kf, const k2k_edge_t *edge, const topo_dist_t cur_dist)
mrpt::utils::CTimeLogger & get_time_profiler()
Access to the time profiler.
topo_dist_t max_optimize_depth
The maximum topological distance of keyframes to be optimized around the most recent keyframe...
void visit_kf(const TKeyFrameID kf_ID, const topo_dist_t cur_dist)
bool visit_filter_kf(const TKeyFrameID kf_ID, const topo_dist_t cur_dist)
landmark_traits< LM_TYPE > landmark_traits_t
kf2kf_pose_traits_t::frameid2pose_map_t frameid2pose_map_t
const TRelativeLandmarkPosMap & get_unknown_feats() const
std::pair< TKeyFrameID, TKeyFrameID > TPairKeyFrameID
Used to represent the IDs of a directed edge (first –> second)
bool visit_filter_feat(const TLandmarkID lm_ID, const topo_dist_t cur_dist)
TEdgeCreationPolicy edge_creation_policy
Parameters for determine_kf2kf_edges_to_create(); custom user-defined policies can be also defined (s...
Aux visitor struct, used in optimize_local_area()
options::sensor_pose_on_robot_none sensor_pose_on_robot_t
The sensor pose coincides with the robot pose.
void create_complete_spanning_tree(const TKeyFrameID root_id, frameid2pose_map_t &span_tree, const size_t max_depth=std::numeric_limits< size_t >::max(), std::vector< bool > *aux_ws=NULL) const
Creates a numeric spanning tree between a given root keyframe and the entire graph, returning it into a user-supplied data structure Note that this method does NOT use the depth-limited spanning trees which are built incrementally with the graph.
jacobian_traits< KF2KF_POSE_TYPE, LM_TYPE, OBS_TYPE >::TSparseBlocksJacobians_dh_dAp TSparseBlocksJacobians_dh_dAp
bool find_path_bfs(const TKeyFrameID from, const TKeyFrameID to, std::vector< TKeyFrameID > *out_path_IDs, typename kf2kf_pose_traits< KF2KF_POSE_TYPE >::k2k_edge_vector_t *out_path_edges=NULL) const
Auxiliary, brute force (BFS) method for finding the shortest path between any two Keyframes...
const pose_t * pose_base_wrt_obs
virtual void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source, const std::string §ion)
See docs of mrpt::utils::CLoadableOptions.
const TOptimizeLocalAreaParams & params
void build_opengl_representation(const srba::TKeyFrameID root_keyframe, const TOpenGLRepresentationOptions &options, mrpt::opengl::CSetOfObjectsPtr out_scene, mrpt::opengl::CSetOfObjectsPtr out_root_tree=mrpt::opengl::CSetOfObjectsPtr()) const
Build an opengl representation of the current state of this RBA problem One of different representati...
size_t create_kf2kf_edge(const TKeyFrameID new_kf_id, const TPairKeyFrameID &new_edge, const typename traits_t::new_kf_observations_t &obs, const pose_t &init_inv_pose_val=pose_t())
Users normally won't need to call this directly.
const RBA_OPTIONS::sensor_pose_on_robot_t::parameters_t & sensor_pose
std::vector< TNewEdgeInfo > created_edge_ids
The newly created edges (minimum: 1 edge)
A versatile "profiler" that logs the time spent within each pair of calls to enter(X)-leave(X), among other stats.
std::vector< size_t > lm_IDs_to_optimize
A partial specialization of CArrayNumeric for double numbers.
void setVerbosityLevel(int level)
Changes the verbosity level: 0=None (only critical msgs), 1=verbose, 2=so verbose you'll have to say ...
OBS_TYPE::TObservationParams sensor
Sensor-specific parameters (sensor calibration, etc.)
void prepare_Jacobians_required_tree_roots(std::set< TKeyFrameID > &kfs_num_spantrees_to_update, const std::vector< typename TSparseBlocksJacobians_dh_dAp::col_t * > &lst_JacobCols_dAp, const std::vector< typename TSparseBlocksJacobians_dh_df::col_t * > &lst_JacobCols_df)
Prepare the list of all required KF roots whose spanning trees need numeric updates with each optimiz...
const pose_t aux_null_pose
A fixed SE(3) pose at the origin (used when we need a pointer or a reference to a "null transformatio...
TRelativeLandmarkPosMap unknown_lms
(unknown values) Landmarks with an unknown fixed 3D position relative to their base frame_id ...
std::multimap< size_t, TKeyFrameID, std::greater< size_t > > base_sorted_lst_t
Information per key-frame needed for RBA.
sensor_model< LM_TYPE, OBS_TYPE > sensor_model_t
The sensor model for the specified combination of LM parameterization + observation type...
landmark_traits_t::TRelativeLandmarkPosMap TRelativeLandmarkPosMap
An index of feature IDs and their relative locations.
mrpt::aligned_containers< residual_t >::vector_t vector_residuals_t
const OBS_TYPE::TObservationParams & sensor_params
size_t dont_optimize_landmarks_seen_less_than_n_times
Set to 1 to try to optimize all landmarks even if they're just observed once, which may makes sense d...
static void add_edge_ij_to_list_needed_roots(std::set< TKeyFrameID > &lst, const TKeyFrameID i, const TKeyFrameID j)
observation_traits_t::array_obs_t array_obs_t
void bfs_visitor(const TKeyFrameID root_id, const topo_dist_t max_distance, const bool rely_on_prebuilt_spanning_trees, KF_VISITOR &kf_visitor, FEAT_VISITOR &feat_visitor, K2K_EDGE_VISITOR &k2k_edge_visitor, K2F_EDGE_VISITOR &k2f_edge_visitor) const
Visits all k2k & k2f edges following a BFS starting at a given starting node and up to a given maximu...
rba_problem_state_t::k2k_edge_t k2k_edge_t
The set of default settings for RbaEngine.
int m_verbose_level
0: None (only critical msgs), 1: verbose, 2:even more verbose, 3: even more
Keyframe-to-feature edge: observation data stored for each keyframe.
TRelativeLandmarkPosMap known_lms
(known values) Landmarks with a known, fixed 3D position relative to their base frame_id ...
const array_landmark_t & xji_i
double eval_overall_squared_error() const
Evaluates the quality of the overall map/landmark estimations, by computing the sum of the squared er...
void gl_aux_draw_node(mrpt::opengl::CSetOfObjects &soo, const std::string &label, const float x, const float y) const
The unique struct which hold all the parameters from the different SRBA modules (sensors, optional features, optimizers,...)
size_t add_observation(const TKeyFrameID observing_kf_id, const typename observation_traits_t::observation_t &new_obs, const array_landmark_t *fixed_relative_position=NULL, const array_landmark_t *unknown_relative_position_init_val=NULL)
Creates a new known/unknown position landmark (upon first LM observation ), and expands Jacobians wit...
options::observation_noise_identity obs_noise_matrix_t
The sensor noise matrix is the same for all observations and equal to * I(identity) ...
std::vector< bool > m_complete_st_ws
Temporary working space used in create_complete_spanning_tree()
Usage: A possible type for RBA_OPTIONS::sensor_pose_on_robot_t.
bool find_path_bfs(const TKeyFrameID src_kf, const TKeyFrameID trg_kf, std::vector< TKeyFrameID > &found_path) const
An unconstrained breadth-first search (BFS) for the shortest path between two keyframes.
void clear()
Reset the entire problem to an empty state (automatically called at construction) ...
Information returned by RbaEngine::define_new_keyframe()
bool feat_has_known_rel_pos
whether it's a known or unknown relative position feature
void determine_kf2kf_edges_to_create(const TKeyFrameID new_kf_id, const typename traits_t::new_kf_observations_t &obs, std::vector< TNewEdgeInfo > &new_k2k_edge_ids)
This method will call edge_creation_policy(), which has predefined algorithms but could be re-defined...
kf2kf_pose_traits< KF2KF_POSE_TYPE > kf2kf_pose_traits_t
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
void optimize_edges(const std::vector< size_t > &run_k2k_edges, const std::vector< size_t > &run_feat_ids_in, TOptimizeExtraOutputInfo &out_info, const std::vector< size_t > &observation_indices_to_optimize=std::vector< size_t >())
mrpt::aligned_containers< TKeyFrameID, pose_flag_t >::map_t frameid2pose_map_t
"numeric" values of spanning tree poses:
bool numeric_jacobians
(Default:false) Use a numeric approximation of the Jacobians (very slow!) instead of analytical ones...
rba_problem_state_t rba_state
All the beef is here.
RbaEngine< KF2KF_POSE_TYPE, LM_TYPE, OBS_TYPE, RBA_OPTIONS > rba_engine_t
traits_t::new_kf_observation_t new_kf_observation_t
k2f_edge_t * k2f
Obs data.
void visit_feat(const TLandmarkID lm_ID, const topo_dist_t cur_dist)
rba_problem_state_t::k2f_edge_t k2f_edge_t
static double huber_kernel(double delta, const double kernel_param)
pseudo-huber cost function
uint64_t TKeyFrameID
Numeric IDs for key-frames (KFs)