Skip to content

Commit 458dd11

Browse files
committed
FIX: Avoid throw when viewing and describing as text a PCD with an empty field
1 parent df41de4 commit 458dd11

File tree

3 files changed

+24
-12
lines changed

3 files changed

+24
-12
lines changed

apps/RawLogViewer/ViewOptions3DPoints.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -127,8 +127,8 @@ ViewOptions3DPoints::ViewOptions3DPoints(wxWindow* parent, wxWindowID id)
127127
FlexGridSizer3->Add(
128128
cbOnlyPointsWithColor, 1, wxALL | wxALIGN_CENTER_HORIZONTAL | wxALIGN_CENTER_VERTICAL, 5);
129129

130-
const wxString colorOptions[] = {"x", "y", "z", "i", "intensity", "ambient",
131-
"r", "t", "time", "timestamp", "reflectivity"};
130+
const wxString colorOptions[] = {"x", "y", "z", "i", "intensity", "ambient",
131+
"ring", "t", "time", "timestamp", "reflectivity"};
132132

133133
cbColorByAxis = new wxComboBox(
134134
this, ID_RADIOBOX1, _("Otherwise, color from:"), wxDefaultPosition, wxDefaultSize,

libs/maps/src/obs/CObservationPointCloud.cpp

Lines changed: 10 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -66,8 +66,11 @@ void CObservationPointCloud::getDescriptionAsText(std::ostream& o) const
6666
{
6767
continue;
6868
}
69-
float Imin, Imax;
70-
mrpt::math::minimum_maximum(*data, Imin, Imax);
69+
float Imin = 0, Imax = 0;
70+
if (!data->empty())
71+
{
72+
mrpt::math::minimum_maximum(*data, Imin, Imax);
73+
}
7174
o << mrpt::format(
7275
"Field: %-20.*s (float32): min=%7.02f max=%7.02f (%zu entries)\n",
7376
static_cast<int>(fieldName.size()), fieldName.data(), Imin, Imax, data->size());
@@ -79,8 +82,11 @@ void CObservationPointCloud::getDescriptionAsText(std::ostream& o) const
7982
{
8083
continue;
8184
}
82-
uint16_t Imin, Imax;
83-
mrpt::math::minimum_maximum(*data, Imin, Imax);
85+
uint16_t Imin = 0, Imax = 0;
86+
if (!data->empty())
87+
{
88+
mrpt::math::minimum_maximum(*data, Imin, Imax);
89+
}
8490
o << mrpt::format(
8591
"Field: %-20.*s (uint16): min=%7hu max=%7hu (%zu entries)\n",
8692
static_cast<int>(fieldName.size()), fieldName.data(), Imin, Imax, data->size());

libs/maps/src/obs/customizable_obs_viz.cpp

Lines changed: 12 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -101,7 +101,7 @@ void mrpt::obs::recolorize3Dpc(
101101
return;
102102
}
103103

104-
std::pair<float, float> dataLimits;
104+
std::pair<float, float> dataLimits{0, 0};
105105
std::size_t dataPoints = 0;
106106

107107
const mrpt::aligned_std_vector<float>* fieldData_f = nullptr;
@@ -110,16 +110,22 @@ void mrpt::obs::recolorize3Dpc(
110110
if (fieldData_f = originalPts->getPointsBufferRef_float_field(p.colorizeByField); fieldData_f)
111111
{
112112
dataPoints = fieldData_f->size();
113-
mrpt::math::minimum_maximum(*fieldData_f, dataLimits.first, dataLimits.second);
113+
if (dataPoints)
114+
{
115+
mrpt::math::minimum_maximum(*fieldData_f, dataLimits.first, dataLimits.second);
116+
}
114117
}
115118
else if (fieldData_u = originalPts->getPointsBufferRef_uint_field(p.colorizeByField); fieldData_u)
116119
{
117120
dataPoints = fieldData_u->size();
118121

119-
uint16_t uMin, uMax;
120-
mrpt::math::minimum_maximum(*fieldData_u, uMin, uMax);
121-
dataLimits.first = static_cast<float>(uMin);
122-
dataLimits.second = static_cast<float>(uMax);
122+
if (dataPoints)
123+
{
124+
uint16_t uMin = 0, uMax = 0;
125+
mrpt::math::minimum_maximum(*fieldData_u, uMin, uMax);
126+
dataLimits.first = static_cast<float>(uMin);
127+
dataLimits.second = static_cast<float>(uMax);
128+
}
123129
}
124130

125131
if (!fieldData_f && !fieldData_u)

0 commit comments

Comments
 (0)