Skip to content

Commit

Permalink
Merge pull request #1 from volkandre/master
Browse files Browse the repository at this point in the history
Fixed bug. Laserscans now cover full 360 degrees.
  • Loading branch information
khallenbeck-dsi committed Sep 30, 2017
2 parents d678c87 + 00f407e commit 7b7be3c
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion velodyne_laserscan/src/VelodyneLaserScan.cpp
Expand Up @@ -85,7 +85,7 @@ void VelodyneLaserScan::recvCallback(const sensor_msgs::PointCloud2ConstPtr& msg
// Construct LaserScan message
if ((offset_x >= 0) && (offset_y >= 0) && (offset_r >= 0)) {
const float RESOLUTION = fabsf(cfg_.resolution);
const size_t SIZE = M_PI / RESOLUTION;
const size_t SIZE = 2.0 * M_PI / RESOLUTION;
sensor_msgs::LaserScanPtr scan(new sensor_msgs::LaserScan());
scan->header = msg->header;
scan->angle_increment = RESOLUTION;
Expand Down

0 comments on commit 7b7be3c

Please sign in to comment.