112 m_pkk.extractMatrix(0,0,out_robotPose.
cov);
142 std::vector<TPoint3D> &out_landmarksPositions,
143 std::map<unsigned int,CLandmark::TLandmarkID> &out_landmarkIDs,
161 m_pkk.extractMatrix(0,0,out_robotPose.
cov);
166 out_landmarksPositions.resize(nLMs);
178 out_fullState.resize(
m_xkk.size() );
179 for (KFVector::Index i=0;i<
m_xkk.size();i++)
180 out_fullState[i] =
m_xkk[i];
183 out_fullCovariance =
m_pkk;
193 CActionCollectionPtr &action,
194 CSensoryFramePtr &SF )
232 vector<vector_uint> partitions;
239 vector<vector_uint> partitions;
247 tmpCluster.push_back(i);
250 partitions.push_back(tmpCluster);
252 tmpCluster.push_back(i);
268 CActionRobotMovement2DPtr actMov2D =
m_action->getBestMovementEstimation();
277 actMov2D->poseChange->getMean(estMovMean);
294 for (KFArray_ACT::Index i=0;i<u.size();i++)
301 const KFArray_ACT &u,
303 bool &out_skipPrediction )
const 311 out_skipPrediction =
true;
322 odoIncrement.
m_quat [0] = u[3];
323 odoIncrement.
m_quat [1] = u[4];
324 odoIncrement.
m_quat [2] = u[5];
325 odoIncrement.
m_quat [3] = u[6];
328 robotPose += odoIncrement;
331 for (
size_t i=0;i<xv.static_size;i++)
332 xv[i] = robotPose[i];
352 CPose3DQuatPDF::jacobiansPoseComposition(
368 CActionRobotMovement2DPtr act2D =
m_action->getBestMovementEstimation();
371 if (act3D && act2D)
THROW_EXCEPTION(
"Both 2D & 3D odometry are present!?!?")
391 odoIncr2D.
copyFrom( *act2D->poseChange );
417 vector_KFArray_OBS &out_predictions )
const 426 ASSERTMSG_(obs,
"*ERROR*: This method requires an observation of type CObservationBearingRange")
453 const CPose3DQuat sensorPoseAbs= robotPose + sensorPoseOnRobot;
455 const size_t N = idx_landmarks_to_predict.
size();
456 out_predictions.resize(N);
457 for (
size_t i=0;i<N;i++)
459 const size_t row_in = feature_size*idx_landmarks_to_predict[i];
463 m_xkk[ vehicle_size + row_in + 0 ],
464 m_xkk[ vehicle_size + row_in + 1 ],
465 m_xkk[ vehicle_size + row_in + 2 ] );
471 out_predictions[i][0],
472 out_predictions[i][1],
473 out_predictions[i][2]
481 const size_t &idx_landmark_to_predict,
483 KFMatrix_OxF &Hy )
const 492 ASSERTMSG_(obs,
"*ERROR*: This method requires an observation of type CObservationBearingRange")
505 CPose3DQuatPDF::jacobiansPoseComposition(
509 H_senpose_senrelpose,
512 const size_t row_in = feature_size*idx_landmark_to_predict;
516 m_xkk[ vehicle_size + row_in + 0 ],
517 m_xkk[ vehicle_size + row_in + 1 ],
518 m_xkk[ vehicle_size + row_in + 2 ] );
533 Hx.multiply( Hx_sensor, H_senpose_vehpose );
550 vector_KFArray_OBS &Z,
552 const vector_KFArray_OBS &all_predictions,
555 const KFMatrix_OxO &
R 567 ASSERTMSG_(obs,
"*ERROR*: This method requires an observation of type CObservationBearingRange")
569 const size_t N = obs->sensedData.size();
573 for (
row=0,itObs = obs->sensedData.begin();itObs!=obs->sensedData.end();++itObs,++
row)
576 Z[
row][0] =itObs->range;
577 Z[
row][1] =itObs->yaw;
578 Z[
row][2] =itObs->pitch;
583 data_association.assign(N,-1);
587 obs_idxs_needing_data_assoc.reserve(N);
593 for (
row=0,itObs = obs->sensedData.begin(),itDA=data_association.begin();itObs!=obs->sensedData.end();++itObs,++itDA,++
row)
596 if (itObs->landmarkID<0)
597 obs_idxs_needing_data_assoc.push_back(
row);
602 *itDA = itID->second;
609 if (obs_idxs_needing_data_assoc.empty())
615 for (
size_t idxObs=0;idxObs<data_association.size();idxObs++)
617 int da = data_association[idxObs];
625 const size_t nObsDA = obs_idxs_needing_data_assoc.size();
628 for (
size_t i=0;i<nObsDA;i++)
630 const size_t idx = obs_idxs_needing_data_assoc[i];
631 for (
unsigned k=0;k<obs_size;k++)
632 Z_obs_means.get_unsafe(i,k) =
Z[idx][k];
637 m_pkk.extractMatrix(0,0, Pxx);
641 const size_t nPredictions = lm_indices_in_S.size();
649 for (
size_t q=0;
q<nPredictions;
q++)
651 const size_t i = lm_indices_in_S[
q];
652 for (
size_t w=0;
w<obs_size;
w++)
678 data_association[ it->first ] = it->second;
695 ASSERTMSG_(T>0,
"Vehicle pose quaternion norm is not >0!!")
697 const double T_ = (
m_xkk[3]<0 ? -1.0:1.0)/T;
757 std_sensor_range ( 0.01f),
758 std_sensor_yaw (
DEG2RAD( 0.2f )),
759 std_sensor_pitch (
DEG2RAD( 0.2f )),
760 std_odo_z_additional ( 0),
761 doPartitioningExperiment(false),
762 quantiles_3D_representation ( 3),
763 partitioningMethod(0),
766 data_assoc_IC_chi2_thres (0.99),
768 data_assoc_IC_ml_threshold (0.0),
769 create_simplemap (false),
770 force_ignore_odometry (false)
786 out.
printf(
"\n----------- [CRangeBearingKFSLAM::TOptions] ------------ \n\n");
788 out.
printf(
"doPartitioningExperiment = %c\n", doPartitioningExperiment ?
'Y':
'N' );
789 out.
printf(
"partitioningMethod = %i\n", partitioningMethod );
792 out.
printf(
"data_assoc_IC_chi2_thres = %.06f\n", data_assoc_IC_chi2_thres );
794 out.
printf(
"data_assoc_IC_ml_threshold = %.06f\n", data_assoc_IC_ml_threshold );
808 ASSERTMSG_(obs,
"*ERROR*: This method requires an observation of type CObservationBearingRange")
819 CPose3DQuatPDF::jacobiansPoseComposition(
823 dsensorabs_dsenrelpose,
848 hn_r * chn_y * chn_p,
849 hn_r * shn_y * chn_p,
858 const kftype values_dynlocal_dhn[] = {
859 chn_p*chn_y , -hn_r*chn_p*shn_y , -hn_r*chn_y*shn_p,
860 chn_p*shn_y , hn_r*chn_p*chn_y , -hn_r*shn_p*shn_y,
861 -shn_p , 0 , -hn_r*chn_p
869 yn_rel_sensor.
x, yn_rel_sensor.
y, yn_rel_sensor.
z,
871 &jacob_dyn_dynrelsensor,
872 &jacob_dyn_dsensorabs
876 dyn_dhn.multiply_AB(jacob_dyn_dynrelsensor, dynlocal_dhn);
879 dyn_dxv.multiply_AB(jacob_dyn_dsensorabs, dsensorabs_dvehpose );
891 const size_t in_obsIdx,
892 const size_t in_idxNewFeat )
897 ASSERTMSG_(obs,
"*ERROR*: This method requires an observation of type CObservationBearingRange")
902 ASSERT_( in_obsIdx < obs->sensedData.size() )
904 if (obs->sensedData[in_obsIdx].landmarkID>=0)
908 obs->sensedData[in_obsIdx].landmarkID,
940 m_pkk.extractMatrix(0,0,3,3, COV);
941 pointGauss.
cov = COV;
946 ellip->setPose(pointGauss.
mean);
947 ellip->setCovMatrix(pointGauss.
cov);
948 ellip->enableDrawSolid3D(
false);
950 ellip->set3DsegmentsCount(10);
951 ellip->setColor(1,0,0);
953 outObj->insert( ellip );
959 for (
size_t i=0;i<nLMs;i++)
965 pointGauss.
cov = COV;
969 ellip->setName(
format(
"%u",static_cast<unsigned int>(i) ) );
970 ellip->enableShowName(
true);
971 ellip->setPose( pointGauss.
mean );
972 ellip->setCovMatrix( pointGauss.
cov );
973 ellip->enableDrawSolid3D(
false);
975 ellip->set3DsegmentsCount(10);
977 ellip->setColor(0,0,1);
983 map<int,bool> belongToPartition;
995 CSensoryFramePtr SF_i;
1000 for (
size_t o=0;o<obs->sensedData.size();o++)
1002 if ( obs->sensedData[o].landmarkID == i_th_ID )
1004 belongToPartition[
p]=
true;
1012 string strParts(
"[");
1016 if (it!=belongToPartition.begin()) strParts +=
string(
",");
1017 strParts +=
format(
"%i",it->first);
1020 ellip->setName( ellip->getName() + strParts +
string(
"]") );
1024 outObj->insert( ellip );
1040 vector<vector_uint> partitions;
1045 tmpCluster.push_back(i);
1048 partitions.push_back(tmpCluster);
1050 tmpCluster.push_back(i);
1066 std::vector<vector_uint> &landmarksMembership )
const 1068 landmarksMembership.clear();
1075 for (
size_t i=0;i<nLMs;i++)
1077 map<int,bool> belongToPartition;
1089 CSensoryFramePtr SF_i;
1094 for (
size_t o=0;o<obs->sensedData.size();o++)
1096 if ( obs->sensedData[o].landmarkID == i_th_ID )
1098 belongToPartition[
p]=
true;
1109 membershipOfThisLM.push_back(it->first);
1111 landmarksMembership.push_back( membershipOfThisLM );
1120 const std::vector<vector_uint> &landmarksMembership )
const 1128 fullCov(i,i) = max(fullCov(i,i), 1e-6);
1133 double sumOffBlocks = 0;
1134 unsigned int nLMs = landmarksMembership.size();
1138 for (i=0;i<nLMs;i++)
1140 for (
size_t j=i+1;j<nLMs;j++)
1148 sumOffBlocks += 2 * H.block(
row,col,2,2).sum();
1164 vector<vector_uint> partitions;
1177 const string &styleLandmarks,
1178 const string &stylePath,
1179 const string &styleRobot )
const 1188 os::fprintf(f,
"%%--------------------------------------------------------------------\n");
1189 os::fprintf(f,
"%% File automatically generated using the MRPT method:\n");
1190 os::fprintf(f,
"%% 'CRangeBearingKFSLAM::saveMapAndPath2DRepresentationAsMATLABFile'\n");
1193 os::fprintf(f,
"%% Jose Luis Blanco Claraco, University of Malaga @ 2008\n");
1195 os::fprintf(f,
"%%--------------------------------------------------------------------\n");
1202 for (
size_t i=0;i<nLMs;i++)
1225 CSensoryFramePtr dummySF;
1226 CPose3DPDFPtr pdf3D;
1238 os::fprintf(f,
"plot(ROB_PATH(:,1),ROB_PATH(:,2),'%s');\n",stylePath.c_str());
1289 ASSERTMSG_(obs,
"*ERROR*: This method requires an observation of type CObservationBearingRange")
1291 #define USE_HEURISTIC_PREDICTION 1293 #ifdef USE_HEURISTIC_PREDICTION 1294 const double sensor_max_range = obs->maxSensorDistance;
1295 const double fov_yaw = obs->fieldOfView_yaw;
1296 const double fov_pitch = obs->fieldOfView_pitch;
1298 const double max_vehicle_loc_uncertainty = 4 * std::sqrt(
m_pkk.get_unsafe(0,0) +
m_pkk.get_unsafe(1,1)+
m_pkk.get_unsafe(2,2) );
1301 out_LM_indices_to_predict.clear();
1302 for (
size_t i=0;i<prediction_means.size();i++)
1304 #ifndef USE_HEURISTIC_PREDICTION 1305 out_LM_indices_to_predict.push_back(i);
1308 if ( prediction_means[i][0] < ( 15 + sensor_max_range + max_vehicle_loc_uncertainty + 4*
options.
std_sensor_range) &&
1313 out_LM_indices_to_predict.push_back(i);
void changeCoordinatesReference(const CPose3DQuat &newReferenceBase)
this = p (+) this.
double x() const
Common members of all points & poses classes.
mrpt::math::CArrayNumeric< double, FEAT_SIZE > KFArray_FEAT
FILE BASE_IMPEXP * fopen(const char *fileName, const char *mode) MRPT_NO_THROWS
An OS-independent version of fopen.
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)...
static CEllipsoidPtr Create()
std::string BASE_IMPEXP 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).
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
mrpt::poses::CPose3DQuat getIncrementFromOdometry() const
Return the last odometry, as a pose increment.
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=NULL, mrpt::math::CMatrixFixedNumeric< double, 3, 7 > *out_jacob_dryp_dpose=NULL) const
Computes the spherical coordinates of a 3D point as seen from the 6D pose specified by this object...
void OnObservationJacobians(const size_t &idx_landmark_to_predict, KFMatrix_OxV &Hx, KFMatrix_OxF &Hy) const
Implements the observation Jacobians and (when applicable) .
std::vector< uint32_t > vector_uint
mrpt::math::CArrayNumeric< double, OBS_SIZE > KFArray_OBS
const_iterator end() const
This namespace provides a OS-independent interface to many useful functions: filenames manipulation...
bool force_ignore_odometry
Whether to ignore the input odometry and behave as if there was no odometry at all (default: false) ...
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=NULL, mrpt::math::CMatrixFixedNumeric< double, 3, 7 > *out_jacobian_df_dpose=NULL) const
Computes the 3D point G such as .
This class stores a sequence of <Probabilistic Pose,SensoryFrame> pairs, thus a "metric map" can be t...
void loadFromConfigFile(const mrpt::utils::CConfigFileBase &iniFile, const std::string §ion) MRPT_OVERRIDE
This method load the options from a ".ini"-like file or memory-stored string list.
void markAllNodesForReconsideration()
Mark all nodes for reconsideration in the next call to "updatePartitions", instead of considering jus...
int BASE_IMPEXP void BASE_IMPEXP fclose(FILE *f)
An OS-independent version of fclose.
void reconsiderPartitionsNow()
The partitioning of the entire map is recomputed again.
void OnPreComputingPredictions(const vector_KFArray_OBS &in_all_prediction_means, vector_size_t &out_LM_indices_to_predict) const
This will be called before OnGetObservationsAndDataAssociation to allow the application to reduce the...
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...
size_t getNumberOfLandmarksInTheMap() const
CPose3DQuat mean
The mean value.
void OnObservationModel(const vector_size_t &idx_landmarks_to_predict, vector_KFArray_OBS &out_predictions) const
#define THROW_EXCEPTION(msg)
GLdouble GLdouble GLdouble GLdouble q
bool useMapMatching
If set to true (default), adjacency matrix is computed from maps matching; otherwise, the method CObservation::likelihoodWith will be called directly from the SFs.
void updatePartitions(std::vector< vector_uint > &partitions)
This method executed only the neccesary part of the partition to take into account the lastest added ...
mrpt::utils::bimap< mrpt::maps::CLandmark::TLandmarkID, unsigned int > m_IDs
The mapping between landmark IDs and indexes in the Pkk cov.
This file implements several operations that operate element-wise on individual or pairs of container...
void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source, const std::string §ion) MRPT_OVERRIDE
This method load the options from a ".ini"-like file or memory-stored string list.
void OnNormalizeStateVector()
This method is called after the prediction and after the update, to give the user an opportunity to n...
Column vector, like Eigen::MatrixX*, but automatically initialized to zeros since construction...
mrpt::math::CMatrixDouble77 cov
The 7x7 covariance matrix.
mrpt::vector_size_t predictions_IDs
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.
int BASE_IMPEXP fprintf(FILE *fil, const char *format,...) MRPT_NO_THROWS MRPT_printf_format_check(2
An OS-independent version of fprintf.
void OnTransitionJacobian(KFMatrix_VxV &out_F) const
Implements the transition Jacobian .
CSetOfObjectsPtr OPENGL_IMPEXP CornerXYZ(float scale=1.0)
Returns three arrows representing a X,Y,Z 3D corner.
double computeOffDiagonalBlocksApproximationError(const std::vector< vector_uint > &landmarksMembership) const
Computes the ratio of the missing information matrix elements which are ignored under a certain parti...
void runOneKalmanIteration()
The main entry point, executes one complete step: prediction + update.
const Scalar * const_iterator
double z
X,Y,Z coordinates.
KFMatrix m_pkk
The system full covariance matrix.
mrpt::poses::CPose3DQuat getCurrentRobotPoseMean() const
Get the current robot pose mean, as a 3D+quaternion pose.
int64_t TLandmarkID
The type for the IDs of landmarks.
TDataAssocInfo m_last_data_association
Last data association.
void getLastPartitionLandmarks(std::vector< vector_uint > &landmarksMembership) const
Return the partitioning of the landmarks in clusters accoring to the last partition.
float std_odo_z_additional
Additional std.
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...
void processActionObservation(mrpt::obs::CActionCollectionPtr &action, mrpt::obs::CSensoryFramePtr &SF)
Process one new action and observations to update the map and robot pose estimate.
This class allows loading and storing values and vectors of different types from a configuration text...
T square(const T x)
Inline function for the square of a number.
vector_KFArray_OBS all_predictions
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...
Represents a probabilistic 3D (6D) movement.
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
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 base provides a set of functions for maths stuff.
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.
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...
TDataAssociationMetric data_assoc_metric
A helper class that can convert an enum value into its textual representation, and viceversa...
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()
mrpt::aligned_containers< KFArray_OBS >::vector_t vector_KFArray_OBS
CONTAINER::Scalar sum(const CONTAINER &v)
Computes the sum of all the elements.
const_iterator find_key(const KEY &k) const
mrpt::obs::CActionCollectionPtr m_action
Set up by processActionObservation.
This namespace contains representation of robot actions and observations.
void loadOptions(const mrpt::utils::CConfigFileBase &ini)
Load options from a ini-like file/text.
bool inverse(const VALUE &v, KEY &out_k) const
Get the key associated the given value, VALUE->KEY, returning false if not present.
std::string BASE_IMPEXP format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
mrpt::slam::CIncrementalMapPartitioner::TOptions options
CIncrementalMapPartitioner mapPartitioner
Used for map partitioning experiments.
TDataAssociationMetric data_assoc_IC_metric
Whether to use mahalanobis (->chi2 criterion) vs. Matching likelihood.
std::map< KEY, VALUE >::iterator iterator
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).
mrpt::maps::CSimpleMap m_SFs
The sequence of all the observations and the robot path (kept for debugging, statistics,etc)
GLsizei const GLchar ** string
unsigned int addMapFrame(const mrpt::obs::CSensoryFramePtr &frame, const mrpt::poses::CPosePDFPtr &robotPose2D)
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...
mrpt::obs::CSensoryFramePtr m_SF
Set up by processActionObservation.
mrpt::math::CArrayDouble< 3 > m_coords
The translation vector [x,y,z].
void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source, const std::string §ion) MRPT_OVERRIDE
This method load the options from a ".ini"-like file or memory-stored string list.
double kftype
The numeric type used in the Kalman Filter (default=double)
void get(size_t index, mrpt::poses::CPose3DPDFPtr &out_posePDF, mrpt::obs::CSensoryFramePtr &out_SF) const
Access to the i'th pair, first one is index '0'.
void OnGetObservationNoise(KFMatrix_OxO &out_R) const
Return the observation NOISE covariance matrix, that is, the model of the Gaussian additive noise of ...
#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...
mrpt::math::CMatrixFixedNumeric< double, OBS_SIZE, OBS_SIZE > KFMatrix_OxO
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
void getAs3DObject(mrpt::opengl::CSetOfObjectsPtr &outObj) const
Returns a 3D representation of the landmarks in the map and the robot 3D position according to the cu...
#define ASSERTDEB_(f)
Defines an assertion mechanism - only when compiled in debug.
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
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.
GLenum GLenum GLvoid * row
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 .
GLsizei GLsizei GLchar * source
void OnGetObservationsAndDataAssociation(vector_KFArray_OBS &out_z, vector_int &out_data_association, const vector_KFArray_OBS &in_all_predictions, const KFMatrix &in_S, const 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...
Declares a class that represents a Probability Density function (PDF) of a 3D pose ...
Information for data-association:
std::vector< size_t > vector_size_t
void dumpToTextStream(mrpt::utils::CStream &out) const MRPT_OVERRIDE
This method should clearly display all the contents of the structure in textual form, sending it to a CStream.
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)
std::vector< int32_t > vector_int
TDataAssociationMethod data_assoc_method
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
void insert(const KEY &k, const VALUE &v)
Insert a new pair KEY<->VALUE in the bi-map.
const std::map< VALUE, KEY > & getInverseMap() const
Return a read-only reference to the internal map KEY->VALUES.
mrpt::math::CMatrixFixedNumeric< double, VEH_SIZE, VEH_SIZE > KFMatrix_VxV
mrpt::math::CMatrixFixedNumeric< double, FEAT_SIZE, VEH_SIZE > KFMatrix_FxV
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()
TDataAssociationMethod
Different algorithms for data association, used in mrpt::slam::data_association.
virtual ~CRangeBearingKFSLAM()
Destructor:
std::vector< vector_uint > m_lastPartitionSet
#define ASSERTMSG_(f, __ERROR_MSG)
float std_sensor_range
The std.
KFVector m_xkk
The system state vector.
double data_assoc_IC_chi2_thres
Threshold in [0,1] for the chi2square test for individual compatibility between predictions and obser...
mrpt::math::CMatrixFixedNumeric< double, FEAT_SIZE, OBS_SIZE > KFMatrix_FxO
void SLAM_IMPEXP 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...
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.
virtual int printf(const char *fmt,...) MRPT_printf_format_check(2
Writes a string to the stream in a textual form.
void getLastPartitionLandmarksAsIfFixedSubmaps(size_t K, std::vector< vector_uint > &landmarksMembership)
For testing only: returns the partitioning as "getLastPartitionLandmarks" but as if a fixed-size subm...
mrpt::math::CMatrixFixedNumeric< double, OBS_SIZE, VEH_SIZE > KFMatrix_OxV
mrpt::math::CVectorFloat stds_Q_no_odo
A 7-length vector with the std.
void copyFrom(const CPosePDF &o) MRPT_OVERRIDE
Copy operator, translating if necesary (for example, between particles and gaussian representations) ...