Skip to content

Commit

Permalink
Fix laser publisher (#425)
Browse files Browse the repository at this point in the history
  • Loading branch information
ad-daniel authored Apr 1, 2022
1 parent 2ad205c commit 8989881
Showing 1 changed file with 3 additions and 3 deletions.
6 changes: 3 additions & 3 deletions webots_ros2_driver/src/plugins/static/Ros2Lidar.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,8 @@ namespace webots_ros2_driver
mLaserPublisher = mNode->create_publisher<sensor_msgs::msg::LaserScan>(mTopicName, rclcpp::SensorDataQoS().reliable());
const int resolution = mLidar->getHorizontalResolution();
mLaserMessage.header.frame_id = mFrameName;
mLaserMessage.angle_increment = -mLidar->getFov() / resolution;
mLaserMessage.angle_min = mLidar->getFov() / 2.0 - mLaserMessage.angle_increment;
mLaserMessage.angle_increment = -mLidar->getFov() / (resolution - 1);
mLaserMessage.angle_min = mLidar->getFov() / 2.0;
mLaserMessage.angle_max = -mLidar->getFov() / 2.0;
mLaserMessage.time_increment = (double)mLidar->getSamplingPeriod() / (1000.0 * resolution);
mLaserMessage.scan_time = (double)mLidar->getSamplingPeriod() / 1000.0;
Expand Down Expand Up @@ -86,7 +86,7 @@ namespace webots_ros2_driver

if (mAlwaysOn)
return;

const bool shouldPointCloudBeEnabled = mPointCloudPublisher->get_subscription_count() > 0;
const bool shouldSensorBeEnabled = shouldPointCloudBeEnabled ||
(mLaserPublisher != nullptr && mLaserPublisher->get_subscription_count() > 0);
Expand Down

0 comments on commit 8989881

Please sign in to comment.