Skip to content

Commit 0b96dc2

Browse files
committed
FIX: Avoid throw when viewing and describing as text a PCD with an empty field
1 parent 1d6f038 commit 0b96dc2

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
@@ -132,8 +132,8 @@ ViewOptions3DPoints::ViewOptions3DPoints(wxWindow* parent, wxWindowID id)
132132
FlexGridSizer3->Add(
133133
cbOnlyPointsWithColor, 1, wxALL | wxALIGN_CENTER_HORIZONTAL | wxALIGN_CENTER_VERTICAL, 5);
134134

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

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

modules/mrpt_maps/src/obs/CObservationPointCloud.cpp

Lines changed: 10 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -71,8 +71,11 @@ void CObservationPointCloud::getDescriptionAsText(std::ostream& o) const
7171
{
7272
continue;
7373
}
74-
float Imin, Imax;
75-
mrpt::math::minimum_maximum(*data, Imin, Imax);
74+
float Imin = 0, Imax = 0;
75+
if (!data->empty())
76+
{
77+
mrpt::math::minimum_maximum(*data, Imin, Imax);
78+
}
7679
o << mrpt::format(
7780
"Field: %-20.*s (float32): min=%7.02f max=%7.02f (%zu entries)\n",
7881
static_cast<int>(fieldName.size()), fieldName.data(), Imin, Imax, data->size());
@@ -84,8 +87,11 @@ void CObservationPointCloud::getDescriptionAsText(std::ostream& o) const
8487
{
8588
continue;
8689
}
87-
uint16_t Imin, Imax;
88-
mrpt::math::minimum_maximum(*data, Imin, Imax);
90+
uint16_t Imin = 0, Imax = 0;
91+
if (!data->empty())
92+
{
93+
mrpt::math::minimum_maximum(*data, Imin, Imax);
94+
}
8995
o << mrpt::format(
9096
"Field: %-20.*s (uint16): min=%7hu max=%7hu (%zu entries)\n",
9197
static_cast<int>(fieldName.size()), fieldName.data(), Imin, Imax, data->size());

modules/mrpt_maps/src/obs/customizable_obs_viz.cpp

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

106-
std::pair<float, float> dataLimits;
106+
std::pair<float, float> dataLimits{0, 0};
107107
std::size_t dataPoints = 0;
108108

109109
const mrpt::aligned_std_vector<float>* fieldData_f = nullptr;
@@ -112,16 +112,22 @@ void mrpt::obs::recolorize3Dpc(
112112
if (fieldData_f = originalPts->getPointsBufferRef_float_field(p.colorizeByField); fieldData_f)
113113
{
114114
dataPoints = fieldData_f->size();
115-
mrpt::math::minimum_maximum(*fieldData_f, dataLimits.first, dataLimits.second);
115+
if (dataPoints)
116+
{
117+
mrpt::math::minimum_maximum(*fieldData_f, dataLimits.first, dataLimits.second);
118+
}
116119
}
117120
else if (fieldData_u = originalPts->getPointsBufferRef_uint_field(p.colorizeByField); fieldData_u)
118121
{
119122
dataPoints = fieldData_u->size();
120123

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

127133
if (!fieldData_f && !fieldData_u)

0 commit comments

Comments
 (0)