Skip to content

Commit 4c9da0f

Browse files
committed
more rawlog info
1 parent 20a43c6 commit 4c9da0f

File tree

4 files changed

+36
-2
lines changed

4 files changed

+36
-2
lines changed

doc/source/doxygen-docs/changelog.md

+2
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,8 @@
22

33
# Version 2.11.8: UNRELEASED
44
- Changes in apps:
5+
- RawLogViewer: Show pointcloud ring, intensity, and time min/max ranges.
6+
- rawlog-edit: Show dataset duration as formatted time interval.
57
- rosbag2rawlog (ROS 1):
68
- Added support for XYZIRT point clouds.
79
- Finally, implemented automatic detection of sensor poses wrt `base_link` from `tf` messages, with an option to manually override sensor poses from YAML config.

libs/apps/src/rawlog-edit_info.cpp

+5
Original file line numberDiff line numberDiff line change
@@ -149,6 +149,11 @@ DECLARE_OP_FUNCTION(op_info)
149149
mrpt::Clock::fromDouble(proc.lastTimestamp))
150150
<< " UTC)\n";
151151

152+
cout << "Duration : "
153+
<< mrpt::system::intervalFormat(
154+
proc.lastTimestamp - proc.firstTimestamp)
155+
<< "\n";
156+
152157
// By sensor labels:
153158
cout << "All sensor labels : ";
154159
for (auto it = proc.infoPerSensorLabel.begin();

libs/maps/src/obs/CObservationPointCloud.cpp

+26
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
#include <mrpt/maps/CColouredPointsMap.h>
1818
#include <mrpt/maps/CPointsMapXYZI.h>
1919
#include <mrpt/maps/CSimplePointsMap.h>
20+
#include <mrpt/math/ops_containers.h> // minimum_maximum()
2021
#include <mrpt/obs/CObservation3DRangeScan.h>
2122
#include <mrpt/obs/CObservationPointCloud.h>
2223
#include <mrpt/serialization/CArchive.h>
@@ -58,6 +59,31 @@ void CObservationPointCloud::getDescriptionAsText(std::ostream& o) const
5859
{
5960
o << pointcloud->GetRuntimeClass()->className << "\n";
6061
o << "Number of points: " << pointcloud->size() << "\n";
62+
63+
// Special cases: show IRT stats:
64+
if (auto* ptrIs = pointcloud->getPointsBufferRef_intensity();
65+
ptrIs && !ptrIs->empty())
66+
{
67+
float Imin, Imax;
68+
mrpt::math::minimum_maximum(*ptrIs, Imin, Imax);
69+
o << "Intensity channel values: min=" << Imin << " max=" << Imax
70+
<< "\n";
71+
}
72+
if (auto* ptrTs = pointcloud->getPointsBufferRef_timestamp();
73+
ptrTs && !ptrTs->empty())
74+
{
75+
float Tmin, Tmax;
76+
mrpt::math::minimum_maximum(*ptrTs, Tmin, Tmax);
77+
o << "Timestamp channel values: min=" << Tmin << " max=" << Tmax
78+
<< "\n";
79+
}
80+
if (auto* ptrRs = pointcloud->getPointsBufferRef_ring();
81+
ptrRs && !ptrRs->empty())
82+
{
83+
uint16_t Rmin, Rmax;
84+
mrpt::math::minimum_maximum(*ptrRs, Rmin, Rmax);
85+
o << "Ring channel values: min=" << Rmin << " max=" << Rmax << "\n";
86+
}
6187
}
6288

6389
if (m_externally_stored != ExternalStorageFormat::None)

libs/math/include/mrpt/math/ops_containers.h

+3-2
Original file line numberDiff line numberDiff line change
@@ -255,8 +255,9 @@ inline double mean(const CONTAINER& v)
255255
}
256256

257257
/** Return the maximum and minimum values of a std::vector */
258-
template <typename T>
259-
inline void minimum_maximum(const std::vector<T>& V, T& curMin, T& curMax)
258+
template <typename T, typename Alloc>
259+
inline void minimum_maximum(
260+
const std::vector<T, Alloc>& V, T& curMin, T& curMax)
260261
{
261262
ASSERT_(V.size() != 0);
262263
const size_t N = V.size();

0 commit comments

Comments
 (0)