Skip to content

Commit c786c7b

Browse files
Fixed segmentation fault in depth_image_octomap_updater (#2963)
1 parent bb69934 commit c786c7b

File tree

7 files changed

+15
-15
lines changed

7 files changed

+15
-15
lines changed

moveit_ros/perception/depth_image_octomap_updater/src/depth_image_octomap_updater.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -438,7 +438,7 @@ void DepthImageOctomapUpdater::depthImageCallback(const sensor_msgs::msg::Image:
438438
debug_msg.encoding = sensor_msgs::image_encodings::TYPE_32FC1;
439439
debug_msg.step = w * sizeof(float);
440440
debug_msg.data.resize(img_size * sizeof(float));
441-
mesh_filter_->getModelDepth(reinterpret_cast<double*>(&debug_msg.data[0]));
441+
mesh_filter_->getModelDepth(reinterpret_cast<float*>(&debug_msg.data[0]));
442442
pub_model_depth_image_.publish(debug_msg, *info_msg);
443443

444444
sensor_msgs::msg::Image filtered_depth_msg;
@@ -449,7 +449,7 @@ void DepthImageOctomapUpdater::depthImageCallback(const sensor_msgs::msg::Image:
449449
filtered_depth_msg.encoding = sensor_msgs::image_encodings::TYPE_32FC1;
450450
filtered_depth_msg.step = w * sizeof(float);
451451
filtered_depth_msg.data.resize(img_size * sizeof(float));
452-
mesh_filter_->getFilteredDepth(reinterpret_cast<double*>(&filtered_depth_msg.data[0]));
452+
mesh_filter_->getFilteredDepth(reinterpret_cast<float*>(&filtered_depth_msg.data[0]));
453453
pub_filtered_depth_image_.publish(filtered_depth_msg, *info_msg);
454454

455455
sensor_msgs::msg::Image label_msg;
@@ -481,7 +481,7 @@ void DepthImageOctomapUpdater::depthImageCallback(const sensor_msgs::msg::Image:
481481
if (filtered_data.size() < img_size)
482482
filtered_data.resize(img_size);
483483

484-
mesh_filter_->getFilteredDepth(reinterpret_cast<double*>(&filtered_data[0]));
484+
mesh_filter_->getFilteredDepth(reinterpret_cast<float*>(&filtered_data[0]));
485485
unsigned short* msg_data = reinterpret_cast<unsigned short*>(&filtered_msg.data[0]);
486486
for (std::size_t i = 0; i < img_size; ++i)
487487
{

moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -106,7 +106,7 @@ class GLRenderer
106106
* \author Suat Gedikli ([email protected])
107107
* \param[out] buffer pointer to memory where the depth values need to be stored
108108
*/
109-
void getDepthBuffer(double* buffer) const;
109+
void getDepthBuffer(float* buffer) const;
110110

111111
/**
112112
* \brief loads, compiles, links and adds GLSL shaders from files to the current OpenGL context.

moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -131,7 +131,7 @@ class MeshFilterBase
131131
* \author Suat Gedikli ([email protected])
132132
* \param[out] depth pointer to buffer to be filled with depth values.
133133
*/
134-
void getFilteredDepth(double* depth) const;
134+
void getFilteredDepth(float* depth) const;
135135

136136
/**
137137
* \brief retrieves the labels of the rendered model
@@ -149,7 +149,7 @@ class MeshFilterBase
149149
* \author Suat Gedikli ([email protected])
150150
* \param[out] depth pointer to buffer to be filled with depth values.
151151
*/
152-
void getModelDepth(double* depth) const;
152+
void getModelDepth(float* depth) const;
153153

154154
/**
155155
* \brief set the shadow threshold. points that are further away than the rendered model are filtered out.

moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -103,13 +103,13 @@ class SensorModel
103103
* \brief transforms depth values from rendered model to metric depth values
104104
* \param[in,out] depth pointer to floating point depth buffer
105105
*/
106-
virtual void transformModelDepthToMetricDepth(double* depth) const;
106+
virtual void transformModelDepthToMetricDepth(float* depth) const;
107107

108108
/**
109109
* \brief transforms depth values from filtered depth to metric depth values
110110
* \param[in,out] depth pointer to floating point depth buffer
111111
*/
112-
virtual void transformFilteredDepthToMetricDepth(double* depth) const;
112+
virtual void transformFilteredDepthToMetricDepth(float* depth) const;
113113

114114
/**
115115
* \brief sets the image size

moveit_ros/perception/mesh_filter/src/gl_renderer.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -213,7 +213,7 @@ void mesh_filter::GLRenderer::getColorBuffer(unsigned char* buffer) const
213213
glBindFramebuffer(GL_FRAMEBUFFER, 0);
214214
}
215215

216-
void mesh_filter::GLRenderer::getDepthBuffer(double* buffer) const
216+
void mesh_filter::GLRenderer::getDepthBuffer(float* buffer) const
217217
{
218218
glBindFramebuffer(GL_FRAMEBUFFER, fbo_id_);
219219
glBindTexture(GL_TEXTURE_2D, depth_id_);

moveit_ros/perception/mesh_filter/src/mesh_filter_base.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -227,7 +227,7 @@ void mesh_filter::MeshFilterBase::getModelLabels(LabelType* labels) const
227227
job->wait();
228228
}
229229

230-
void mesh_filter::MeshFilterBase::getModelDepth(double* depth) const
230+
void mesh_filter::MeshFilterBase::getModelDepth(float* depth) const
231231
{
232232
JobPtr job1 =
233233
std::make_shared<FilterJob<void>>([&renderer = *mesh_renderer_, depth] { renderer.getDepthBuffer(depth); });
@@ -243,7 +243,7 @@ void mesh_filter::MeshFilterBase::getModelDepth(double* depth) const
243243
job2->wait();
244244
}
245245

246-
void mesh_filter::MeshFilterBase::getFilteredDepth(double* depth) const
246+
void mesh_filter::MeshFilterBase::getFilteredDepth(float* depth) const
247247
{
248248
JobPtr job1 = std::make_shared<FilterJob<void>>([&filter = *depth_filter_, depth] { filter.getDepthBuffer(depth); });
249249
JobPtr job2 = std::make_shared<FilterJob<void>>(

moveit_ros/perception/mesh_filter/src/sensor_model.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -102,7 +102,7 @@ inline bool isAligned16(const void* pointer)
102102
#endif
103103
} // namespace
104104

105-
void mesh_filter::SensorModel::Parameters::transformModelDepthToMetricDepth(double* depth) const
105+
void mesh_filter::SensorModel::Parameters::transformModelDepthToMetricDepth(float* depth) const
106106
{
107107
#if HAVE_SSE_EXTENSIONS
108108
const __m128 mmNear = _mm_set1_ps(near_clipping_plane_distance_);
@@ -161,7 +161,7 @@ void mesh_filter::SensorModel::Parameters::transformModelDepthToMetricDepth(doub
161161
const float nf = near * far;
162162
const float f_n = far - near;
163163

164-
const double* depth_end = depth + width_ * height_;
164+
const float* depth_end = depth + width_ * height_;
165165
while (depth < depth_end)
166166
{
167167
if (*depth != 0 && *depth != 1)
@@ -178,7 +178,7 @@ void mesh_filter::SensorModel::Parameters::transformModelDepthToMetricDepth(doub
178178
#endif
179179
}
180180

181-
void mesh_filter::SensorModel::Parameters::transformFilteredDepthToMetricDepth(double* depth) const
181+
void mesh_filter::SensorModel::Parameters::transformFilteredDepthToMetricDepth(float* depth) const
182182
{
183183
#if HAVE_SSE_EXTENSIONS
184184
//* SSE version
@@ -223,7 +223,7 @@ void mesh_filter::SensorModel::Parameters::transformFilteredDepthToMetricDepth(d
223223
++mmDepth;
224224
}
225225
#else
226-
const double* depth_end = depth + width_ * height_;
226+
const float* depth_end = depth + width_ * height_;
227227
const float scale = far_clipping_plane_distance_ - near_clipping_plane_distance_;
228228
const float offset = near_clipping_plane_distance_;
229229
while (depth < depth_end)

0 commit comments

Comments
 (0)