diff --git a/libs/ros1bridge/src/point_cloud2.cpp b/libs/ros1bridge/src/point_cloud2.cpp index f44aed3d7c..927e99701a 100644 --- a/libs/ros1bridge/src/point_cloud2.cpp +++ b/libs/ros1bridge/src/point_cloud2.cpp @@ -261,7 +261,7 @@ bool mrpt::ros1bridge::toROS( const auto& xs = obj.getPointsBufferRef_x(); const auto& ys = obj.getPointsBufferRef_y(); const auto& zs = obj.getPointsBufferRef_z(); - const auto& Is = obj.getPointsBufferRef_intensity(); + const auto* Is = obj.getPointsBufferRef_intensity(); float* pointDest = reinterpret_cast(msg.data.data()); for (size_t i = 0; i < xs.size(); i++) @@ -269,7 +269,7 @@ bool mrpt::ros1bridge::toROS( *pointDest++ = xs[i]; *pointDest++ = ys[i]; *pointDest++ = zs[i]; - *pointDest++ = Is[i]; + *pointDest++ = (*Is)[i]; } return true;