Show EOL distros: 

Package Summary

The rplidar ros package

Package Summary

The rplidar ros package, support rplidar A2/A1 and A3/S1

Package Summary

The rplidar ros package, support rplidar A2/A1

Package Summary

The rplidar ros package, support rplidar A2/A1 and A3/S1

Package Summary

The rplidar ros package, support rplidar A2/A1 and A3/S1

Package Summary

The rplidar ros package, support rplidar A1/A2/A3/S1/S2/S3

Package Summary

The rplidar ros package, support rplidar A1/A2/A3/S1/S2/S3/T1/C1

Overview

This package provides basic device handling for 2D Laser Scanner RPLIDAR A1/A2 and A3.

RPLIDAR is a low cost LIDAR sensor suitable for indoor robotic SLAM application. It provides 360 degree scan field, 5.5hz/10hz rotating frequency with guaranteed 8 meter ranger distance, current more than 16m for A2 and 25m for A3 . By means of the high speed image processing engine designed by RoboPeak, the whole cost are reduced greatly, RPLIDAR is the ideal sensor in cost sensitive areas like robots consumer and hardware hobbyist.

RPLIDAR A3 performs high speed distance measurement with more than 16K samples per second,RPLIDAR A2 performs high speed distance measurement with more than 4K/8K samples per second,RPLIDAR A1 supports 2K/4K samples per second. For a scan requires 360 samples per rotation, the 10hz scanning frequency can be achieved. Users can customized the scanning frequency from 2hz to 10hz freely by control the speed of the scanning motor. RPLIDAR will self-adapt the current scanning speed.

The driver publishes device-dependent sensor_msgs/LaserScan data.

SLAM based on RPLIDAR and ROS Hector Mapping:

ROS Nodes

rplidarNode

rplidarNode is a driver for RPLIDAR. It reads RPLIDAR raw scan result using RPLIDAR's SDK and convert to ROS LaserScan message.

Published Topics

scan (sensor_msgs/LaserScan)
  • it publishes scan topic from the laser.

Services

stop_motor (std_srvs/Empty)
  • Call the serive to stop the motor of rplidar.
start_motor (std_srvs/Empty)
  • Call the service to start the motor of rplidar.

Parameters

serial_port (string, default: /dev/ttyUSB0)
  • serial port name used in your system.
serial_baudrate (int, default: 115200)
  • serial port baud rate.
frame_id (string, default: laser_frame)
  • frame ID for the device.
inverted (bool, default: false)
  • indicated whether the LIDAR is mounted inverted.
angle_compensate (bool, default: false)
  • indicated whether the driver needs do angle compensation.
scan_mode (string, default: std::string())
  • the scan mode of lidar.

Device Settings

RPLIDAR tutorial

Use following udev rules to set permission for a rplidar device.

KERNEL=="ttyUSB*", MODE="0666"

For fixed rplidar port, you can using the script file to remap the USB port name:

./scripts/create_udev_rules.sh

Once you have change the USB port remap, you can change the launch file about the serial_port value.

<param name="serial_port" type="string" value="/dev/rplidar"/>

Launch File Examples

Check the authority of rplidar's serial-port :

ls -l /dev |grep ttyUSB

Add the authority of write: (such as /dev/ttyUSB0)

 sudo chmod 666 /dev/ttyUSB0

Start a rplidar node and view the scan result in rviz.

 $ roslaunch rplidar_ros view_rplidar.launch    #for rplidar A1/A2
or
 $ roslaunch rplidar_ros view_rplidar_a3.launch #for rplidar A3

Start a rplidar node and run rplidar client process to print the raw scan result

 $ roslaunch rplidar_ros rplidar.launch  #for rplidar A1/A2
or
 $ roslaunch rplidar_ros_a3 rplidar.launch  #for rplidar A3

 $ rosrun rplidar_ros rplidarNodeClient

About Slamtec/RoboPeak

RoboPeak is a research & development team in robotics platforms and applications, founded in 2009. Our team members are Software Engineers, Electronics Engineers and New Media Artists that all come from China. We establish our company Slamtec in 2013.

Slamtec focus on providing economically affordable and high-performance solution for robots in auto localization and navigation as well as offering related core sensors. And our major products are low-cost LIDAR sensor(RPLIDAR), SLAM (Simultaneous Localization and Mapping) solution based on LIDAR technology and Zeus General Purpose Robot Platform which can be widely used in business places.

Our vision is to enrich people’s daily-life with the ever-changing development and innovation in robotic technologies.

Website: Slamtec

Slamtec resellers

Slamtec HomePage

RPLIDAR SDK

rplidar_ros tutorial

Review by mechatronicsguy

Wiki: rplidar (last edited 2019-08-02 02:00:29 by TheoKanning)