21 #if MRPT_HAS_WXWIDGETS 23 #include <wx/busyinfo.h> 25 #include <wx/msgdlg.h> 26 #include <wx/progdlg.h> 27 #include <wx/string.h> 28 #endif // MRPT_HAS_WXWIDGETS 59 #if MRPT_HAS_WXWIDGETS 61 std::unique_ptr<wxBusyCursor> waitCursorPtr;
62 if (isGUI) waitCursorPtr = std::make_unique<wxBusyCursor>();
71 set<string> lstGPSLabels;
81 if (outInfo) *outInfo = outInfoTemp;
83 map<string, map<Clock::time_point, TPoint3D>>
87 bool ref_valid =
false;
98 ref_valid = !
ref.isClear();
101 const double std_0 = memFil.
read_double(
"CONSISTENCY_TEST",
"std_0", 0);
102 bool doConsistencyCheck = std_0 > 0;
106 const bool doUncertaintyCovs = outInfoTemp.
W_star.
rows() != 0;
107 if (doUncertaintyCovs &&
110 "ERROR: W_star matrix for uncertainty estimation is provided but " 111 "it's not a 6x6 matrix.");
116 #if MRPT_HAS_WXWIDGETS 117 wxProgressDialog* progDia =
nullptr;
120 progDia =
new wxProgressDialog(
121 wxT(
"Building map"), wxT(
"Getting GPS observations..."),
122 (
int)(last -
first + 1),
124 wxPD_CAN_ABORT | wxPD_APP_MODAL | wxPD_SMOOTH | wxPD_AUTO_HIDE |
125 wxPD_ELAPSED_TIME | wxPD_ESTIMATED_TIME | wxPD_REMAINING_TIME);
130 using TListGPSs = std::map<
132 TListGPSs list_gps_obs;
134 map<string, size_t> GPS_RTK_reads;
135 map<string, TPoint3D>
136 GPS_local_coords_on_vehicle;
138 for (
size_t i =
first; !abort && i <= last; i++)
145 case CRawlog::etObservation:
154 if (obs->has_GGA_datum &&
159 list_gps_obs[obs->timestamp][obs->sensorLabel] = obs;
161 lstGPSLabels.insert(obs->sensorLabel);
165 if (obs->has_GGA_datum &&
171 GPS_RTK_reads[obs->sensorLabel]++;
175 if (GPS_local_coords_on_vehicle.find(
177 GPS_local_coords_on_vehicle.end())
178 GPS_local_coords_on_vehicle[obs->sensorLabel] =
179 TPoint3D(obs->sensorPose.asTPose());
185 gps_paths[obs->sensorLabel][obs->timestamp] =
TPoint3D(
199 if ((
count++ % 100) == 0)
201 #if MRPT_HAS_WXWIDGETS 204 if (!progDia->Update((
int)(i -
first))) abort =
true;
211 #if MRPT_HAS_WXWIDGETS 225 map<set<string>,
double> Ad_ij;
226 map<set<string>,
double>
230 map<size_t, string> D_cov_rev_indexes;
236 if (doConsistencyCheck && GPS_local_coords_on_vehicle.size() == 3)
238 unsigned int cnt = 0;
239 for (
auto i = GPS_local_coords_on_vehicle.begin();
240 i != GPS_local_coords_on_vehicle.end(); ++i)
243 D_cov_indexes[i->first] = cnt;
244 D_cov_rev_indexes[cnt] = i->first;
247 for (
auto j = i; j != GPS_local_coords_on_vehicle.end(); ++j)
254 phi_ij[
make_set(i->first, j->first)] =
255 atan2(pj.
y - pi.
y, pj.
x - pi.
x);
259 ASSERT_(D_cov_indexes.size() == 3 && D_cov_rev_indexes.size() == 3);
261 D_cov.
setSize(D_cov_indexes.size(), D_cov_indexes.size());
262 D_mean.
resize(D_cov_indexes.size());
269 square(Ad_ij[
make_set(D_cov_rev_indexes[0], D_cov_rev_indexes[1])]);
272 square(Ad_ij[
make_set(D_cov_rev_indexes[0], D_cov_rev_indexes[2])]);
275 square(Ad_ij[
make_set(D_cov_rev_indexes[1], D_cov_rev_indexes[2])]);
278 Ad_ij[
make_set(D_cov_rev_indexes[0], D_cov_rev_indexes[1])] *
279 Ad_ij[
make_set(D_cov_rev_indexes[0], D_cov_rev_indexes[2])] *
280 cos(phi_ij[
make_set(D_cov_rev_indexes[0], D_cov_rev_indexes[1])] -
281 phi_ij[
make_set(D_cov_rev_indexes[0], D_cov_rev_indexes[2])]);
282 D_cov(0, 1) = D_cov(1, 0);
285 -Ad_ij[
make_set(D_cov_rev_indexes[0], D_cov_rev_indexes[1])] *
286 Ad_ij[
make_set(D_cov_rev_indexes[1], D_cov_rev_indexes[2])] *
287 cos(phi_ij[
make_set(D_cov_rev_indexes[0], D_cov_rev_indexes[1])] -
288 phi_ij[
make_set(D_cov_rev_indexes[1], D_cov_rev_indexes[2])]);
289 D_cov(0, 2) = D_cov(2, 0);
292 Ad_ij[
make_set(D_cov_rev_indexes[0], D_cov_rev_indexes[2])] *
293 Ad_ij[
make_set(D_cov_rev_indexes[1], D_cov_rev_indexes[2])] *
294 cos(phi_ij[
make_set(D_cov_rev_indexes[0], D_cov_rev_indexes[2])] -
295 phi_ij[
make_set(D_cov_rev_indexes[1], D_cov_rev_indexes[2])]);
296 D_cov(1, 2) = D_cov(2, 1);
298 D_cov *= 4 *
square(std_0);
305 square(Ad_ij[
make_set(D_cov_rev_indexes[0], D_cov_rev_indexes[1])]);
307 square(Ad_ij[
make_set(D_cov_rev_indexes[0], D_cov_rev_indexes[2])]);
309 square(Ad_ij[
make_set(D_cov_rev_indexes[1], D_cov_rev_indexes[2])]);
312 doConsistencyCheck =
false;
317 int N_GPSs = list_gps_obs.size();
323 if (list_gps_obs.size() > 4)
325 auto F = list_gps_obs.begin();
328 auto E = list_gps_obs.end();
332 for (
auto it = F; it != E; ++it)
336 std::map<std::string, CObservationGPS::Ptr>& GPS = it->second;
339 for (
const auto& lstGPSLabel : lstGPSLabels)
342 bool fnd = (GPS.find(lstGPSLabel) != GPS.end());
355 if (i_b1->second.find(lstGPSLabel) != i_b1->second.end())
356 GPS_b1 = i_b1->second.find(lstGPSLabel)->second;
358 if (i_a1->second.find(lstGPSLabel) != i_a1->second.end())
359 GPS_a1 = i_a1->second.find(lstGPSLabel)->second;
361 if (!disableGPSInterp && GPS_a1 && GPS_b1)
364 GPS_b1->timestamp, GPS_a1->timestamp) < 0.5)
366 auto new_gps = CObservationGPS::Create(*GPS_a1);
367 new_gps->sensorLabel = lstGPSLabel;
377 .fields.longitude_degrees =
382 .fields.longitude_degrees);
384 .fields.latitude_degrees =
389 .fields.latitude_degrees);
391 .fields.altitude_meters =
396 .fields.altitude_meters);
400 (GPS_a1->timestamp.time_since_epoch()
402 GPS_b1->timestamp.time_since_epoch()
406 it->second[new_gps->sensorLabel] = new_gps;
413 #if MRPT_HAS_WXWIDGETS 414 wxProgressDialog* progDia3 =
nullptr;
417 progDia3 =
new wxProgressDialog(
418 wxT(
"Building map"), wxT(
"Estimating 6D path..."),
421 wxPD_CAN_ABORT | wxPD_APP_MODAL | wxPD_SMOOTH | wxPD_AUTO_HIDE |
422 wxPD_ELAPSED_TIME | wxPD_ESTIMATED_TIME |
423 wxPD_REMAINING_TIME);
429 for (
auto i = list_gps_obs.begin(); i != list_gps_obs.end();
433 if (i->second.size() >= 3)
435 const size_t N = i->second.size();
436 std::map<std::string, CObservationGPS::Ptr>& GPS = i->second;
438 std::map<string, size_t>
447 .getAsStruct<TGeodeticCoords>();
453 std::map<std::string, CObservationGPS::Ptr>::iterator g_it;
455 for (k = 0, g_it = GPS.begin(); g_it != GPS.end(); ++g_it, ++k)
465 string(
"OFFSET_") + g_it->second->sensorLabel;
470 XYZidxs[g_it->second->sensorLabel] =
477 g_it->second->sensorPose.x(),
478 g_it->second->sensorPose.y(),
479 g_it->second->sensorPose
488 if (doConsistencyCheck && GPS.size() == 3)
499 X[XYZidxs[D_cov_rev_indexes[0]]],
500 Y[XYZidxs[D_cov_rev_indexes[0]]],
501 Z[XYZidxs[D_cov_rev_indexes[0]]]);
503 X[XYZidxs[D_cov_rev_indexes[1]]],
504 Y[XYZidxs[D_cov_rev_indexes[1]]],
505 Z[XYZidxs[D_cov_rev_indexes[1]]]);
507 X[XYZidxs[D_cov_rev_indexes[2]]],
508 Y[XYZidxs[D_cov_rev_indexes[2]]],
509 Z[XYZidxs[D_cov_rev_indexes[2]]]);
516 iGPSdist2, D_mean, D_cov_1);
526 double optimal_scale;
531 corrs, optimal_pose, optimal_scale,
true);
546 robot_path.
insert(i->first, veh_pose);
549 if (doUncertaintyCovs)
553 final_veh_uncert.
cov = outInfoTemp.
W_star;
559 final_veh_uncert.
cov;
564 if ((
count++ % 100) == 0)
566 #if MRPT_HAS_WXWIDGETS 569 if (!progDia3->Update(idx_in_GPSs)) abort =
true;
576 #if MRPT_HAS_WXWIDGETS 584 if (PATH_SMOOTH_FILTER > 0 && robot_path.
size() > 1)
590 const double MAX_DIST_TO_FILTER = 4.0;
592 for (
auto i = robot_path.
begin(); i != robot_path.
end(); ++i)
603 k < PATH_SMOOTH_FILTER &&
q != robot_path.
begin(); k++)
615 k < PATH_SMOOTH_FILTER &&
q != (--robot_path.
end()); k++)
630 filtered_robot_path.
insert(i->first,
p);
633 robot_path = filtered_robot_path;
645 for (
auto& GPS_RTK_read : GPS_RTK_reads)
647 if (GPS_RTK_read.second > bestNum)
649 bestNum = GPS_RTK_read.second;
650 bestLabel = GPS_RTK_read.first;
657 const string sect =
string(
"OFFSET_") + bestLabel;
658 const double off_X = memFil.
read_double(sect,
"x", 0);
659 const double off_Y = memFil.
read_double(sect,
"y", 0);
660 const double off_Z = memFil.
read_double(sect,
"z", 0);
681 if (outInfo) *outInfo = outInfoTemp;
mrpt::math::CQuaternionDouble & quat()
Read/Write access to the quaternion representing the 3D rotation.
std::chrono::duration< rep, period > duration
This class implements a config file-like interface over a memory-stored string list.
GLuint GLuint GLsizei count
double averageWrap2Pi(const CVectorDouble &angles)
Computes the average of a sequence of angles in radians taking into account the correct wrapping in t...
uint8_t fix_quality
NMEA standard values: 0 = invalid, 1 = GPS fix (SPS), 2 = DGPS fix, 3 = PPS fix, 4 = Real Time Kinema...
CPose3D mean
The mean value.
double x
X,Y,Z coordinates.
double latitude_degrees
The measured latitude, in degrees (North:+ , South:-)
std::chrono::time_point< Clock > time_point
#define THROW_EXCEPTION(msg)
T y() const
Return y coordinate of the quaternion.
void read_matrix(const std::string §ion, const std::string &name, MATRIX_TYPE &outMatrix, const MATRIX_TYPE &defaultMatrix=MATRIX_TYPE(), bool failIfNotFound=false) const
Reads a configuration parameter as a matrix written in a matlab-like format - for example: "[2 3 4 ; ...
GLdouble GLdouble GLdouble GLdouble q
A set of geodetic coordinates: latitude, longitude and height, defined over a given geoid (typically...
void geodeticToENU_WGS84(const TGeodeticCoords &in_coords, mrpt::math::TPoint3D &out_ENU_point, const TGeodeticCoords &in_coords_origin)
Coordinates transformation from longitude/latitude/height to ENU (East-North-Up) X/Y/Z coordinates Th...
void setInterpolationMethod(TInterpolatorMethod method)
Change the method used to interpolate the robot path.
Used to return optional information from mrpt::topography::path_from_rtk_gps.
void push_back(const T &val)
T square(const T x)
Inline function for the square of a number.
#define ASSERT_(f)
Defines an assertion mechanism.
double altitude_meters
The measured altitude, in meters (A).
This base provides a set of functions for maths stuff.
T r() const
Return r coordinate of the quaternion.
#define CLASS_ID(T)
Access to runtime class ID for a defined class name.
#define MRPT_CHECK_NORMAL_NUMBER(v)
Throws an exception if the number is NaN, IND, or +/-INF, or return the same number otherwise...
CObservation::Ptr getAsObservation(size_t index) const
Returns the i'th element in the sequence, as being an observation, where index=0 is the first object...
std::map< mrpt::Clock::time_point, mrpt::math::CMatrixDouble66 > vehicle_uncertainty
The 6x6 covariance matrix for the uncertainty of each vehicle pose (may be empty if there is no W_sta...
double distanceTo(const TPoint3D &p) const
Point-to-point distance.
double longitude_degrees
The measured longitude, in degrees (East:+ , West:-)
This class stores a rawlog (robotic datasets) in one of two possible formats:
This namespace contains representation of robot actions and observations.
double read_double(const std::string §ion, const std::string &name, double defaultValue, bool failIfNotFound=false) const
double x() const
Common members of all points & poses classes.
A class used to store a 3D pose as a translation (x,y,z) and a quaternion (qr,qx,qy,qz).
Derived inverse_LLt() const
Returns the inverse of a symmetric matrix using LLt.
GLsizei const GLchar ** string
size_type rows() const
Number of rows in the matrix.
size_type cols() const
Number of columns in the matrix.
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
A structure for holding correspondences between two sets of points or points-like entities in 2D or 3...
mrpt::math::CMatrixDouble66 cov
The 6x6 covariance matrix.
void setMaxTimeInterpolation(const mrpt::Clock::duration &time)
Set value of the maximum time to consider interpolation.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
T x() const
Return x coordinate of the quaternion.
void clear()
Clears the current sequence of poses.
void path_from_rtk_gps(mrpt::poses::CPose3DInterpolator &robot_path, const mrpt::obs::CRawlog &rawlog, size_t rawlog_first, size_t rawlog_last, bool isGUI=false, bool disableGPSInterp=false, int path_smooth_filter_size=2, TPathFromRTKInfo *outInfo=nullptr)
Reconstruct the path of a vehicle equipped with 3 RTK GPSs.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
double sqrDistanceTo(const TPoint3D &p) const
Point-to-point distance, squared.
std::set< T > make_set(const T &v0, const T &v1)
std::map< mrpt::Clock::time_point, mrpt::math::TPoint3D > best_gps_path
the path of the "best" GPS.
mrpt::math::CMatrixDouble W_star
The reference covariance matrix used to compute vehicle_uncertainty.
void setSize(size_t row, size_t col, bool zeroNewElements=false)
Changes the size of matrix, maintaining the previous contents.
VECTORLIKE1::Scalar mahalanobisDistance(const VECTORLIKE1 &X, const VECTORLIKE2 &MU, const MAT &COV)
Computes the mahalanobis distance of a vector X given the mean MU and the covariance inverse COV_inv ...
TGEODETICCOORDS getAsStruct() const
Return the geodetic coords as a mrpt::topography::TGeodeticCoords structure (requires linking against...
void setFromValues(const double x0, const double y0, const double z0, const double yaw=0, const double pitch=0, const double roll=0)
Set the pose from a 3D position (meters) and yaw/pitch/roll angles (radians) - This method recomputes...
Lightweight 3D pose (three spatial coordinates, plus three angular coordinates).
content_t fields
Message content, accesible by individual fields.
Declares a class that represents a Probability Density function (PDF) of a 3D pose ...
bool se3_l2(const mrpt::tfest::TMatchingPairList &in_correspondences, mrpt::poses::CPose3DQuat &out_transform, double &out_scale, bool forceScaleToUnity=false)
Least-squares (L2 norm) solution to finding the optimal SE(3) transform between two reference frames ...
This class stores a time-stamped trajectory in SE(3) (CPose3D poses).
std::map< mrpt::Clock::time_point, double > mahalabis_quality_measure
A measure of the quality at each point (may be empty if not there is no enough information).
TEntryType getType(size_t index) const
Returns the type of a given element.
void insert(const mrpt::Clock::time_point &t, const pose_t &p)
Inserts a new pose in the sequence.
void changeCoordinatesReference(const CPose3D &newReferenceBase) override
this = p (+) this.
double timeDifference(const mrpt::system::TTimeStamp t_first, const mrpt::system::TTimeStamp t_later)
Returns the time difference from t1 to t2 (positive if t2 is posterior to t1), in seconds...
void resize(std::size_t N, bool zeroNewElements=false)
This namespace provides topography helper functions, coordinate transformations.
This class stores messages from GNSS or GNSS+IMU devices, from consumer-grade inexpensive GPS receive...
T z() const
Return z coordinate of the quaternion.
size_t size() const
Returns the number of actions / observations object in the sequence.
Functions for estimating the optimal transformation between two frames of references given measuremen...
void getCommentTextAsConfigFile(mrpt::config::CConfigFileMemory &memCfg) const
Saves the block of comment text for the rawlog into the passed config file object.
#define MRPT_UNUSED_PARAM(a)
Determines whether this is an X86 or AMD64 platform.