108 m_pkk.extractMatrix(0, 0, out_robotPose.
cov);
137 std::vector<TPoint3D>& out_landmarksPositions,
138 std::map<unsigned int, CLandmark::TLandmarkID>& out_landmarkIDs,
155 m_pkk.extractMatrix(0, 0, out_robotPose.
cov);
160 out_landmarksPositions.resize(nLMs);
161 for (i = 0; i < nLMs; i++)
163 out_landmarksPositions[i].x =
165 out_landmarksPositions[i].y =
167 out_landmarksPositions[i].z =
175 out_fullState.resize(
m_xkk.size());
176 for (KFVector::Index i = 0; i <
m_xkk.size(); i++)
177 out_fullState[i] =
m_xkk[i];
180 out_fullCovariance =
m_pkk;
230 vector<std::vector<uint32_t>> partitions;
237 vector<std::vector<uint32_t>> partitions;
238 std::vector<uint32_t> tmpCluster;
243 for (
size_t i = 0; i <
m_SFs.
size(); i++)
245 tmpCluster.push_back(i);
248 partitions.push_back(tmpCluster);
250 tmpCluster.push_back(i);
270 m_action->getBestMovementEstimation();
280 actMov2D->poseChange->getMean(estMovMean);
297 for (KFArray_ACT::Index i = 0; i < u.size(); i++) u[i] = theIncr[i];
304 const KFArray_ACT& u, KFArray_VEH& xv,
bool& out_skipPrediction)
const 314 out_skipPrediction =
true;
325 odoIncrement.
m_quat[0] = u[3];
326 odoIncrement.
m_quat[1] = u[4];
327 odoIncrement.
m_quat[2] = u[5];
328 odoIncrement.
m_quat[3] = u[6];
331 robotPose += odoIncrement;
334 for (
size_t i = 0; i < xv.static_size; i++) xv[i] = robotPose[i];
355 CPose3DQuatPDF::jacobiansPoseComposition(
396 odoIncr2D.
copyFrom(*act2D->poseChange);
420 const std::vector<size_t>& idx_landmarks_to_predict,
421 vector_KFArray_OBS& out_predictions)
const 433 "*ERROR*: This method requires an observation of type " 434 "CObservationBearingRange");
464 const CPose3DQuat sensorPoseAbs = robotPose + sensorPoseOnRobot;
466 const size_t N = idx_landmarks_to_predict.size();
467 out_predictions.resize(N);
468 for (
size_t i = 0; i < N; i++)
470 const size_t row_in = feature_size * idx_landmarks_to_predict[i];
474 m_xkk[vehicle_size + row_in + 0],
m_xkk[vehicle_size + row_in + 1],
475 m_xkk[vehicle_size + row_in + 2]);
481 out_predictions[i][0],
482 out_predictions[i][1],
483 out_predictions[i][2]
491 const size_t& idx_landmark_to_predict, KFMatrix_OxV& Hx,
492 KFMatrix_OxF& Hy)
const 504 "*ERROR*: This method requires an observation of type " 505 "CObservationBearingRange");
520 CPose3DQuatPDF::jacobiansPoseComposition(
521 robotPose, sensorPoseOnRobot, H_senpose_vehpose, H_senpose_senrelpose,
524 const size_t row_in = feature_size * idx_landmark_to_predict;
528 m_xkk[vehicle_size + row_in + 0],
m_xkk[vehicle_size + row_in + 1],
529 m_xkk[vehicle_size + row_in + 2]);
542 Hx.multiply(Hx_sensor, H_senpose_vehpose);
570 vector_KFArray_OBS& Z, std::vector<int>& data_association,
571 const vector_KFArray_OBS& all_predictions,
const KFMatrix& S,
572 const std::vector<size_t>& lm_indices_in_S,
const KFMatrix_OxO&
R)
586 "*ERROR*: This method requires an observation of type " 587 "CObservationBearingRange");
589 const size_t N = obs->sensedData.size();
593 for (
row = 0, itObs = obs->sensedData.begin();
594 itObs != obs->sensedData.end(); ++itObs, ++
row)
597 Z[
row][0] = itObs->range;
598 Z[
row][1] = itObs->yaw;
599 Z[
row][2] = itObs->pitch;
604 data_association.assign(N, -1);
607 std::vector<size_t> obs_idxs_needing_data_assoc;
608 obs_idxs_needing_data_assoc.reserve(N);
614 for (
row = 0, itObs = obs->sensedData.begin(),
615 itDA = data_association.begin();
616 itObs != obs->sensedData.end(); ++itObs, ++itDA, ++
row)
619 if (itObs->landmarkID < 0)
620 obs_idxs_needing_data_assoc.push_back(
row);
626 *itDA = itID->second;
635 if (obs_idxs_needing_data_assoc.empty())
641 for (
size_t idxObs = 0; idxObs < data_association.size(); idxObs++)
643 int da = data_association[idxObs];
646 data_association[idxObs];
652 const size_t nObsDA = obs_idxs_needing_data_assoc.size();
655 for (
size_t i = 0; i < nObsDA; i++)
657 const size_t idx = obs_idxs_needing_data_assoc[i];
658 for (
unsigned k = 0; k < obs_size; k++)
659 Z_obs_means.get_unsafe(i, k) =
Z[idx][k];
664 m_pkk.extractMatrix(0, 0, Pxx);
668 const size_t nPredictions = lm_indices_in_S.size();
676 for (
size_t q = 0;
q < nPredictions;
q++)
678 const size_t i = lm_indices_in_S[
q];
679 for (
size_t w = 0;
w < obs_size;
w++)
707 data_association[it->first] = it->second;
723 const double T = std::sqrt(
726 ASSERTMSG_(T > 0,
"Vehicle pose quaternion norm is not >0!!");
728 const double T_ = (
m_xkk[3] < 0 ? -1.0 : 1.0) / T;
794 std_sensor_range(0.01f),
796 std_sensor_pitch(
DEG2RAD(0.2f)),
797 std_odo_z_additional(0),
798 doPartitioningExperiment(false),
799 quantiles_3D_representation(3),
800 partitioningMethod(0),
803 data_assoc_IC_chi2_thres(0.99),
805 data_assoc_IC_ml_threshold(0.0),
806 create_simplemap(false),
807 force_ignore_odometry(false)
822 "\n----------- [CRangeBearingKFSLAM::TOptions] ------------ \n\n");
825 "doPartitioningExperiment = %c\n",
826 doPartitioningExperiment ?
'Y' :
'N');
828 "partitioningMethod = %i\n", partitioningMethod);
830 "data_assoc_method = %s\n",
834 "data_assoc_metric = %s\n",
838 "data_assoc_IC_chi2_thres = %.06f\n",
839 data_assoc_IC_chi2_thres);
841 "data_assoc_IC_metric = %s\n",
845 "data_assoc_IC_ml_threshold = %.06f\n",
846 data_assoc_IC_ml_threshold);
861 "*ERROR*: This method requires an observation of type " 862 "CObservationBearingRange");
875 CPose3DQuatPDF::jacobiansPoseComposition(
876 robotPose, sensorPoseOnRobot, dsensorabs_dvehpose,
877 dsensorabs_dsenrelpose, &sensorPoseAbs);
903 hn_r * chn_y * chn_p, hn_r * shn_y * chn_p, -hn_r * shn_p);
914 const kftype values_dynlocal_dhn[] = {chn_p * chn_y,
915 -hn_r * chn_p * shn_y,
916 -hn_r * chn_y * shn_p,
918 hn_r * chn_p * chn_y,
919 -hn_r * shn_p * shn_y,
929 yn_rel_sensor.
x, yn_rel_sensor.
y,
932 &jacob_dyn_dynrelsensor, &jacob_dyn_dsensorabs);
935 dyn_dhn.multiply_AB(jacob_dyn_dynrelsensor, dynlocal_dhn);
939 jacob_dyn_dsensorabs, dsensorabs_dvehpose);
955 const size_t in_obsIdx,
const size_t in_idxNewFeat)
963 "*ERROR*: This method requires an observation of type " 964 "CObservationBearingRange");
969 ASSERT_(in_obsIdx < obs->sensedData.size());
970 if (obs->sensedData[in_obsIdx].landmarkID >= 0)
973 m_IDs.
insert(obs->sensedData[in_obsIdx].landmarkID, in_idxNewFeat);
1003 m_pkk.extractMatrix(0, 0, 3, 3, COV);
1004 pointGauss.
cov = COV;
1008 mrpt::make_aligned_shared<opengl::CEllipsoid>();
1010 ellip->setPose(pointGauss.
mean);
1011 ellip->setCovMatrix(pointGauss.
cov);
1012 ellip->enableDrawSolid3D(
false);
1014 ellip->set3DsegmentsCount(10);
1015 ellip->setColor(1, 0, 0);
1017 outObj->insert(ellip);
1022 for (
size_t i = 0; i < nLMs; i++)
1030 m_pkk.extractMatrix(
1034 pointGauss.
cov = COV;
1037 mrpt::make_aligned_shared<opengl::CEllipsoid>();
1039 ellip->setName(
format(
"%u", static_cast<unsigned int>(i)));
1040 ellip->enableShowName(
true);
1041 ellip->setPose(pointGauss.
mean);
1042 ellip->setCovMatrix(pointGauss.
cov);
1043 ellip->enableDrawSolid3D(
false);
1045 ellip->set3DsegmentsCount(10);
1047 ellip->setColor(0, 0, 1);
1053 map<int, bool> belongToPartition;
1073 for (
size_t o = 0; o < obs->sensedData.size(); o++)
1075 if (obs->sensedData[o].landmarkID == i_th_ID)
1077 belongToPartition[
p] =
true;
1085 string strParts(
"[");
1088 it != belongToPartition.end(); ++it)
1090 if (it != belongToPartition.begin()) strParts +=
string(
",");
1091 strParts +=
format(
"%i", it->first);
1094 ellip->setName(ellip->getName() + strParts +
string(
"]"));
1097 outObj->insert(ellip);
1105 size_t K, std::vector<std::vector<uint32_t>>& landmarksMembership)
1113 vector<std::vector<uint32_t>> partitions;
1114 std::vector<uint32_t> tmpCluster;
1116 for (
size_t i = 0; i <
m_SFs.
size(); i++)
1118 tmpCluster.push_back(i);
1121 partitions.push_back(tmpCluster);
1123 tmpCluster.push_back(
1140 std::vector<std::vector<uint32_t>>& landmarksMembership)
const 1142 landmarksMembership.clear();
1149 for (
size_t i = 0; i < nLMs; i++)
1151 map<int, bool> belongToPartition;
1171 for (
size_t o = 0; o < obs->sensedData.size(); o++)
1173 if (obs->sensedData[o].landmarkID == i_th_ID)
1175 belongToPartition[
p] =
true;
1183 std::vector<uint32_t> membershipOfThisLM;
1186 it != belongToPartition.end(); ++it)
1187 membershipOfThisLM.push_back(it->first);
1189 landmarksMembership.push_back(membershipOfThisLM);
1197 const std::vector<std::vector<uint32_t>>& landmarksMembership)
const 1205 fullCov(i, i) = max(fullCov(i, i), 1e-6);
1210 double sumOffBlocks = 0;
1211 unsigned int nLMs = landmarksMembership.size();
1216 for (i = 0; i < nLMs; i++)
1218 for (
size_t j = i + 1; j < nLMs; j++)
1223 landmarksMembership[i], landmarksMembership[j]))
1227 sumOffBlocks += 2 * H.block(
row, col, 2, 2).sum();
1232 return sumOffBlocks /
1248 vector<std::vector<uint32_t>> partitions;
1257 const string& fil,
float stdCount,
const string& styleLandmarks,
1258 const string& stylePath,
const string& styleRobot)
const 1269 "%%--------------------------------------------------------------------" 1271 os::fprintf(f,
"%% File automatically generated using the MRPT method:\n");
1275 "'CRangeBearingKFSLAM::saveMapAndPath2DRepresentationAsMATLABFile'\n");
1279 f,
"%% Jose Luis Blanco Claraco, University of Malaga @ 2008\n");
1283 "%%--------------------------------------------------------------------" 1291 for (
size_t i = 0; i < nLMs; i++)
1295 cov(0, 0) =
m_pkk(idx + 0, idx + 0);
1296 cov(1, 1) =
m_pkk(idx + 1, idx + 1);
1314 for (
size_t i = 0; i <
m_SFs.
size(); i++)
1329 f,
"plot(ROB_PATH(:,1),ROB_PATH(:,2),'%s');\n", stylePath.c_str());
1388 std::vector<size_t>& out_LM_indices_to_predict)
const 1394 "*ERROR*: This method requires an observation of type " 1395 "CObservationBearingRange");
1397 #define USE_HEURISTIC_PREDICTION 1399 #ifdef USE_HEURISTIC_PREDICTION 1400 const double sensor_max_range = obs->maxSensorDistance;
1401 const double fov_yaw = obs->fieldOfView_yaw;
1402 const double fov_pitch = obs->fieldOfView_pitch;
1404 const double max_vehicle_loc_uncertainty =
1406 m_pkk.get_unsafe(0, 0) +
m_pkk.get_unsafe(1, 1) +
1407 m_pkk.get_unsafe(2, 2));
1410 out_LM_indices_to_predict.clear();
1411 for (
size_t i = 0; i < prediction_means.size(); i++)
1413 #ifndef USE_HEURISTIC_PREDICTION 1414 out_LM_indices_to_predict.push_back(i);
1417 if (prediction_means[i][0] <
1418 (15 + sensor_max_range + max_vehicle_loc_uncertainty +
1420 fabs(prediction_means[i][1]) <
1422 fabs(prediction_means[i][2]) <
1425 out_LM_indices_to_predict.push_back(i);
mrpt::math::CMatrixFixedNumeric< double, OBS_SIZE, VEH_SIZE > KFMatrix_OxV
const_iterator end() const
void changeCoordinatesReference(const CPose3DQuat &newReferenceBase)
this = p (+) this.
void updatePartitions(std::vector< std::vector< uint32_t >> &partitions)
Recalculate the map/graph partitions.
double x() const
Common members of all points & poses classes.
void copyFrom(const CPosePDF &o) override
Copy operator, translating if necesary (for example, between particles and gaussian representations) ...
void getCurrentRobotPose(mrpt::poses::CPose3DQuatPDFGaussian &out_robotPose) const
Returns the mean & the 7x7 covariance matrix of the robot 6D pose (with rotation as a quaternion)...
TOptions options
Algorithm parameters.
std::string MATLAB_plotCovariance2D(const CMatrixFloat &cov22, const CVectorFloat &mean, const float &stdCount, const std::string &style=std::string("b"), const size_t &nEllipsePoints=30)
Generates a string with the MATLAB commands required to plot an confidence interval (ellipse) for a 2...
void reset()
Reset the state of the SLAM filter: The map is emptied and the robot put back to (0,0,0).
mrpt::poses::CPose3DQuat getIncrementFromOdometry() const
Return the last odometry, as a pose increment.
void OnObservationJacobians(const size_t &idx_landmark_to_predict, KFMatrix_OxV &Hx, KFMatrix_OxF &Hy) const
Implements the observation Jacobians and (when applicable) .
double RAD2DEG(const double x)
Radians to degrees.
void getLastPartitionLandmarks(std::vector< std::vector< uint32_t >> &landmarksMembership) const
Return the partitioning of the landmarks in clusters accoring to the last partition.
#define THROW_EXCEPTION(msg)
bool force_ignore_odometry
Whether to ignore the input odometry and behave as if there was no odometry at all (default: false) ...
uint64_t TLandmarkID
Unique IDs for landmarks.
This class stores a sequence of <Probabilistic Pose,SensoryFrame> pairs, thus a "metric map" can be t...
int void fclose(FILE *f)
An OS-independent version of fclose.
void reconsiderPartitionsNow()
The partitioning of the entire map is recomputed again.
void loadFromConfigFile(const mrpt::config::CConfigFileBase &iniFile, const std::string §ion) override
This method load the options from a ".ini"-like file or memory-stored string list.
CPoint3D mean
The mean value.
size_t countCommonElements(const CONTAINER1 &a, const CONTAINER2 &b)
Counts the number of elements that appear in both STL-like containers (comparison through the == oper...
double DEG2RAD(const double x)
Degrees to radians.
size_t getNumberOfLandmarksInTheMap() const
CPose3DQuat mean
The mean value.
GLdouble GLdouble GLdouble GLdouble q
const_iterator find_key(const KEY &k) const
void processActionObservation(mrpt::obs::CActionCollection::Ptr &action, mrpt::obs::CSensoryFrame::Ptr &SF)
Process one new action and observations to update the map and robot pose estimate.
This file implements several operations that operate element-wise on individual or pairs of container...
void OnNormalizeStateVector()
This method is called after the prediction and after the update, to give the user an opportunity to n...
void OnPreComputingPredictions(const vector_KFArray_OBS &in_all_prediction_means, std::vector< size_t > &out_LM_indices_to_predict) const
This will be called before OnGetObservationsAndDataAssociation to allow the application to reduce the...
void insert(const KEY &k, const VALUE &v)
Insert a new pair KEY<->VALUE in the bi-map.
Column vector, like Eigen::MatrixX*, but automatically initialized to zeros since construction...
mrpt::math::CMatrixDouble77 cov
The 7x7 covariance matrix.
void saveMapAndPath2DRepresentationAsMATLABFile(const std::string &fil, float stdCount=3.0f, const std::string &styleLandmarks=std::string("b"), const std::string &stylePath=std::string("r"), const std::string &styleRobot=std::string("r")) const
Save the current state of the filter (robot pose & map) to a MATLAB script which displays all the ele...
void OnGetAction(KFArray_ACT &out_u) const
Must return the action vector u.
void OnTransitionJacobian(KFMatrix_VxV &out_F) const
Implements the transition Jacobian .
void sphericalCoordinates(const mrpt::math::TPoint3D &point, double &out_range, double &out_yaw, double &out_pitch, mrpt::math::CMatrixFixedNumeric< double, 3, 3 > *out_jacob_dryp_dpoint=nullptr, mrpt::math::CMatrixFixedNumeric< double, 3, 7 > *out_jacob_dryp_dpose=nullptr) const
Computes the spherical coordinates of a 3D point as seen from the 6D pose specified by this object...
void runOneKalmanIteration()
The main entry point, executes one complete step: prediction + update.
KFMatrix m_pkk
The system full covariance matrix.
uint32_t addMapFrame(const mrpt::obs::CSensoryFrame &frame, const mrpt::poses::CPose3DPDF &robotPose3D)
Insert a new keyframe to the graph.
mrpt::poses::CPose3DQuat getCurrentRobotPoseMean() const
Get the current robot pose mean, as a 3D+quaternion pose.
TDataAssocInfo m_last_data_association
Last data association.
float std_odo_z_additional
Additional std.
mrpt::containers::bimap< mrpt::maps::CLandmark::TLandmarkID, unsigned int > m_IDs
The mapping between landmark IDs and indexes in the Pkk cov.
void clear()
Clear the contents of the bi-map.
GLubyte GLubyte GLubyte GLubyte w
void OnNewLandmarkAddedToMap(const size_t in_obsIdx, const size_t in_idxNewFeat)
If applicable to the given problem, do here any special handling of adding a new landmark to the map...
mrpt::math::CMatrixTemplateNumeric< kftype > Y_pred_means
Declares a class that represents a Probability Density function (PDF) of a 3D pose using a quaternion...
mrpt::math::CArrayNumeric< double, FEAT_SIZE > KFArray_FEAT
vector_KFArray_OBS all_predictions
int64_t TLandmarkID
The type for the IDs of landmarks.
T square(const T x)
Inline function for the square of a number.
mrpt::math::CMatrixFixedNumeric< double, VEH_SIZE, VEH_SIZE > KFMatrix_VxV
const std::map< VALUE, KEY > & getInverseMap() const
Return a read-only reference to the internal map KEY->VALUES.
#define ASSERT_(f)
Defines an assertion mechanism.
void composePoint(const double lx, const double ly, const double lz, double &gx, double &gy, double &gz, mrpt::math::CMatrixFixedNumeric< double, 3, 3 > *out_jacobian_df_dpoint=nullptr, mrpt::math::CMatrixFixedNumeric< double, 3, 7 > *out_jacobian_df_dpose=nullptr) const
Computes the 3D point G such as .
Represents a probabilistic 3D (6D) movement.
void OnTransitionNoise(KFMatrix_VxV &out_Q) const
Implements the transition noise covariance .
void wrapToPiInPlace(T &a)
Modifies the given angle to translate it into the ]-pi,pi] range.
A numeric matrix of compile-time fixed size.
This class allows loading and storing values and vectors of different types from a configuration text...
This base provides a set of functions for maths stuff.
A bidirectional version of std::map, declared as bimap<KEY,VALUE> and which actually contains two std...
Declares a class that represents a Probability Density function (PDF) of a 2D pose ...
static size_t get_vehicle_size()
TKF_options KF_options
Generic options for the Kalman Filter algorithm itself.
TDataAssociationMetric data_assoc_metric
mrpt::math::CArrayNumeric< double, OBS_SIZE > KFArray_OBS
int partitioningMethod
Applicable only if "doPartitioningExperiment=true".
TDataAssociationMetric
Different metrics for data association, used in mrpt::slam::data_association For a comparison of both...
TOptions()
Default values.
mrpt::math::CMatrixDouble33 cov
The 3x3 covariance matrix.
CMatrixTemplateNumeric< double > CMatrixDouble
Declares a matrix of double numbers (non serializable).
void OnSubstractObservationVectors(KFArray_OBS &A, const KFArray_OBS &B) const
Computes A=A-B, which may need to be re-implemented depending on the topology of the individual scala...
static size_t get_observation_size()
CONTAINER::Scalar sum(const CONTAINER &v)
Computes the sum of all the elements.
This namespace contains representation of robot actions and observations.
CIncrementalMapPartitioner mapPartitioner
Used for map partitioning experiments.
TDataAssociationMetric data_assoc_IC_metric
Whether to use mahalanobis (->chi2 criterion) vs.
double x
X,Y,Z coordinates.
#define ASSERTMSG_(f, __ERROR_MSG)
Defines an assertion mechanism.
double computeOffDiagonalBlocksApproximationError(const std::vector< std::vector< uint32_t >> &landmarksMembership) const
Computes the ratio of the missing information matrix elements which are ignored under a certain parti...
size_t size() const
Returns the count of pairs (pose,sensory data)
A class used to store a 3D pose as a translation (x,y,z) and a quaternion (qr,qx,qy,qz).
double kftype
The numeric type used in the Kalman Filter (default=double)
void get(size_t index, mrpt::poses::CPose3DPDF::Ptr &out_posePDF, mrpt::obs::CSensoryFrame::Ptr &out_SF) const
Access to the i'th pair, first one is index '0'.
mrpt::math::CMatrixFixedNumeric< double, OBS_SIZE, OBS_SIZE > KFMatrix_OxO
mrpt::maps::CSimpleMap m_SFs
The sequence of all the observations and the robot path (kept for debugging, statistics,etc)
GLsizei const GLchar ** string
double data_assoc_IC_ml_threshold
Only if data_assoc_IC_metric==ML, the log-ML threshold (Default=0.0)
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
std::vector< std::vector< uint32_t > > m_lastPartitionSet
mrpt::aligned_std_vector< KFArray_OBS > vector_KFArray_OBS
mrpt::math::CArrayDouble< 3 > m_coords
The translation vector [x,y,z].
void loadOptions(const mrpt::config::CConfigFileBase &ini)
Load options from a ini-like file/text.
int fprintf(FILE *fil, const char *format,...) noexcept MRPT_printf_format_check(2
An OS-independent version of fprintf.
#define MRPT_LOAD_CONFIG_VAR( variableName, variableType, configFileObject, sectionNameStr)
An useful macro for loading variables stored in a INI-like file under a key with the same name that t...
void OnGetObservationNoise(KFMatrix_OxO &out_R) const
Return the observation NOISE covariance matrix, that is, the model of the Gaussian additive noise of ...
void OnGetObservationsAndDataAssociation(vector_KFArray_OBS &out_z, std::vector< int > &out_data_association, const vector_KFArray_OBS &in_all_predictions, const KFMatrix &in_S, const std::vector< size_t > &in_lm_indices_in_S, const KFMatrix_OxO &in_R)
This is called between the KF prediction step and the update step, and the application must return th...
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
std::vector< size_t > predictions_IDs
void OnObservationModel(const std::vector< size_t > &idx_landmarks_to_predict, vector_KFArray_OBS &out_predictions) const
mrpt::obs::CSensoryFrame::Ptr m_SF
Set up by processActionObservation.
void getCurrentState(mrpt::poses::CPose3DQuatPDFGaussian &out_robotPose, std::vector< mrpt::math::TPoint3D > &out_landmarksPositions, std::map< unsigned int, mrpt::maps::CLandmark::TLandmarkID > &out_landmarkIDs, mrpt::math::CVectorDouble &out_fullState, mrpt::math::CMatrixDouble &out_fullCovariance) const
Returns the complete mean and cov.
mrpt::slam::CRangeBearingKFSLAM::TOptions options
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string §ion) override
This method load the options from a ".ini"-like file or memory-stored string list.
mrpt::math::CMatrixFixedNumeric< double, FEAT_SIZE, VEH_SIZE > KFMatrix_FxV
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
float quantiles_3D_representation
Default = 3.
#define ASSERTDEB_(f)
Defines an assertion mechanism - only when compiled in debug.
CSetOfObjects::Ptr CornerXYZ(float scale=1.0)
Returns three arrows representing a X,Y,Z 3D corner.
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
std::map< observation_index_t, prediction_index_t > associations
For each observation (with row index IDX_obs in the input "Z_observations"), its association in the p...
GLenum GLenum GLvoid * row
void getLastPartitionLandmarksAsIfFixedSubmaps(size_t K, std::vector< std::vector< uint32_t >> &landmarksMembership)
For testing only: returns the partitioning as "getLastPartitionLandmarks" but as if a fixed-size subm...
void dumpToTextStream(std::ostream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a std::ostream.
This observation represents a number of range-bearing value pairs, each one for a detected landmark...
void OnTransitionModel(const KFArray_ACT &in_u, KFArray_VEH &inout_x, bool &out_skipPrediction) const
Implements the transition model .
void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr &outObj) const
Returns a 3D representation of the landmarks in the map and the robot 3D position according to the cu...
GLsizei GLsizei GLchar * source
bool inverse(const VALUE &v, KEY &out_k) const
Get the key associated the given value, VALUE->KEY, returning false if not present.
Declares a class that represents a Probability Density function (PDF) of a 3D pose ...
Information for data-association:
void OnInverseObservationModel(const KFArray_OBS &in_z, KFArray_FEAT &out_yn, KFMatrix_FxV &out_dyn_dxv, KFMatrix_FxO &out_dyn_dhn) const
If applicable to the given problem, this method implements the inverse observation model needed to ex...
CRangeBearingKFSLAM()
Constructor.
bool create_simplemap
Whether to fill m_SFs (default=false)
FILE * fopen(const char *fileName, const char *mode) noexcept
An OS-independent version of fopen.
TDataAssociationMethod data_assoc_method
Eigen::Matrix< typename MATRIX::Scalar, MATRIX::ColsAtCompileTime, MATRIX::ColsAtCompileTime > cov(const MATRIX &v)
Computes the covariance matrix from a list of samples in an NxM matrix, where each row is a sample...
bool doPartitioningExperiment
If set to true (default=false), map will be partitioned using the method stated by partitioningMethod...
mrpt::math::CQuaternionDouble m_quat
The quaternion.
TDataAssociationResults results
mrpt::math::CMatrixTemplateNumeric< kftype > Y_pred_covs
void insert(const mrpt::poses::CPose3DPDF *in_posePDF, const mrpt::obs::CSensoryFrame &in_SF)
Add a new pair to the sequence.
static size_t get_feature_size()
mrpt::obs::CActionCollection::Ptr m_action
Set up by processActionObservation.
TDataAssociationMethod
Different algorithms for data association, used in mrpt::slam::data_association.
virtual ~CRangeBearingKFSLAM()
Destructor:
float std_sensor_range
The std.
KFVector m_xkk
The system state vector.
const Scalar * const_iterator
double data_assoc_IC_chi2_thres
Threshold in [0,1] for the chi2square test for individual compatibility between predictions and obser...
void data_association_full_covariance(const mrpt::math::CMatrixDouble &Z_observations_mean, const mrpt::math::CMatrixDouble &Y_predictions_mean, const mrpt::math::CMatrixDouble &Y_predictions_cov, TDataAssociationResults &results, const TDataAssociationMethod method=assocJCBB, const TDataAssociationMetric metric=metricMaha, const double chi2quantile=0.99, const bool DAT_ASOC_USE_KDTREE=true, const std::vector< prediction_index_t > &predictions_IDs=std::vector< prediction_index_t >(), const TDataAssociationMetric compatibilityTestMetric=metricMaha, const double log_ML_compat_test_threshold=0.0)
Computes the data-association between the prediction of a set of landmarks and their observations...
mrpt::math::CMatrixFixedNumeric< double, FEAT_SIZE, OBS_SIZE > KFMatrix_FxO
EIGEN_STRONG_INLINE double mean() const
Computes the mean of the entire matrix.
void clear()
Remove all stored pairs.
A gaussian distribution for 3D points.
mrpt::math::CVectorFloat stds_Q_no_odo
A 7-length vector with the std.