Skip to content

Commit

Permalink
this commit fixes #265 @5m
Browse files Browse the repository at this point in the history
  • Loading branch information
Augusto Luis Ballardini committed May 27, 2015
1 parent 47cbff0 commit d430b64
Showing 1 changed file with 1 addition and 0 deletions.
1 change: 1 addition & 0 deletions src/laserscan_multi_merger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -196,6 +196,7 @@ void LaserscanMerger::pointcloud_to_laserscan(Eigen::MatrixXf points, pcl::PCLPo
sensor_msgs::LaserScanPtr output(new sensor_msgs::LaserScan());
output->header = pcl_conversions::fromPCL(merged_cloud->header);
output->header.frame_id = destination_frame.c_str();
output->header.stamp = ros::Time::now(); //fixes #265
output->angle_min = this->angle_min;
output->angle_max = this->angle_max;
output->angle_increment = this->angle_increment;
Expand Down

0 comments on commit d430b64

Please sign in to comment.