Skip to content

Commit

Permalink
fix(image_projection_based_fusion): fix invalidPointerCast (autowaref…
Browse files Browse the repository at this point in the history
…oundation#7927)

* fix(image_projection_based_fusion): fix invalidPointerCast
add cppcheck-suppress for reinterpret_cast 

Signed-off-by: Koichi Imai <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
  • Loading branch information
2 people authored and badai-nguyen committed Aug 5, 2024
1 parent d52bbe4 commit 3068017
Showing 1 changed file with 3 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -329,9 +329,11 @@ dc | dc dc dc dc ||zc|
int stride = p_step * i;
unsigned char * data = &painted_pointcloud_msg.data[0];
unsigned char * output = &painted_pointcloud_msg.data[0];
// cppcheck-suppress-begin invalidPointerCast
float p_x = *reinterpret_cast<const float *>(&data[stride + x_offset]);
float p_y = *reinterpret_cast<const float *>(&data[stride + y_offset]);
float p_z = *reinterpret_cast<const float *>(&data[stride + z_offset]);
// cppcheck-suppress-end invalidPointerCast
point_lidar << p_x, p_y, p_z;
point_camera = lidar2cam_affine * point_lidar;
p_x = point_camera.x();
Expand All @@ -352,6 +354,7 @@ dc | dc dc dc dc ||zc|
int label2d = feature_object.object.classification.front().label;
if (!isUnknown(label2d) && isInsideBbox(projected_point.x(), projected_point.y(), roi, p_z)) {
data = &painted_pointcloud_msg.data[0];
// cppcheck-suppress invalidPointerCast
auto p_class = reinterpret_cast<float *>(&output[stride + class_offset]);
for (const auto & cls : isClassTable_) {
// add up the class values if the point belongs to multiple classes
Expand Down

0 comments on commit 3068017

Please sign in to comment.