Skip to content

Commit

Permalink
Merge pull request allenh1#6 from tiiuae/DP-1508-galactic_porting
Browse files Browse the repository at this point in the history
Warning fixes
  • Loading branch information
spurnvoj authored Dec 9, 2021
2 parents 403c488 + 976522a commit cc550b5
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 3 deletions.
4 changes: 2 additions & 2 deletions launch/rplidar.launch.py
100644 → 100755
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,9 @@
def generate_launch_description():
return LaunchDescription([
Node(
node_name='rplidar',
name='rplidar',
package='rplidar_ros2',
node_executable='rplidar',
executable='rplidar',
output='screen',
parameters=[
path.join(get_package_share_directory('rplidar_ros2'), 'config',
Expand Down
2 changes: 1 addition & 1 deletion src/client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ void scanCallback(const std::shared_ptr<sensor_msgs::msg::LaserScan> scan)
const auto& logger = rclcpp::get_logger("RPlidar Client");
const auto count = static_cast<size_t>(scan->scan_time / scan->time_increment);

RCLCPP_INFO(logger, "I heard a laser scan %s[%d]:", scan->header.frame_id.c_str(), count);
RCLCPP_INFO(logger, "I heard a laser scan %s[%ld]:", scan->header.frame_id.c_str(), count);
RCLCPP_INFO(logger, "angle_range, %f, %f", radians_to_degrees(scan->angle_min), radians_to_degrees(scan->angle_max));

for (size_t index = 0; index < count; ++index) {
Expand Down

0 comments on commit cc550b5

Please sign in to comment.