Skip to content

Commit

Permalink
fix #323 pointcloud size
Browse files Browse the repository at this point in the history
  • Loading branch information
goldbattle committed Apr 15, 2023
1 parent 5d9fbee commit 70b0ae3
Showing 1 changed file with 4 additions and 4 deletions.
8 changes: 4 additions & 4 deletions ov_msckf/src/ros/ROSVisualizerHelper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,15 +38,15 @@ sensor_msgs::PointCloud2 ROSVisualizerHelper::get_ros_pointcloud(const std::vect
sensor_msgs::PointCloud2 cloud;
cloud.header.frame_id = "global";
cloud.header.stamp = ros::Time::now();
cloud.width = 3 * feats.size();
cloud.width = feats.size();
cloud.height = 1;
cloud.is_bigendian = false;
cloud.is_dense = false; // there may be invalid points

// Setup pointcloud fields
sensor_msgs::PointCloud2Modifier modifier(cloud);
modifier.setPointCloud2FieldsByString(1, "xyz");
modifier.resize(3 * feats.size());
modifier.resize(feats.size());

// Iterators
sensor_msgs::PointCloud2Iterator<float> out_x(cloud, "x");
Expand Down Expand Up @@ -96,15 +96,15 @@ sensor_msgs::msg::PointCloud2 ROSVisualizerHelper::get_ros_pointcloud(std::share
sensor_msgs::msg::PointCloud2 cloud;
cloud.header.frame_id = "global";
cloud.header.stamp = node->now();
cloud.width = 3 * feats.size();
cloud.width = feats.size();
cloud.height = 1;
cloud.is_bigendian = false;
cloud.is_dense = false; // there may be invalid points

// Setup pointcloud fields
sensor_msgs::PointCloud2Modifier modifier(cloud);
modifier.setPointCloud2FieldsByString(1, "xyz");
modifier.resize(3 * feats.size());
modifier.resize(feats.size());

// Iterators
sensor_msgs::PointCloud2Iterator<float> out_x(cloud, "x");
Expand Down

0 comments on commit 70b0ae3

Please sign in to comment.