Definition at line 54 of file vision_stereo_rectify/test.cpp.
Public Types | |
using | kftype = double |
The numeric type used in the Kalman Filter (default=double) More... | |
using | KFCLASS = CKalmanFilterCapable< VEH_SIZE, OBS_SIZE, FEAT_SIZE, ACT_SIZE, double > |
My class, in a shorter name! More... | |
using | KFVector = Eigen::Matrix< double, Eigen::Dynamic, 1 > |
using | KFMatrix = mrpt::math::CMatrixTemplateNumeric< double > |
using | KFMatrix_VxV = mrpt::math::CMatrixFixedNumeric< double, VEH_SIZE, VEH_SIZE > |
using | KFMatrix_OxO = mrpt::math::CMatrixFixedNumeric< double, OBS_SIZE, OBS_SIZE > |
using | KFMatrix_FxF = mrpt::math::CMatrixFixedNumeric< double, FEAT_SIZE, FEAT_SIZE > |
using | KFMatrix_AxA = mrpt::math::CMatrixFixedNumeric< double, ACT_SIZE, ACT_SIZE > |
using | KFMatrix_VxO = mrpt::math::CMatrixFixedNumeric< double, VEH_SIZE, OBS_SIZE > |
using | KFMatrix_VxF = mrpt::math::CMatrixFixedNumeric< double, VEH_SIZE, FEAT_SIZE > |
using | KFMatrix_FxV = mrpt::math::CMatrixFixedNumeric< double, FEAT_SIZE, VEH_SIZE > |
using | KFMatrix_FxO = mrpt::math::CMatrixFixedNumeric< double, FEAT_SIZE, OBS_SIZE > |
using | KFMatrix_OxF = mrpt::math::CMatrixFixedNumeric< double, OBS_SIZE, FEAT_SIZE > |
using | KFMatrix_OxV = mrpt::math::CMatrixFixedNumeric< double, OBS_SIZE, VEH_SIZE > |
using | KFArray_VEH = mrpt::math::CArrayNumeric< double, VEH_SIZE > |
using | KFArray_ACT = mrpt::math::CArrayNumeric< double, ACT_SIZE > |
using | KFArray_OBS = mrpt::math::CArrayNumeric< double, OBS_SIZE > |
using | vector_KFArray_OBS = mrpt::aligned_std_vector< KFArray_OBS > |
using | KFArray_FEAT = mrpt::math::CArrayNumeric< double, FEAT_SIZE > |
Public Member Functions | |
CRangeBearing () | |
virtual | ~CRangeBearing () |
void | doProcess (double DeltaTime, double observationRange, double observationBearing) |
void | getState (KFVector &xkk, KFMatrix &pkk) |
size_t | getNumberOfLandmarksInTheMap () const |
bool | isMapEmpty () const |
size_t | getStateVectorLength () const |
KFVector & | internal_getXkk () |
KFMatrix & | internal_getPkk () |
void | getLandmarkMean (size_t idx, KFArray_FEAT &feat) const |
Returns the mean of the estimated value of the idx'th landmark (not applicable to non-SLAM problems). More... | |
void | getLandmarkCov (size_t idx, KFMatrix_FxF &feat_cov) const |
Returns the covariance of the idx'th landmark (not applicable to non-SLAM problems). More... | |
mrpt::system::CTimeLogger & | getProfiler () |
Static Public Member Functions | |
static size_t | get_vehicle_size () |
static size_t | get_observation_size () |
static size_t | get_feature_size () |
static size_t | get_action_size () |
Public Attributes | |
TKF_options | KF_options |
Generic options for the Kalman Filter algorithm itself. More... | |
Protected Member Functions | |
void | runOneKalmanIteration () |
The main entry point, executes one complete step: prediction + update. More... | |
Virtual methods for Kalman Filter implementation | |
void | OnGetAction (KFArray_ACT &out_u) const |
Must return the action vector u. More... | |
void | OnTransitionModel (const KFArray_ACT &in_u, KFArray_VEH &inout_x, bool &out_skipPrediction) const |
Implements the transition model ![]() | |
void | OnTransitionJacobian (KFMatrix_VxV &out_F) const |
Implements the transition Jacobian ![]() | |
void | OnTransitionNoise (KFMatrix_VxV &out_Q) const |
Implements the transition noise covariance ![]() | |
void | OnGetObservationNoise (KFMatrix_OxO &out_R) const |
Return the observation NOISE covariance matrix, that is, the model of the Gaussian additive noise of the sensor. More... | |
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 the observations and, when applicable, the data association between these observations and the current map. More... | |
void | OnObservationModel (const std::vector< size_t > &idx_landmarks_to_predict, vector_KFArray_OBS &out_predictions) const |
Implements the observation prediction ![]() | |
void | OnObservationJacobians (const size_t &idx_landmark_to_predict, KFMatrix_OxV &Hx, KFMatrix_OxF &Hy) const |
Implements the observation Jacobians ![]() ![]() | |
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 scalar components (eg, angles). More... | |
Protected Attributes | |
float | m_obsBearing |
float | m_obsRange |
float | m_deltaTime |
mrpt::system::CTimeLogger | m_timLogger |
Kalman filter state | |
KFVector | m_xkk |
The system state vector. More... | |
KFMatrix | m_pkk |
The system full covariance matrix. More... | |
Kalman filter state | |
KFVector | m_xkk |
The system state vector. More... | |
KFMatrix | m_pkk |
The system full covariance matrix. More... | |
Static Private Member Functions | |
static void | KF_aux_estimate_trans_jacobian (const KFArray_VEH &x, const std::pair< KFCLASS *, KFArray_ACT > &dat, KFArray_VEH &out_x) |
Auxiliary functions for Jacobian numeric estimation. More... | |
static void | KF_aux_estimate_obs_Hx_jacobian (const KFArray_VEH &x, const std::pair< KFCLASS *, size_t > &dat, KFArray_OBS &out_x) |
static void | KF_aux_estimate_obs_Hy_jacobian (const KFArray_FEAT &x, const std::pair< KFCLASS *, size_t > &dat, KFArray_OBS &out_x) |
Private Attributes | |
vector_KFArray_OBS | all_predictions |
std::vector< size_t > | predictLMidxs |
mrpt::aligned_std_vector< KFMatrix_OxV > | Hxs |
The vector of all partial Jacobians dh[i]_dx for each prediction. More... | |
mrpt::aligned_std_vector< KFMatrix_OxF > | Hys |
The vector of all partial Jacobians dh[i]_dy[i] for each prediction. More... | |
KFMatrix | S |
KFMatrix | Pkk_subset |
vector_KFArray_OBS | Z |
KFMatrix | K |
KFMatrix | S_1 |
KFMatrix | dh_dx_full_obs |
KFMatrix | aux_K_dh_dx |
bool | m_user_didnt_implement_jacobian |
Virtual methods for Kalman Filter implementation | |
virtual 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 extend the "map" with a new "element". More... | |
virtual void | OnInverseObservationModel (const KFArray_OBS &in_z, KFArray_FEAT &out_yn, KFMatrix_FxV &out_dyn_dxv, KFMatrix_FxO &out_dyn_dhn, KFMatrix_FxF &out_dyn_dhn_R_dyn_dhnT, bool &out_use_dyn_dhn_jacobian) const |
If applicable to the given problem, this method implements the inverse observation model needed to extend the "map" with a new "element". More... | |
virtual 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. More... | |
virtual void | OnNormalizeStateVector () |
This method is called after the prediction and after the update, to give the user an opportunity to normalize the state vector (eg, keep angles within -pi,pi range) if the application requires it. More... | |
virtual void | OnPostIteration () |
This method is called after finishing one KF iteration and before returning from runOneKalmanIteration(). More... | |
virtual void | OnTransitionJacobianNumericGetIncrements (KFArray_VEH &out_increments) const |
Only called if using a numeric approximation of the transition Jacobian, this method must return the increments in each dimension of the vehicle state vector while estimating the Jacobian. More... | |
virtual 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 number of covariance landmark predictions to be made. More... | |
virtual 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)=0 |
This is called between the KF prediction step and the update step, and the application must return the observations and, when applicable, the data association between these observations and the current map. More... | |
virtual void | OnObservationModel (const std::vector< size_t > &idx_landmarks_to_predict, vector_KFArray_OBS &out_predictions) const=0 |
Implements the observation prediction ![]() | |
virtual void | OnObservationJacobiansNumericGetIncrements (KFArray_VEH &out_veh_increments, KFArray_FEAT &out_feat_increments) const |
Only called if using a numeric approximation of the observation Jacobians, this method must return the increments in each dimension of the vehicle state vector while estimating the Jacobian. More... | |
|
inherited |
Definition at line 268 of file CKalmanFilterCapable.h.
|
inherited |
Definition at line 271 of file CKalmanFilterCapable.h.
|
inherited |
Definition at line 269 of file CKalmanFilterCapable.h.
|
inherited |
Definition at line 267 of file CKalmanFilterCapable.h.
|
inherited |
My class, in a shorter name!
Definition at line 239 of file CKalmanFilterCapable.h.
|
inherited |
Definition at line 243 of file CKalmanFilterCapable.h.
|
inherited |
Definition at line 252 of file CKalmanFilterCapable.h.
|
inherited |
Definition at line 250 of file CKalmanFilterCapable.h.
|
inherited |
Definition at line 261 of file CKalmanFilterCapable.h.
|
inherited |
Definition at line 259 of file CKalmanFilterCapable.h.
|
inherited |
Definition at line 263 of file CKalmanFilterCapable.h.
|
inherited |
Definition at line 248 of file CKalmanFilterCapable.h.
|
inherited |
Definition at line 265 of file CKalmanFilterCapable.h.
|
inherited |
Definition at line 257 of file CKalmanFilterCapable.h.
|
inherited |
Definition at line 255 of file CKalmanFilterCapable.h.
|
inherited |
Definition at line 246 of file CKalmanFilterCapable.h.
|
inherited |
The numeric type used in the Kalman Filter (default=double)
Definition at line 236 of file CKalmanFilterCapable.h.
|
inherited |
Definition at line 242 of file CKalmanFilterCapable.h.
|
inherited |
Definition at line 270 of file CKalmanFilterCapable.h.
CRangeBearing::CRangeBearing | ( | ) |
Definition at line 425 of file vision_stereo_rectify/test.cpp.
|
virtual |
Definition at line 444 of file vision_stereo_rectify/test.cpp.
void CRangeBearing::doProcess | ( | double | DeltaTime, |
double | observationRange, | ||
double | observationBearing | ||
) |
Definition at line 445 of file vision_stereo_rectify/test.cpp.
|
inlinestaticinherited |
Definition at line 229 of file CKalmanFilterCapable.h.
|
inlinestaticinherited |
Definition at line 228 of file CKalmanFilterCapable.h.
|
inlinestaticinherited |
Definition at line 227 of file CKalmanFilterCapable.h.
|
inlinestaticinherited |
Definition at line 226 of file CKalmanFilterCapable.h.
|
inlineinherited |
Returns the covariance of the idx'th landmark (not applicable to non-SLAM problems).
std::exception | On idx>= getNumberOfLandmarksInTheMap() |
Definition at line 291 of file CKalmanFilterCapable.h.
|
inlineinherited |
Returns the mean of the estimated value of the idx'th landmark (not applicable to non-SLAM problems).
std::exception | On idx>= getNumberOfLandmarksInTheMap() |
Definition at line 280 of file CKalmanFilterCapable.h.
|
inlineinherited |
Definition at line 230 of file CKalmanFilterCapable.h.
|
inlineinherited |
Definition at line 616 of file CKalmanFilterCapable.h.
Definition at line 66 of file vision_stereo_rectify/test.cpp.
|
inlineinherited |
Definition at line 273 of file CKalmanFilterCapable.h.
|
inlineinherited |
Definition at line 275 of file CKalmanFilterCapable.h.
|
inlineinherited |
Definition at line 274 of file CKalmanFilterCapable.h.
|
inlineinherited |
Definition at line 234 of file CKalmanFilterCapable.h.
|
staticprivateinherited |
Definition at line 1217 of file CKalmanFilterCapable_impl.h.
|
staticprivateinherited |
Definition at line 1234 of file CKalmanFilterCapable_impl.h.
|
staticprivateinherited |
Auxiliary functions for Jacobian numeric estimation.
Definition at line 1204 of file CKalmanFilterCapable_impl.h.
|
protectedvirtual |
Must return the action vector u.
out_u | The action vector which will be passed to OnTransitionModel |
Implements mrpt::bayes::CKalmanFilterCapable< 4, 2, 0, 1 >.
Definition at line 458 of file vision_stereo_rectify/test.cpp.
|
protectedvirtual |
Return the observation NOISE covariance matrix, that is, the model of the Gaussian additive noise of the sensor.
out_R | The noise covariance matrix. It might be non diagonal, but it'll usually be. |
Implements mrpt::bayes::CKalmanFilterCapable< 4, 2, 0, 1 >.
Definition at line 509 of file vision_stereo_rectify/test.cpp.
|
protected |
This is called between the KF prediction step and the update step, and the application must return the observations and, when applicable, the data association between these observations and the current map.
out_z | N vectors, each for one "observation" of length OBS_SIZE, N being the number of "observations": how many observed landmarks for a map, or just one if not applicable. |
out_data_association | An empty vector or, where applicable, a vector where the i'th element corresponds to the position of the observation in the i'th row of out_z within the system state vector (in the range [0,getNumberOfLandmarksInTheMap()-1]), or -1 if it is a new map element and we want to insert it at the end of this KF iteration. |
in_all_predictions | A vector with the prediction of ALL the landmarks in the map. Note that, in contrast, in_S only comprises a subset of all the landmarks. |
in_S | The full covariance matrix of the observation predictions (i.e. the "innovation covariance matrix"). This is a MĀ·O x MĀ·O matrix with M=length of "in_lm_indices_in_S". |
in_lm_indices_in_S | The indices of the map landmarks (range [0,getNumberOfLandmarksInTheMap()-1]) that can be found in the matrix in_S. |
This method will be called just once for each complete KF iteration.
Definition at line 515 of file vision_stereo_rectify/test.cpp.
|
protectedpure virtualinherited |
This is called between the KF prediction step and the update step, and the application must return the observations and, when applicable, the data association between these observations and the current map.
out_z | N vectors, each for one "observation" of length OBS_SIZE, N being the number of "observations": how many observed landmarks for a map, or just one if not applicable. |
out_data_association | An empty vector or, where applicable, a vector where the i'th element corresponds to the position of the observation in the i'th row of out_z within the system state vector (in the range [0,getNumberOfLandmarksInTheMap()-1]), or -1 if it is a new map element and we want to insert it at the end of this KF iteration. |
in_all_predictions | A vector with the prediction of ALL the landmarks in the map. Note that, in contrast, in_S only comprises a subset of all the landmarks. |
in_S | The full covariance matrix of the observation predictions (i.e. the "innovation covariance matrix"). This is a M*O x M*O matrix with M=length of "in_lm_indices_in_S". |
in_lm_indices_in_S | The indices of the map landmarks (range [0,getNumberOfLandmarksInTheMap()-1]) that can be found in the matrix in_S. |
This method will be called just once for each complete KF iteration.
|
inlinevirtualinherited |
If applicable to the given problem, this method implements the inverse observation model needed to extend the "map" with a new "element".
in_z | The observation vector whose inverse sensor model is to be computed. This is actually one of the vector<> returned by OnGetObservationsAndDataAssociation(). |
out_yn | The F-length vector with the inverse observation model ![]() |
out_dyn_dxv | The ![]() ![]() |
out_dyn_dhn | The ![]() ![]() |
Definition at line 504 of file CKalmanFilterCapable.h.
|
inlinevirtualinherited |
If applicable to the given problem, this method implements the inverse observation model needed to extend the "map" with a new "element".
The uncertainty in the new map feature comes from two parts: one from the vehicle uncertainty (through the out_dyn_dxv Jacobian), and another from the uncertainty in the observation itself. By default, out_use_dyn_dhn_jacobian=true on call, and if it's left at "true", the base KalmanFilter class will compute the uncertainty of the landmark relative position from out_dyn_dhn. Only in some problems (e.g. MonoSLAM), it'll be needed for the application to directly return the covariance matrix out_dyn_dhn_R_dyn_dhnT, which is the equivalent to:
\f$ \frac{\partial y_n}{\partial h_n} R \frac{\partial
y_n}{\partial h_n}^\top y_n=y(x,z_n)
@_fakenlF \times V
\frac{\partial y_n}{\partial x_v}
@_fakenlF \times O
\frac{\partial y_n}{\partial h_n}
Definition at line 557 of file CKalmanFilterCapable.h.
|
inlinevirtualinherited |
If applicable to the given problem, do here any special handling of adding a new landmark to the map.
in_obsIndex | The index of the observation whose inverse sensor is to be computed. It corresponds to the row in in_z where the observation can be found. |
in_idxNewFeat | The index that this new feature will have in the state vector (0:just after the vehicle state, 1: after that,...). Save this number so data association can be done according to these indices. |
Definition at line 580 of file CKalmanFilterCapable.h.
|
inlinevirtualinherited |
This method is called after the prediction and after the update, to give the user an opportunity to normalize the state vector (eg, keep angles within -pi,pi range) if the application requires it.
Definition at line 592 of file CKalmanFilterCapable.h.
|
protectedvirtual |
Implements the observation Jacobians and (when applicable)
.
Implements the observation Jacobians and (when applicable)
.
idx_landmark_to_predict | The index of the landmark in the map whose prediction is expected as output. For non SLAM-like problems, this will be zero and the expected output is for the whole state vector. |
Hx | The output Jacobian ![]() |
Hy | The output Jacobian ![]() |
idx_landmark_to_predict | The index of the landmark in the map whose prediction is expected as output. For non SLAM-like problems, this will be zero and the expected output is for the whole state vector. |
Hx | The output Jacobian ![]() |
Hy | The output Jacobian ![]() |
Reimplemented from mrpt::bayes::CKalmanFilterCapable< 4, 2, 0, 1 >.
Definition at line 559 of file vision_stereo_rectify/test.cpp.
|
inlineprotectedvirtualinherited |
Only called if using a numeric approximation of the observation Jacobians, this method must return the increments in each dimension of the vehicle state vector while estimating the Jacobian.
Definition at line 464 of file CKalmanFilterCapable.h.
|
protected |
Implements the observation prediction .
idx_landmark_to_predict | The indices of the landmarks in the map whose predictions are expected as output. For non SLAM-like problems, this input value is undefined and the application should just generate one observation for the given problem. |
out_predictions | The predicted observations. |
Definition at line 534 of file vision_stereo_rectify/test.cpp.
|
protectedpure virtualinherited |
Implements the observation prediction .
idx_landmark_to_predict | The indices of the landmarks in the map whose predictions are expected as output. For non SLAM-like problems, this input value is undefined and the application should just generate one observation for the given problem. |
out_predictions | The predicted observations. |
|
inlinevirtualinherited |
This method is called after finishing one KF iteration and before returning from runOneKalmanIteration().
Definition at line 600 of file CKalmanFilterCapable.h.
|
inlineprotectedvirtualinherited |
This will be called before OnGetObservationsAndDataAssociation to allow the application to reduce the number of covariance landmark predictions to be made.
For example, features which are known to be "out of sight" shouldn't be added to the output list to speed up the calculations.
in_all_prediction_means | The mean of each landmark predictions; the computation or not of the corresponding covariances is what we're trying to determined with this method. |
out_LM_indices_to_predict | The list of landmark indices in the map [0,getNumberOfLandmarksInTheMap()-1] that should be predicted. |
Definition at line 378 of file CKalmanFilterCapable.h.
|
protectedvirtual |
Computes A=A-B, which may need to be re-implemented depending on the topology of the individual scalar components (eg, angles).
Reimplemented from mrpt::bayes::CKalmanFilterCapable< 4, 2, 0, 1 >.
Definition at line 580 of file vision_stereo_rectify/test.cpp.
|
protectedvirtual |
Implements the transition Jacobian .
out_F | Must return the Jacobian. The returned matrix must be ![]() |
Reimplemented from mrpt::bayes::CKalmanFilterCapable< 4, 2, 0, 1 >.
Definition at line 483 of file vision_stereo_rectify/test.cpp.
|
inlineprotectedvirtualinherited |
Only called if using a numeric approximation of the transition Jacobian, this method must return the increments in each dimension of the vehicle state vector while estimating the Jacobian.
Definition at line 350 of file CKalmanFilterCapable.h.
|
protectedvirtual |
Implements the transition model .
in_u | The vector returned by OnGetAction. |
inout_x | At input has ![]() ![]() |
out_skip | Set this to true if for some reason you want to skip the prediction step (to do not modify either the vector or the covariance). Default:false |
Implements mrpt::bayes::CKalmanFilterCapable< 4, 2, 0, 1 >.
Definition at line 468 of file vision_stereo_rectify/test.cpp.
|
protectedvirtual |
Implements the transition noise covariance .
out_Q | Must return the covariance matrix. The returned matrix must be of the same size than the jacobian from OnTransitionJacobian |
Implements mrpt::bayes::CKalmanFilterCapable< 4, 2, 0, 1 >.
Definition at line 496 of file vision_stereo_rectify/test.cpp.
|
protectedinherited |
The main entry point, executes one complete step: prediction + update.
It is protected since derived classes must provide a problem-specific entry point for users. The exact order in which this method calls the virtual method is explained in http://www.mrpt.org/Kalman_Filters
Definition at line 27 of file CKalmanFilterCapable_impl.h.
|
privateinherited |
Definition at line 624 of file CKalmanFilterCapable.h.
|
privateinherited |
Definition at line 636 of file CKalmanFilterCapable.h.
|
privateinherited |
Definition at line 635 of file CKalmanFilterCapable.h.
|
privateinherited |
The vector of all partial Jacobians dh[i]_dx for each prediction.
Definition at line 627 of file CKalmanFilterCapable.h.
|
privateinherited |
The vector of all partial Jacobians dh[i]_dy[i] for each prediction.
Definition at line 629 of file CKalmanFilterCapable.h.
|
privateinherited |
Definition at line 633 of file CKalmanFilterCapable.h.
|
inherited |
Generic options for the Kalman Filter algorithm itself.
Definition at line 618 of file CKalmanFilterCapable.h.
|
protected |
Definition at line 74 of file vision_stereo_rectify/test.cpp.
|
protected |
Definition at line 73 of file vision_stereo_rectify/test.cpp.
|
protected |
Definition at line 73 of file vision_stereo_rectify/test.cpp.
|
protectedinherited |
The system full covariance matrix.
Definition at line 304 of file CKalmanFilterCapable.h.
|
protectedinherited |
Definition at line 308 of file CKalmanFilterCapable.h.
|
mutableprivateinherited |
Definition at line 648 of file CKalmanFilterCapable.h.
|
protectedinherited |
The system state vector.
Definition at line 302 of file CKalmanFilterCapable.h.
|
privateinherited |
Definition at line 631 of file CKalmanFilterCapable.h.
|
privateinherited |
Definition at line 625 of file CKalmanFilterCapable.h.
|
privateinherited |
Definition at line 630 of file CKalmanFilterCapable.h.
|
privateinherited |
Definition at line 634 of file CKalmanFilterCapable.h.
|
privateinherited |
Definition at line 632 of file CKalmanFilterCapable.h.
Page generated by Doxygen 1.8.17 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at miƩ 12 jul 2023 10:03:34 CEST |