iRobotEducation / create3_examples

Example nodes to drive the iRobot® Create® 3 Educational Robot

Geek Repo:Geek Repo

Github PK Tool:Github PK Tool

RPLidar connection notes

carlsondc-ceva opened this issue · comments

Suggestions for the documentation:

  • Note that for an RPLidar A2, if the cable is coming out towards the tray, you need to set flip_axis to true in config/rplidar_node.yaml . I'm assuming this value is fine as it is specified for the A1 which is used in the readme. You can tell that Something Is Wrong by looking at the /scan topic in rviz and driving it towards a wall (set fixed frame to base_link)-- the scan hits will move the wrong direction unless you flip the x axis.

  • You can make the following changes to ensure that the LIDAR is always available at a fixed device file:

  1. Connect RPLidar USB adapter to SBC and run sudo lsusb. Look for the section describing the UART bridge:
Bus 001 Device 004: ID 10c4:ea60 Silicon Labs CP210x UART Bridge
Device Descriptor:
 bLength                18
 bDescriptorType         1
 bcdUSB               1.10
 bDeviceClass            0
 bDeviceSubClass         0
 bDeviceProtocol         0
 bMaxPacketSize0        64
 idVendor           0x10c4 Silicon Labs
 idProduct          0xea60 CP210x UART Bridge

Note the "idVendor" and "idProduct" fields (0x10c4, 0xea60 respectively)
2. Create a file under /etc/udev/rules.d to handle usb-serial device connections and automatically symlink to a predictable location

Create /etc/udev/rules.d/99-usb-serial.rules (or similar file)

SUBSYSTEM=="tty", ATTRS{idVendor}=="10c4", ATTRS{idProduct}=="ea60", SYMLINK+="lidar_0"

  1. Set the serial_port entry in config/rplidar_node.yaml to /dev/lidar_0
  2. Rebuild the workspace

Not sure if this is due to some quirk of the RPLidar A2 or if this is likely to affect the A1 that the example specifies, but I noticed that during constant-velocity rotations, the map <-> odom transform updated and introduced a step error that resolved once the rotation stopped and another SLAM update occurred. I tracked this down to an unreported 50ms of latency in the LIDAR data (timestamps were 50ms later than they should have been).

Top plot is the rotation in the map<-> odom transform, middle is the heading of base_footprint and motion capture ("MC"), bottom is residuals from various heading sources. The two odometry sources (c3_odom and pi_scout_odom) have a small flat residual which shows that they were well-aligned in time with the ground truth. The SLAM sources all have a step in their residual mid-turn, and then once we go back to straight driving, they drop back down.

image

The height of this step corresponded to ~50 ms of rotation, so it looks like SLAM was matching up the scan at time t with odometry at time t - 50 ms. I put together a ROS node to modify the laser scan header, remapped a few topics, and got rid of this effect.

Anyway, I'm leaving this here in case somebody else tries to connect an RPLidar A2 and sees this behavior. Here's the node that I used to shift the timestamp:

#!/usr/bin/env python3
import rclpy
from rclpy.node import Node
from sensor_msgs.msg import LaserScan
import rclpy.time

class AdjustLaserScanTime(Node):
    def __init__(self):
        super().__init__('adjust_LaserScan_time')
        self.publisher = self.create_publisher(LaserScan, "scan_out", 10)
        self.declare_parameter('time_shift', 0.0)
        self.subscription = self.create_subscription(LaserScan,
                                                     "scan_in",
                                                     self.callback,
                                                     10)
        self.time_shift = rclpy.time.Duration(seconds=self.get_parameter('time_shift').get_parameter_value().double_value)


    def callback(self, msg):
        msg.header.stamp = rclpy.time.Time.to_msg(rclpy.time.Time.from_msg(msg.header.stamp) + self.time_shift)
        self.publisher.publish(msg)


def main(args=None):
    rclpy.init(args=args)
    adjustLaserScanTime = AdjustLaserScanTime()
    rclpy.spin(adjustLaserScanTime)
    adjustLaserScanTime.destroy_node()
    rclpy.shutdown()


if __name__ == '__main__':
    main()

@carlsondc-ceva
Here is what I did:

  1. My file /etc/udev/rules.d/99-usb-serial.rules has this SUBSYSTEM=="tty", ATTRS{idVendor}=="10c4", ATTRS{idProduct}=="ea60", SYMLINK+="lidar_0"
  2. I changed my config/rplidar_node.yaml to look like this
rplidar_node:
  ros__parameters:
    angle_compensate: true
    channel_type: serial
    flip_x_axis: false
    frame_id: laser_frame
    inverted: false
    scan_mode: ''
    serial_baudrate: 115200
    serial_port: /dev/lidar_0
    topic_name: scan
    use_sim_time: false

But when I run ros2 launch create3_lidar sensors_launch.py I get this as an output:

[INFO] [launch]: All log files can be found below /home/robotics_roomba_2/.ros/log/2023-04-10-16-06-31-101572-roomba-pi-12470
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [static_transform_publisher-1]: process started with pid [12471]
[INFO] [rplidar_composition-2]: process started with pid [12473]
[static_transform_publisher-1] [WARN] [1681160791.650758709] []: Old-style arguments are deprecated; see --help for new-style arguments
[static_transform_publisher-1] [INFO] [1681160791.725777071] [static_transform_publisher_8uYdphFJos3spgzt]: Spinning until stopped - publishing transform
[static_transform_publisher-1] translation: ('-0.012000', '0.000000', '0.144000')
[static_transform_publisher-1] rotation: ('0.000000', '0.000000', '0.000000', '1.000000')
[static_transform_publisher-1] from 'base_footprint' to 'laser_frame'
[rplidar_composition-2] [INFO] [1681160791.737906400] [rplidar_node]: RPLIDAR running on ROS 2 package rplidar_ros. SDK Version: '1.12.0'
[rplidar_composition-2] [ERROR] [1681160791.738414210] [rplidar_node]: Error, cannot bind to the specified serial port '/dev/lidar_0'.

Any help is appreciated!

Are the values you put into the 99-usb-serial.rules files the idVendor and idProduct values you see when you do lsusb? The values I put in above were what I saw on my machine, but your LIDAR might report different values.

You'll know it worked if you can do ls -la /dev/lidar_0 and it shows you a symbolic link to /dev/ttyUSBxxx where xxx is probably 0 but may not be if you have multiple USB devices plugged in.

You'll also need to make sure that the user running this has the relevant permissions -- typically being a member of the dialout group is sufficient.