Skip to content

Commit

Permalink
make linters happy
Browse files Browse the repository at this point in the history
Signed-off-by: Alejandro Hernández Cordero <[email protected]>
  • Loading branch information
ahcorde committed May 15, 2024
1 parent 434bdfa commit 6d71757
Show file tree
Hide file tree
Showing 2 changed files with 41 additions and 41 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -167,54 +167,54 @@ void copyChannelData(
* Points for which FILTER is true are part of the final pointcloud.
*/
#define CREATE_FILTERED_CLOUD(IN, OUT, KEEP_ORGANIZED, FILTER) { \
const auto inputIsOrganized = (IN).height > 1; \
const auto outIsOrganized = (KEEP_ORGANIZED) && inputIsOrganized; \
const auto inputIsOrganized = (IN).height > 1; \
const auto outIsOrganized = (KEEP_ORGANIZED) && inputIsOrganized; \
\
(OUT).header = (IN).header; \
(OUT).fields = (IN).fields; \
(OUT).point_step = (IN).point_step; \
(OUT).height = outIsOrganized ? (IN).height : 1; \
(OUT).width = outIsOrganized ? (IN).width : 0; \
(OUT).header = (IN).header; \
(OUT).fields = (IN).fields; \
(OUT).point_step = (IN).point_step; \
(OUT).height = outIsOrganized ? (IN).height : 1; \
(OUT).width = outIsOrganized ? (IN).width : 0; \
\
(OUT).data.resize(0); \
(OUT).data.reserve((IN).data.size()); \
(OUT).data.resize(0); \
(OUT).data.reserve((IN).data.size()); \
\
::cras::CloudConstIter x_it((IN), "x"); \
::cras::CloudConstIter y_it((IN), "y"); \
::cras::CloudConstIter z_it((IN), "z"); \
::cras::CloudConstIter x_it((IN), "x"); \
::cras::CloudConstIter y_it((IN), "y"); \
::cras::CloudConstIter z_it((IN), "z"); \
\
const auto numPoints = ::cras::numPoints(IN); \
const auto numPoints = ::cras::numPoints(IN); \
\
if (!outIsOrganized) { \
for (size_t i = 0; i < numPoints; ++i, ++x_it, ++y_it, ++z_it) { \
if (FILTER) { \
size_t from = (i / (IN).width) * (IN).row_step + (i % (IN).width) * (IN).point_step; \
size_t to = from + (IN).point_step; \
(OUT).data.insert( \
(OUT).data.end(), (IN).data.begin() + from, \
(IN).data.begin() + to); \
(OUT).width++; \
} \
} \
(OUT).is_dense = true; \
} else { \
(OUT).data.insert((OUT).data.end(), (IN).data.begin(), (IN).data.end()); \
if (!outIsOrganized) { \
for (size_t i = 0; i < numPoints; ++i, ++x_it, ++y_it, ++z_it) { \
if (FILTER) { \
size_t from = (i / (IN).width) * (IN).row_step + (i % (IN).width) * (IN).point_step; \
size_t to = from + (IN).point_step; \
(OUT).data.insert( \
(OUT).data.end(), (IN).data.begin() + from, \
(IN).data.begin() + to); \
(OUT).width++; \
} \
} \
(OUT).is_dense = true; \
} else { \
(OUT).data.insert((OUT).data.end(), (IN).data.begin(), (IN).data.end()); \
\
::cras::CloudIter x_out_it((OUT), "x"); \
::cras::CloudIter y_out_it((OUT), "y"); \
::cras::CloudIter z_out_it((OUT), "z"); \
const auto invalidValue = std::numeric_limits<float>::quiet_NaN(); \
::cras::CloudIter x_out_it((OUT), "x"); \
::cras::CloudIter y_out_it((OUT), "y"); \
::cras::CloudIter z_out_it((OUT), "z"); \
const auto invalidValue = std::numeric_limits<float>::quiet_NaN(); \
\
for (size_t i = 0; i < numPoints; \
++i, ++x_it, ++y_it, ++z_it, ++x_out_it, ++y_out_it, ++z_out_it) { \
if (!(FILTER)) { \
*x_out_it = *y_out_it = *z_out_it = invalidValue; \
(OUT).is_dense = false; \
} \
} \
for (size_t i = 0; i < numPoints; \
++i, ++x_it, ++y_it, ++z_it, ++x_out_it, ++y_out_it, ++z_out_it) { \
if (!(FILTER)) { \
*x_out_it = *y_out_it = *z_out_it = invalidValue; \
(OUT).is_dense = false; \
} \
} \
} \
\
(OUT).row_step = (OUT).width * (OUT).point_step; \
(OUT).row_step = (OUT).width * (OUT).point_step; \
}
} // namespace cras

Expand Down
4 changes: 2 additions & 2 deletions draco_point_cloud_transport/src/cloud.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -149,9 +149,9 @@ void GenericCloudIterator<T>::copyData(const GenericCloudIterator<T> & otherIter

// explicitly instantiate
template class GenericCloudIteratorBase<unsigned char, unsigned char, unsigned char,
sensor_msgs::msg::PointCloud2, GenericCloudIterator>;
sensor_msgs::msg::PointCloud2, GenericCloudIterator>;
template class GenericCloudIteratorBase<unsigned char, const unsigned char, const unsigned char,
const sensor_msgs::msg::PointCloud2, GenericCloudConstIterator>;
const sensor_msgs::msg::PointCloud2, GenericCloudConstIterator>;

template class GenericCloudIterator<>;
template class GenericCloudConstIterator<>;
Expand Down

0 comments on commit 6d71757

Please sign in to comment.