Skip to content

Commit

Permalink
fix(image_projection_based_fusion): fix invalidPointerCast
Browse files Browse the repository at this point in the history
Signed-off-by: Koichi Imai <kotty.0704@gmail.com>
  • Loading branch information
Koichi98 committed Jul 10, 2024
1 parent 5e5ad0b commit e0c4249
Showing 1 changed file with 4 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -322,9 +322,9 @@ 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];
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]);
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);
point_lidar << p_x, p_y, p_z;
point_camera = lidar2cam_affine * point_lidar;
p_x = point_camera.x();
Expand All @@ -345,7 +345,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];
auto p_class = reinterpret_cast<float *>(&output[stride + class_offset]);
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
*p_class = cls.second(label2d) ? (class_index_[cls.first] + *p_class) : *p_class;
Expand Down

0 comments on commit e0c4249

Please sign in to comment.