YDLIDAR / ydlidar_ros2_driver

ydlidar driver package under ros2
Other
54 stars 99 forks source link

ranges length is not constant #15

Closed rasheeddo closed 2 years ago

rasheeddo commented 2 years ago

Hi, thank you for the work on ros2_driver support, I am using TG30 but I noticed that the length of ranges array from /scan topic from ydlidar_ros2_driver_node is not constant. When I was using your ydlidar_ros package on ROS1 with TG.launch, it gave a ranges length as 2019 constantly. Here is my ydlidar.yaml config file to run with ydlidar_ros2_driver_node

ydlidar_ros2_driver_node:
  ros__parameters:
    port: /dev/ydlidar
    frame_id: base_laser
    ignore_array: ""
    baudrate: 512000
    lidar_type: 0
    device_type: 0
    sample_rate: 20
    abnormal_check_count: 4
    resolution_fixed: true
    reversion: true
    inverted: true
    auto_reconnect: true
    isSingleChannel: false
    intensity: false
    support_motor_dtr: false
    angle_max: 180.0
    angle_min: -180.0
    range_max: 16.0
    range_min: 0.01
    frequency: 10.0 #8.0
    invalid_range_is_inf: false

I made a python script to subscribe on that, and the ranges length is like 1963, 1965, 1971, 1967, 1965, 1961,... Here is the test script I am using,

import rclpy
from rclpy.node import Node
from sensor_msgs.msg import LaserScan

class Test(Node):
    def __init__(self):
        super().__init__("test_node")
        self.get_logger().info('Check lidar')
        # https://answers.ros.org/question/334649/ros2-turtlebot3-gazebo-scan-topic-subscriber-is-not-calling-the-callback-function/
        qos_policy = rclpy.qos.QoSProfile(reliability=rclpy.qos.ReliabilityPolicy.BEST_EFFORT, history=rclpy.qos.HistoryPolicy.KEEP_LAST, depth=1)
        self.sub = self.create_subscription(LaserScan, 'scan', self.callback, qos_profile=qos_policy)
        ### Loop spin ###
        timer_period = 0.05
        self.timer = self.create_timer(timer_period, self.timer_callback)

       def callback(self, msg):
        print(len(msg.ranges))

    def timer_callback(self):
        pass

def main(args=None):
    rclpy.init(args=args)
    node = Test()
    rclpy.spin(node)
    node.destroy_node()
    rclpy.shutdown()

if __name__ == "__main__":
    main()

Do you have any idea why the length of ranges is not constant as your ROS1 package?

rasheeddo commented 2 years ago

This problem would be an issue when using this ydlidar_ros2 package with slam_toolbox package to create a map.

I have solved it just temporarily by using ros1_bridge with your ydlidar_ros (ROS1) package, with TG.launch file it could give me a constant length of 2019, so the ros2 run slam_toolbox online_async_launch.py to make the map became working fine.

Wimll commented 2 years ago

Hi @rasheeddo,

Did you manage to solve this issue in the ros2 node? Thanks!

chenjunnn commented 2 years ago

I met the same problem using G4. And I found that the problem was caused by wrong param name resolution_fixed in ydlidar.yaml.

https://github.com/YDLIDAR/ydlidar_ros2_driver/blob/2e095da315aec0a0bc5aaac12082cb9d1f97f8b5/params/ydlidar.yaml#L11

https://github.com/YDLIDAR/ydlidar_ros2_driver/blob/2e095da315aec0a0bc5aaac12082cb9d1f97f8b5/src/ydlidar_ros2_driver_node.cpp#L88-L92

Which is also mentioned in https://github.com/YDLIDAR/ydlidar_ros2_driver/pull/13

@rasheeddo @Wimll

rasheeddo commented 2 years ago

@Wimll I solved it temporarily by using ydlidar_ros (ros1) with ros1_bridge. It just only for slam_toolbox when making a map, but for navigation2 I could come back and use ydlidar_ros2_driver as usual (even the length is not fixed).

@chenjunnn I tried changing the parameter name as you mentioned but the ranges became none (zero length), here is what topic echo gave me

header:
  stamp:
    sec: 1652847653
    nanosec: 148561000
  frame_id: laser_frame
angle_min: -3.1415927410125732
angle_max: 3.1415927410125732
angle_increment: -6.2831854820251465
time_increment: 4.999999873689376e-05
scan_time: 0.0989999994635582
range_min: 0.009999999776482582
range_max: 32.0
ranges: []
intensities: []

Here is my ydlidar.yaml

ydlidar_ros2_driver_node:
  ros__parameters:
    port: /dev/ydlidar
    frame_id: laser_frame
    ignore_array: ""
    baudrate: 512000
    lidar_type: 0 #1
    device_type: 0
    sample_rate: 20 #9
    abnormal_check_count: 4
    #resolution_fixed: true
    fixed_resolution: true
    reversion: true
    inverted: true
    auto_reconnect: true
    isSingleChannel: false
    intensity: false
    support_motor_dtr: false
    angle_max: 180.0
    angle_min: -180.0
    range_max: 32.0
    range_min: 0.01
    frequency: 10.0
    invalid_range_is_inf: false

Note that I tried changing the sample rate to 20 and lidar_type to 0, as an original TG.launch in ros1, but none of this works for me. When I commented fixed_resolution out (use default) I could see ranges data, but again I couldn't get the fixed length or ranges in this case.