19 #if MRPT_HAS_WXWIDGETS 21 #include <wx/msgdlg.h> 22 #include <wx/string.h> 23 #include <wx/progdlg.h> 24 #include <wx/busyinfo.h> 26 #endif // MRPT_HAS_WXWIDGETS 56 bool disableGPSInterp,
57 int PATH_SMOOTH_FILTER ,
63 #if MRPT_HAS_WXWIDGETS 65 std::shared_ptr<wxBusyCursor> waitCursorPtr;
67 waitCursorPtr = std::shared_ptr<wxBusyCursor>(
new wxBusyCursor() );
79 set<string> lstGPSLabels;
88 if (outInfo) *outInfo = outInfoTemp;
90 map<string, map<TTimeStamp,TPoint3D> > gps_paths;
93 bool ref_valid =
false;
104 ref_valid = !
ref.isClear();
107 const double std_0 = memFil.
read_double(
"CONSISTENCY_TEST",
"std_0",0);
108 bool doConsistencyCheck = std_0>0;
112 const bool doUncertaintyCovs =
size(outInfoTemp.
W_star,1)!=0;
114 THROW_EXCEPTION(
"ERROR: W_star matrix for uncertainty estimation is provided but it's not a 6x6 matrix.");
119 #if MRPT_HAS_WXWIDGETS 120 wxProgressDialog *progDia=NULL;
123 progDia =
new wxProgressDialog(
125 wxT(
"Getting GPS observations..."),
133 wxPD_ESTIMATED_TIME |
134 wxPD_REMAINING_TIME);
139 typedef std::map< mrpt::system::TTimeStamp, std::map<std::string,CObservationGPSPtr> > TListGPSs;
140 TListGPSs list_gps_obs;
142 map<string,size_t> GPS_RTK_reads;
143 map<string,TPoint3D> GPS_local_coords_on_vehicle;
145 for (i=
first;!abort && i<=last;i++)
152 case CRawlog::etObservation:
158 CObservationGPSPtr obs = CObservationGPSPtr(o);
163 list_gps_obs[obs->timestamp][obs->sensorLabel] = obs;
165 lstGPSLabels.insert(obs->sensorLabel);
171 GPS_RTK_reads[obs->sensorLabel]++;
174 if (GPS_local_coords_on_vehicle.find(obs->sensorLabel)==GPS_local_coords_on_vehicle.end())
175 GPS_local_coords_on_vehicle[obs->sensorLabel] =
TPoint3D( obs->sensorPose );
178 gps_paths[obs->sensorLabel][obs->timestamp] =
TPoint3D(
189 if ((
count++ % 100)==0)
191 #if MRPT_HAS_WXWIDGETS 194 if (!progDia->Update((
int)(i-
first)))
202 #if MRPT_HAS_WXWIDGETS 216 map< set<string>,
double > Ad_ij;
217 map< set<string>,
double > phi_ij;
218 map< string, size_t> D_cov_indexes;
219 map< size_t, string> D_cov_rev_indexes;
225 if (doConsistencyCheck && GPS_local_coords_on_vehicle.size()==3)
227 unsigned int cnt = 0;
231 D_cov_indexes[i->first] = cnt;
232 D_cov_rev_indexes[cnt] = i->first;
242 phi_ij[
make_set(i->first,j->first) ] = atan2( pj.
y-pi.
y, pj.
x-pi.
x );
246 ASSERT_( D_cov_indexes.size()==3 && D_cov_rev_indexes.size()==3 );
248 D_cov.setSize( D_cov_indexes.size(), D_cov_indexes.size() );
249 D_mean.resize( D_cov_indexes.size() );
254 D_cov(0,0) = 2*
square( Ad_ij[
make_set(D_cov_rev_indexes[0],D_cov_rev_indexes[1])] );
255 D_cov(1,1) = 2*
square( Ad_ij[
make_set(D_cov_rev_indexes[0],D_cov_rev_indexes[2])] );
256 D_cov(2,2) = 2*
square( Ad_ij[
make_set(D_cov_rev_indexes[1],D_cov_rev_indexes[2])] );
258 D_cov(1,0) = Ad_ij[
make_set(D_cov_rev_indexes[0],D_cov_rev_indexes[1])] * Ad_ij[
make_set(D_cov_rev_indexes[0],D_cov_rev_indexes[2])]
259 * cos( phi_ij[
make_set(D_cov_rev_indexes[0],D_cov_rev_indexes[1])] - phi_ij[
make_set(D_cov_rev_indexes[0],D_cov_rev_indexes[2])] );
260 D_cov(0,1) = D_cov(1,0);
262 D_cov(2,0) =-Ad_ij[
make_set(D_cov_rev_indexes[0],D_cov_rev_indexes[1])] * Ad_ij[
make_set(D_cov_rev_indexes[1],D_cov_rev_indexes[2])]
263 * cos( phi_ij[
make_set(D_cov_rev_indexes[0],D_cov_rev_indexes[1])] - phi_ij[
make_set(D_cov_rev_indexes[1],D_cov_rev_indexes[2])] );
264 D_cov(0,2) = D_cov(2,0);
266 D_cov(2,1) = Ad_ij[
make_set(D_cov_rev_indexes[0],D_cov_rev_indexes[2])] * Ad_ij[
make_set(D_cov_rev_indexes[1],D_cov_rev_indexes[2])]
267 * cos( phi_ij[
make_set(D_cov_rev_indexes[0],D_cov_rev_indexes[2])] - phi_ij[
make_set(D_cov_rev_indexes[1],D_cov_rev_indexes[2])] );
268 D_cov(1,2) = D_cov(2,1);
272 D_cov_1 = D_cov.inv();
276 D_mean[0] =
square( Ad_ij[
make_set(D_cov_rev_indexes[0],D_cov_rev_indexes[1])] );
277 D_mean[1] =
square( Ad_ij[
make_set(D_cov_rev_indexes[0],D_cov_rev_indexes[2])] );
278 D_mean[2] =
square( Ad_ij[
make_set(D_cov_rev_indexes[1],D_cov_rev_indexes[2])] );
281 else doConsistencyCheck =
false;
287 int N_GPSs = list_gps_obs.size();
293 if (list_gps_obs.size()>4)
304 std::map<std::string, CObservationGPSPtr> & GPS = i->second;
310 bool fnd = ( GPS.find(*l)!=GPS.end() );
319 CObservationGPSPtr GPS_b1, GPS_a1;
321 if (i_b1->second.find( *l )!=i_b1->second.end())
322 GPS_b1 = i_b1->second.find( *l )->second;
324 if (i_a1->second.find( *l )!=i_a1->second.end())
325 GPS_a1 = i_a1->second.find( *l )->second;
327 if (!disableGPSInterp && GPS_a1 && GPS_b1)
331 CObservationGPSPtr new_gps = CObservationGPSPtr(
new CObservationGPS(*GPS_a1) );
332 new_gps->sensorLabel = *l;
341 new_gps->timestamp = (GPS_a1->timestamp + GPS_b1->timestamp) / 2;
343 i->second[new_gps->sensorLabel] = new_gps;
352 #if MRPT_HAS_WXWIDGETS 353 wxProgressDialog *progDia3=NULL;
356 progDia3 =
new wxProgressDialog(
358 wxT(
"Estimating 6D path..."),
366 wxPD_ESTIMATED_TIME |
367 wxPD_REMAINING_TIME);
376 if (i->second.size()>=3)
378 const size_t N = i->second.size();
379 std::map<std::string, CObservationGPSPtr> & GPS = i->second;
381 std::map<string,size_t> XYZidxs;
394 for (k=0,g_it=GPS.begin();g_it!=GPS.end();++g_it,++k)
403 const string sect =
string(
"OFFSET_")+g_it->second->sensorLabel;
408 XYZidxs[g_it->second->sensorLabel] = k;
414 g_it->second->sensorPose.x(),g_it->second->sensorPose.y(),g_it->second->sensorPose.z()
422 if (doConsistencyCheck && GPS.size()==3)
431 TPoint3D P0( X[XYZidxs[D_cov_rev_indexes[0]]], Y[XYZidxs[D_cov_rev_indexes[0]]], Z[XYZidxs[D_cov_rev_indexes[0]]] );
432 TPoint3D P1( X[XYZidxs[D_cov_rev_indexes[1]]], Y[XYZidxs[D_cov_rev_indexes[1]]], Z[XYZidxs[D_cov_rev_indexes[1]]] );
433 TPoint3D P2( X[XYZidxs[D_cov_rev_indexes[2]]], Y[XYZidxs[D_cov_rev_indexes[2]]], Z[XYZidxs[D_cov_rev_indexes[2]]] );
447 double optimal_scale;
465 robot_path.
insert( i->first, veh_pose );
468 if (doUncertaintyCovs)
472 final_veh_uncert.
cov = outInfoTemp.
W_star;
482 if ((
count++ % 100)==0)
484 #if MRPT_HAS_WXWIDGETS 487 if (!progDia3->Update(idx_in_GPSs))
495 #if MRPT_HAS_WXWIDGETS 503 if (PATH_SMOOTH_FILTER>0 && robot_path.
size()>1)
509 const double MAX_DIST_TO_FILTER = 4.0;
511 for (
auto i=robot_path.
begin();i!=robot_path.
end();++i)
517 pitchs.push_back(
p.pitch);
518 rolls.push_back(
p.roll);
521 for (
int k=0;k<PATH_SMOOTH_FILTER &&
q!=robot_path.
begin();k++)
526 pitchs.push_back(
q->second.pitch );
527 rolls.push_back(
q->second.roll );
531 for (
int k=0;k<PATH_SMOOTH_FILTER &&
q!=(--robot_path.
end()) ;k++)
536 pitchs.push_back(
q->second.pitch );
537 rolls.push_back(
q->second.roll );
545 filtered_robot_path.
insert( i->first,
p );
548 robot_path = filtered_robot_path;
562 if (i->second>bestNum)
565 bestLabel = i->first;
572 const string sect =
string(
"OFFSET_")+bestLabel;
573 const double off_X = memFil.
read_double( sect,
"x", 0 );
574 const double off_Y = memFil.
read_double( sect,
"y", 0 );
575 const double off_Z = memFil.
read_double( sect,
"z", 0 );
593 if (outInfo) *outInfo = outInfoTemp;
CObservationPtr getAsObservation(size_t index) const
Returns the i'th element in the sequence, as being an observation, where index=0 is the first object...
mrpt::math::CQuaternionDouble & quat()
Read/Write access to the quaternion representing the 3D rotation.
double x() const
Common members of all points & poses classes.
GLuint GLuint GLsizei count
double BASE_IMPEXP 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...
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
CPose3D mean
The mean value.
double latitude_degrees
The measured latitude, in degrees (North:+ , South:-)
This namespace provides a OS-independent interface to many useful functions: filenames manipulation...
T y() const
Return y coordinate of the quaternion.
#define MRPT_CHECK_NORMAL_NUMBER(val)
#define THROW_EXCEPTION(msg)
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...
double z
X,Y,Z coordinates.
void TOPO_IMPEXP 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. The default method at construction is "imSpline...
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.
This class implements a config file-like interface over a memory-stored string list.
double altitude_meters
The measured altitude, in meters (A).
mrpt::aligned_containers< mrpt::system::TTimeStamp, mrpt::math::CMatrixDouble66 >::map_t vehicle_uncertainty
The 6x6 covariance matrix for the uncertainty of each vehicle pose (may be empty if there is no W_sta...
This base provides a set of functions for maths stuff.
void insert(mrpt::system::TTimeStamp t, const pose_t &p)
Inserts a new pose in the sequence.
T r() const
Return r coordinate of the quaternion.
std::map< mrpt::system::TTimeStamp, double > mahalabis_quality_measure
A measure of the quality at each point (may be empty if not there is no enough information).
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 ; ...
#define MRPT_UNUSED_PARAM(a)
Can be used to avoid "not used parameters" warnings from the compiler.
double distanceTo(const TPoint3D &p) const
Point-to-point distance.
void changeCoordinatesReference(const CPose3D &newReferenceBase) MRPT_OVERRIDE
this = p (+) this.
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.
bool TFEST_IMPEXP se3_l2(const mrpt::utils::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 ...
A class used to store a 3D pose as a translation (x,y,z) and a quaternion (qr,qx,qy,qz).
void setMaxTimeInterpolation(double time)
Set value of the maximum time to consider interpolation.
GLsizei const GLchar ** string
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
mrpt::math::CMatrixDouble66 cov
The 6x6 covariance matrix.
#define CLASS_ID(class_name)
Access to runtime class ID for a defined class name.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
T x() const
Return x coordinate of the quaternion.
std::map< mrpt::system::TTimeStamp, mrpt::math::TPoint3D > best_gps_path
the path of the "best" GPS.
void clear()
Clears the current sequence of poses.
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)
double read_double(const std::string §ion, const std::string &name, double defaultValue, bool failIfNotFound=false) const
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 ...
This class stores a time-stamped trajectory in SE(3) (CPose3D poses).
TEntryType getType(size_t index) const
Returns the type of a given element.
double BASE_IMPEXP 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.
A structure for holding correspondences between two sets of points or points-like entities in 2D or 3...
void getCommentTextAsConfigFile(mrpt::utils::CConfigFileMemory &memCfg) const
Saves the block of comment text for the rawlog into the passed config file object.
void TOPO_IMPEXP 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=NULL)
Reconstruct the path of a vehicle equipped with 3 RTK GPSs.