Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Reduce overhead related to memory allocation #29

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
32 changes: 16 additions & 16 deletions rslidar_pointcloud/src/convert.cc
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@ Convert::Convert(ros::NodeHandle node, ros::NodeHandle private_nh) : data_(new r
private_nh.param("input_packets_topic", input_packets_topic, std::string("rslidar_packets"));
rslidar_scan_ = node.subscribe(input_packets_topic, 10, &Convert::processScan, (Convert*)this,
ros::TransportHints().tcpNoDelay(true));
out_points_.reset(new pcl::PointCloud<pcl::PointXYZI>);
}

void Convert::callback(rslidar_pointcloud::CloudNodeConfig& config, uint32_t level)
Expand All @@ -52,35 +53,34 @@ void Convert::callback(rslidar_pointcloud::CloudNodeConfig& config, uint32_t lev
/** @brief Callback for raw scan messages. */
void Convert::processScan(const rslidar_msgs::rslidarScan::ConstPtr& scanMsg)
{
pcl::PointCloud<pcl::PointXYZI>::Ptr outPoints(new pcl::PointCloud<pcl::PointXYZI>);
outPoints->header.stamp = pcl_conversions::toPCL(scanMsg->header).stamp;
outPoints->header.frame_id = scanMsg->header.frame_id;
outPoints->clear();
out_points_->header.stamp = pcl_conversions::toPCL(scanMsg->header).stamp;
out_points_->header.frame_id = scanMsg->header.frame_id;
out_points_->clear();
if (model == "RS16")
{
outPoints->height = 16;
outPoints->width = 24 * (int)scanMsg->packets.size();
outPoints->is_dense = false;
outPoints->resize(outPoints->height * outPoints->width);
out_points_->height = 16;
out_points_->width = 24 * (int)scanMsg->packets.size();
out_points_->is_dense = false;
out_points_->resize(out_points_->height * out_points_->width);
}
else if (model == "RS32")
{
outPoints->height = 32;
outPoints->width = 12 * (int)scanMsg->packets.size();
outPoints->is_dense = false;
outPoints->resize(outPoints->height * outPoints->width);
out_points_->height = 32;
out_points_->width = 12 * (int)scanMsg->packets.size();
out_points_->is_dense = false;
out_points_->resize(out_points_->height * out_points_->width);
}

// process each packet provided by the driver

data_->block_num = 0;
for (size_t i = 0; i < scanMsg->packets.size(); ++i)
{
data_->unpack(scanMsg->packets[i], outPoints);
data_->unpack(scanMsg->packets[i], out_points_);
}
sensor_msgs::PointCloud2 outMsg;
pcl::toROSMsg(*outPoints, outMsg);

output_.publish(outMsg);
pcl::toROSMsg(*out_points_, out_msg_);

output_.publish(out_msg_);
}
} // namespace rslidar_pointcloud
3 changes: 3 additions & 0 deletions rslidar_pointcloud/src/convert.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,9 @@ class Convert
boost::shared_ptr<rslidar_rawdata::RawData> data_;
ros::Subscriber rslidar_scan_;
ros::Publisher output_;

pcl::PointCloud<pcl::PointXYZI>::Ptr out_points_;
sensor_msgs::PointCloud2 out_msg_;
};

} // namespace rslidar_pointcloud
Expand Down