Hokuyo UST-10LX¶
Links¶
Documents¶
- Hokuyo UST-10LX Instruction Manual
- Hokuyo UST-10LX Datasheet
- Hokuyo UST-10LX-H01 Datasheet
- Hokuyo UST-10LX-H02 Datasheet
- Hokuyo UST-10LX UST Communication Protocol Specification
- Hokuyo UST-10LX IP Discovery Tool
- Hokuyo UST-10LX 3D Model (STEP)
Note
Indeed, there are two versions of the Hokuyo UST-10LX sensor: H01 (most typical one, indoor usage) and H02 (outdoor environments). As a result, the latter supports a much higher surrounding intensity specification than the former (< 80.000lx versus < 15.000lx for H02 and H01, respectively).
Setup¶
Network¶
- Open Ubuntu Settings
- Task Bar Settings
- Dock Show Applications Settings
- Network Wired
Settings IPv4
- Set IPv4 Method to Manual
- Addresses
- Address:
192.168.0.1
- Netmask:
255.255.255.0
- Address:
Info
The default network setting of the Hokuyo UST-10LX is the following one:
- IP address:
192.168.0.10
- Port number:
10940
As a result, the computer should be in the same IP range, following a
255.255.255.0
mask for the IP address.
Info
If you want to change the IP address of the Hokuyo sensor, use the IP Discovery Tool.
Tip
One way to discover the IP address of the Hokuyo UST-10LX sensor is (assuming that the Ethernet wired connection is already configured to Manual IPv4 Method and its static IP is in the same range of the sensor):
nmap 192.168.0.0/24 -sn # ping scan (disables port scan, should be faster)
nmap 192.168.0.0/24 -p 10940 # only scan a specific port
nmap 192.168.0.0/24 -p1-65535 # scans a range of ports (1 to 65535)
ROS 1 Noetic¶
sudo apt install ros-noetic-urg-node
ROS 2 Foxy¶
sudo apt install ros-foxy-urg-node
Launch¶
ROS 1 Noetic¶
source /opt/ros/noetic/setup.bash
mkdir ~/ros1_ws/launch/urg_node/ -p
cd ~/ros1_ws/launch/urg_node
touch hokuyo_ust10lx.launch
tee hokuyo_ust10lx.launch <<EOF
<launch>
<node pkg="urg_node" type="urg_node" name="urg_node" output="screen">
<param name="ip_address" value="192.168.0.10"/>
<param name="ip_port" value="10940"/>
<param name="serial_port" value=""/>
<param name="serial_baud" value=""/>
<param name="frame_id" value="laser"/>
<param name="calibrate_time" value="false"/>
<param name="publish_intensity" value="false"/>
<param name="publish_multiecho" value="false"/>
<param name="angle_min" value="-2.2689"/>
<param name="angle_max" value="2.2689"/>
</node>
</launch>
EOF
roslaunch hokuyo_ust10lx.launch
<launch>
<node pkg="urg_node" type="urg_node" name="urg_node" output="screen">
<param name="ip_address" value="192.168.0.10"/>
<param name="ip_port" value="10940"/>
<param name="serial_port" value=""/>
<param name="serial_baud" value=""/>
<param name="frame_id" value="laser"/>
<param name="calibrate_time" value="false"/>
<param name="publish_intensity" value="false"/>
<param name="publish_multiecho" value="false"/>
<param name="angle_min" value="-2.2689"/>
<param name="angle_max" value="2.2689"/>
</node>
</launch>
ROS 2 Foxy¶
source /opt/ros/foxy/setup.bash
mkdir ~/ros2_ws/launch/urg_node/ -p
cd ~/ros2_ws/launch/urg_node
touch hokuyo_ust10lx.launch.xml
tee hokuyo_ust10lx.launch.xml <<EOF
<launch>
<node pkg="urg_node" exec="urg_node_driver" name="urg_node">
<param name="ip_address" value="192.168.0.10"/>
<param name="ip_port" value="10940"/>
<param name="laser_frame_id" value="laser"/>
<param name="calibrate_time" value="false"/>
<param name="publish_intensity" value="false"/>
<param name="publish_multiecho" value="false"/>
<param name="angle_min" value="-2.2689"/>
<param name="angle_max" value="2.2689"/>
</node>
</launch>
EOF
ros2 launch hokuyo_ust10lx.launch.xml
<launch>
<node pkg="urg_node" exec="urg_node_driver" name="urg_node">
<param name="ip_address" value="192.168.0.10"/>
<param name="ip_port" value="10940"/>
<param name="laser_frame_id" value="laser"/>
<param name="calibrate_time" value="false"/>
<param name="publish_intensity" value="false"/>
<param name="publish_multiecho" value="false"/>
<param name="angle_min" value="-2.2689"/>
<param name="angle_max" value="2.2689"/>
</node>
</launch>