21 #if MRPT_HAS_WXWIDGETS 23 #include <wx/msgdlg.h> 24 #include <wx/string.h> 25 #include <wx/progdlg.h> 26 #include <wx/busyinfo.h> 28 #endif // MRPT_HAS_WXWIDGETS 59 #if MRPT_HAS_WXWIDGETS 61 std::unique_ptr<wxBusyCursor> waitCursorPtr;
63 waitCursorPtr = std::unique_ptr<wxBusyCursor>(
new wxBusyCursor());
72 set<string> lstGPSLabels;
82 if (outInfo) *outInfo = outInfoTemp;
84 map<string, map<Clock::time_point, TPoint3D>>
88 bool ref_valid =
false;
99 ref_valid = !
ref.isClear();
102 const double std_0 = memFil.
read_double(
"CONSISTENCY_TEST",
"std_0", 0);
103 bool doConsistencyCheck = std_0 > 0;
107 const bool doUncertaintyCovs = outInfoTemp.
W_star.rows() != 0;
108 if (doUncertaintyCovs &&
109 (outInfoTemp.
W_star.rows() != 6 || outInfoTemp.
W_star.cols() != 6))
111 "ERROR: W_star matrix for uncertainty estimation is provided but " 112 "it's not a 6x6 matrix.");
117 #if MRPT_HAS_WXWIDGETS 118 wxProgressDialog* progDia =
nullptr;
121 progDia =
new wxProgressDialog(
122 wxT(
"Building map"), wxT(
"Getting GPS observations..."),
123 (
int)(last -
first + 1),
125 wxPD_CAN_ABORT | wxPD_APP_MODAL | wxPD_SMOOTH | wxPD_AUTO_HIDE |
126 wxPD_ELAPSED_TIME | wxPD_ESTIMATED_TIME | wxPD_REMAINING_TIME);
131 using TListGPSs = std::map<
133 TListGPSs list_gps_obs;
135 map<string, size_t> GPS_RTK_reads;
136 map<string, TPoint3D>
137 GPS_local_coords_on_vehicle;
139 for (
size_t i =
first; !abort && i <= last; i++)
146 case CRawlog::etObservation:
155 if (obs->has_GGA_datum &&
160 list_gps_obs[obs->timestamp][obs->sensorLabel] = obs;
162 lstGPSLabels.insert(obs->sensorLabel);
166 if (obs->has_GGA_datum &&
172 GPS_RTK_reads[obs->sensorLabel]++;
176 if (GPS_local_coords_on_vehicle.find(
178 GPS_local_coords_on_vehicle.end())
179 GPS_local_coords_on_vehicle[obs->sensorLabel] =
180 TPoint3D(obs->sensorPose.asTPose());
186 gps_paths[obs->sensorLabel][obs->timestamp] =
TPoint3D(
200 if ((
count++ % 100) == 0)
202 #if MRPT_HAS_WXWIDGETS 205 if (!progDia->Update((
int)(i -
first))) abort =
true;
212 #if MRPT_HAS_WXWIDGETS 226 map<set<string>,
double> Ad_ij;
227 map<set<string>,
double>
231 map<size_t, string> D_cov_rev_indexes;
237 if (doConsistencyCheck && GPS_local_coords_on_vehicle.size() == 3)
239 unsigned int cnt = 0;
241 GPS_local_coords_on_vehicle.begin();
242 i != GPS_local_coords_on_vehicle.end(); ++i)
245 D_cov_indexes[i->first] = cnt;
246 D_cov_rev_indexes[cnt] = i->first;
250 j != GPS_local_coords_on_vehicle.end(); ++j)
257 phi_ij[
make_set(i->first, j->first)] =
258 atan2(pj.
y - pi.
y, pj.
x - pi.
x);
262 ASSERT_(D_cov_indexes.size() == 3 && D_cov_rev_indexes.size() == 3);
264 D_cov.setSize(D_cov_indexes.size(), D_cov_indexes.size());
265 D_mean.resize(D_cov_indexes.size());
272 square(Ad_ij[
make_set(D_cov_rev_indexes[0], D_cov_rev_indexes[1])]);
275 square(Ad_ij[
make_set(D_cov_rev_indexes[0], D_cov_rev_indexes[2])]);
278 square(Ad_ij[
make_set(D_cov_rev_indexes[1], D_cov_rev_indexes[2])]);
281 Ad_ij[
make_set(D_cov_rev_indexes[0], D_cov_rev_indexes[1])] *
282 Ad_ij[
make_set(D_cov_rev_indexes[0], D_cov_rev_indexes[2])] *
283 cos(phi_ij[
make_set(D_cov_rev_indexes[0], D_cov_rev_indexes[1])] -
284 phi_ij[
make_set(D_cov_rev_indexes[0], D_cov_rev_indexes[2])]);
285 D_cov(0, 1) = D_cov(1, 0);
288 -Ad_ij[
make_set(D_cov_rev_indexes[0], D_cov_rev_indexes[1])] *
289 Ad_ij[
make_set(D_cov_rev_indexes[1], D_cov_rev_indexes[2])] *
290 cos(phi_ij[
make_set(D_cov_rev_indexes[0], D_cov_rev_indexes[1])] -
291 phi_ij[
make_set(D_cov_rev_indexes[1], D_cov_rev_indexes[2])]);
292 D_cov(0, 2) = D_cov(2, 0);
295 Ad_ij[
make_set(D_cov_rev_indexes[0], D_cov_rev_indexes[2])] *
296 Ad_ij[
make_set(D_cov_rev_indexes[1], D_cov_rev_indexes[2])] *
297 cos(phi_ij[
make_set(D_cov_rev_indexes[0], D_cov_rev_indexes[2])] -
298 phi_ij[
make_set(D_cov_rev_indexes[1], D_cov_rev_indexes[2])]);
299 D_cov(1, 2) = D_cov(2, 1);
301 D_cov *= 4 *
square(std_0);
303 D_cov_1 = D_cov.inv();
308 square(Ad_ij[
make_set(D_cov_rev_indexes[0], D_cov_rev_indexes[1])]);
310 square(Ad_ij[
make_set(D_cov_rev_indexes[0], D_cov_rev_indexes[2])]);
312 square(Ad_ij[
make_set(D_cov_rev_indexes[1], D_cov_rev_indexes[2])]);
315 doConsistencyCheck =
false;
320 int N_GPSs = list_gps_obs.size();
326 if (list_gps_obs.size() > 4)
339 std::map<std::string, CObservationGPS::Ptr>& GPS = it->second;
343 l != lstGPSLabels.end(); ++l)
346 bool fnd = (GPS.find(*l) != GPS.end());
359 if (i_b1->second.find(*l) != i_b1->second.end())
360 GPS_b1 = i_b1->second.find(*l)->second;
362 if (i_a1->second.find(*l) != i_a1->second.end())
363 GPS_a1 = i_a1->second.find(*l)->second;
365 if (!disableGPSInterp && GPS_a1 && GPS_b1)
368 GPS_b1->timestamp, GPS_a1->timestamp) < 0.5)
372 new_gps->sensorLabel = *l;
382 .fields.longitude_degrees =
387 .fields.longitude_degrees);
389 .fields.latitude_degrees =
394 .fields.latitude_degrees);
396 .fields.altitude_meters =
401 .fields.altitude_meters);
405 (GPS_a1->timestamp.time_since_epoch()
407 GPS_b1->timestamp.time_since_epoch()
411 it->second[new_gps->sensorLabel] = new_gps;
418 #if MRPT_HAS_WXWIDGETS 419 wxProgressDialog* progDia3 =
nullptr;
422 progDia3 =
new wxProgressDialog(
423 wxT(
"Building map"), wxT(
"Estimating 6D path..."),
426 wxPD_CAN_ABORT | wxPD_APP_MODAL | wxPD_SMOOTH | wxPD_AUTO_HIDE |
427 wxPD_ELAPSED_TIME | wxPD_ESTIMATED_TIME |
428 wxPD_REMAINING_TIME);
435 i != list_gps_obs.end(); ++i, idx_in_GPSs++)
438 if (i->second.size() >= 3)
440 const size_t N = i->second.size();
441 std::map<std::string, CObservationGPS::Ptr>& GPS = i->second;
443 std::map<string, size_t>
452 .getAsStruct<TGeodeticCoords>();
460 for (k = 0, g_it = GPS.begin(); g_it != GPS.end(); ++g_it, ++k)
470 string(
"OFFSET_") + g_it->second->sensorLabel;
475 XYZidxs[g_it->second->sensorLabel] =
482 g_it->second->sensorPose.x(),
483 g_it->second->sensorPose.y(),
484 g_it->second->sensorPose
493 if (doConsistencyCheck && GPS.size() == 3)
504 X[XYZidxs[D_cov_rev_indexes[0]]],
505 Y[XYZidxs[D_cov_rev_indexes[0]]],
506 Z[XYZidxs[D_cov_rev_indexes[0]]]);
508 X[XYZidxs[D_cov_rev_indexes[1]]],
509 Y[XYZidxs[D_cov_rev_indexes[1]]],
510 Z[XYZidxs[D_cov_rev_indexes[1]]]);
512 X[XYZidxs[D_cov_rev_indexes[2]]],
513 Y[XYZidxs[D_cov_rev_indexes[2]]],
514 Z[XYZidxs[D_cov_rev_indexes[2]]]);
521 iGPSdist2, D_mean, D_cov_1);
531 double optimal_scale;
536 corrs, optimal_pose, optimal_scale,
true);
551 robot_path.
insert(i->first, veh_pose);
554 if (doUncertaintyCovs)
558 final_veh_uncert.
cov = outInfoTemp.
W_star;
564 final_veh_uncert.
cov;
569 if ((
count++ % 100) == 0)
571 #if MRPT_HAS_WXWIDGETS 574 if (!progDia3->Update(idx_in_GPSs)) abort =
true;
581 #if MRPT_HAS_WXWIDGETS 589 if (PATH_SMOOTH_FILTER > 0 && robot_path.
size() > 1)
595 const double MAX_DIST_TO_FILTER = 4.0;
597 for (
auto i = robot_path.
begin(); i != robot_path.
end(); ++i)
603 pitchs.push_back(
p.pitch);
604 rolls.push_back(
p.roll);
608 k < PATH_SMOOTH_FILTER &&
q != robot_path.
begin(); k++)
614 pitchs.push_back(
q->second.pitch);
615 rolls.push_back(
q->second.roll);
620 k < PATH_SMOOTH_FILTER &&
q != (--robot_path.
end()); k++)
626 pitchs.push_back(
q->second.pitch);
627 rolls.push_back(
q->second.roll);
635 filtered_robot_path.
insert(i->first,
p);
638 robot_path = filtered_robot_path;
651 i != GPS_RTK_reads.end(); ++i)
653 if (i->second > bestNum)
656 bestLabel = i->first;
663 const string sect =
string(
"OFFSET_") + bestLabel;
664 const double off_X = memFil.
read_double(sect,
"x", 0);
665 const double off_Y = memFil.
read_double(sect,
"y", 0);
666 const double off_Z = memFil.
read_double(sect,
"z", 0);
689 if (outInfo) *outInfo = outInfoTemp;
mrpt::math::CQuaternionDouble & quat()
Read/Write access to the quaternion representing the 3D rotation.
std::chrono::duration< rep, period > duration
double x() const
Common members of all points & poses classes.
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.
mrpt::aligned_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 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...
Column vector, like Eigen::MatrixX*, but automatically initialized to zeros since construction...
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.
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...
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 x
X,Y,Z coordinates.
double read_double(const std::string §ion, const std::string &name, double defaultValue, bool failIfNotFound=false) const
A class used to store a 3D pose as a translation (x,y,z) and a quaternion (qr,qx,qy,qz).
GLsizei const GLchar ** string
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.
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...
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.