Hokuyo URG-04LX-UG01
This tutorial will guide you through the process of connecting a LiDAR sensor to your Leo Rover.
Light Detection and Ranging devices, or lidars for short, are mechanisms used for mapping the environment, object detection, tracking the speed of vehicles and in a wide range of other applications. In robotics 2D lidars, like RPLidar A2M8, are used for things such as indoor SLAM (Simultaneous localization and mapping) or safety systems.
The steps might slightly differ for other LiDAR sensors but should be essentially similar.
What to expect?
After completing this tutorial, you should be able to visualize the model and data from the sensor like in the video below.
Prerequisites
List of components
- Hokuyo URG-04LX-UG01
- 3D-printed 04008 Hokuyo URG-04LX adapter (available here)
- miniUSB-USB A cable (provided by default with Leo Rover)
- 4x M5x10 mounting screws
- 2x M3x10 mounting screws
Mechanical integration
When mounting the sensor, you should be particularly careful not to obstruct the field of view by other parts of the Rover.
We developed 3D printable models of mechanical interfaces that allow you to mount the aforementioned sensor to the mounting plate of the rover. Locating the sensor the top of the robot provides a wide field of view with not many obstacles for the laser beam to get caught on. Get the files from here: Addon Adapters.
- With 2x M3x6 Allen screws connect the sensor to the printed interface plate.
- Use 4x M5x10 Allen screws to fasten the sensor to the Leo Rover.
Wiring and electronics connection
The sensor can be connected to the robot's main computer via the USB socket positioned at the top of the rover.
USB connection provides power to the sensor and allows the data transfer. This means that no external power sources are necessary. Some lidars might need external power connections, that's when Powerbox might come in handy.
With everything connected Leo Rover looks like this:
Software integration
The first thing you can do is to make sure your device has the correct permissions and is available at the fixed path on your system. To do this, you can add the following rule to the udev service:
KERNEL=="ttyACM*", ATTRS{idVendor}=="15d1", MODE="0666", GROUP="dialout", SYMLINK+="lidar", ENV{ID_MM_DEVICE_IGNORE}="1"
Paste these lines to /etc/udev/rules.d/lidar.rules
file and reload udev rules
by typing:
sudo udevadm control --reload-rules && sudo udevadm trigger
Your device should now be available at the /dev/lidar
path.
We want the sensor functionality to be available in the ROS ecosystem, so you should install a ROS package that provides a node for the sensor you are trying to integrate.
sudo apt install ros-${ROS_DISTRO}-urg-node
Now, create a launch file that would start the node with a fitting configuration.
<launch>
<node name="urg_node" pkg="urg_node" type="urg_node" output="log">
<param name="port" value="/dev/lidar"/>
<param name="frame_id" value="laser_frame"/>
<param name="calibrate_time" value="true"/>
</node>
</launch>
Include your launch file in the robot.launch
file, so that your node will
start at boot.
<include file="/etc/ros/laser.launch"/>
Your robot should be aware of where the scanner is located and what space it occupies. You can ensure it does that by creating a URDF model of the sensor.
<?xml version="1.0"?>
<robot>
<link name="hokuyo_link">
<visual>
<origin xyz="0 0 0.003"/>
<geometry>
<box size="0.079 0.05 0.006"/>
</geometry>
<material name="support">
<color rgba="0.5 0.5 0.5 1.0"/>
</material>
</visual>
<visual>
<origin xyz="0 0 0.041"/>
<geometry>
<box size="0.05 0.05 0.07"/>
</geometry>
<material name="lidar">
<color rgba="1.0 0.0 0.0 0.7"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0.003"/>
<geometry>
<box size="0.079 0.05 0.006"/>
</geometry>
</collision>
<collision>
<origin xyz="0 0 0.041"/>
<geometry>
<box size="0.05 0.05 0.07"/>
</geometry>
</collision>
</link>
<joint name="hokuyo_joint" type="fixed">
<origin xyz="0.0775 0 0"/>
<parent link="base_link"/>
<child link="hokuyo_link"/>
</joint>
<link name="laser_frame"/>
<joint name="laser_joint" type="fixed">
<origin xyz="0 0 0.064"/>
<parent link="hokuyo_link"/>
<child link="laser_frame"/>
</joint>
</robot>
And including it in the description that is uploaded at boot.
<xacro:include filename="/etc/ros/urdf/laser.urdf.xacro"/>
You can experiment with the URDF file and create a more representative model of the sensor by adding more visual and collision tags or by including meshes in STL or COLLADA format.
The last step is to either reboot the robot or restart the leo service.
sudo systemctl restart leo
Examples
Reading and visualizing the data of the Hokuyo laser scanner
The robot should now publish the
LaserScan messages
on the /scan
topic. You can check the raw data that it sends by typing:
rostopic echo /scan
If you have ROS installed on your computer, you can get a more graphical representation of the data with RViz. If you don't have ROS, you can follow this guide:
Before starting RViz, make sure you completed the Connecting another computer to ROS network section of ROS Development tutorial:
Now, open RViz by typing rviz
in the terminal, or, if you have the leo_viz
package installed, type:
roslaunch leo_viz rviz.launch
This will start RViz with visualization of the current robot model.
On the Displays panel click Add -> By topic and search for the /scan
topic. Choose the LaserScan display and click Ok.
You should now be able to see the data from the sensor visualized as points in 3D space.
To put the points into the camera image, you can also add the Camera display.
Be sure to check compressed
as the Transport Hint and /camera/image_raw
as
the Image Topic.
What next?
Lidars are commonly used in projects involving autonomous navigation, you might be interested in a tutorial about it.
They are however, not the only way of teaching a Leo Rover how to move on it's own. Check out our line follower tutorial if you want to learn more. You can also check our Integrations page for more instructions.