ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Using Hokuyo node with multiple lasers

asked 2012-11-22 05:37:48 -0500

vhwanger gravatar image

I've got two Hokuyo laser scanners, both of which work individually when I run the hokuyo_node and change to the appropriate port. However, I'd like to have them both running at the same time, publishing to two different topics. How do I go about this?

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
2

answered 2012-11-22 06:51:59 -0500

kszonek gravatar image

updated 2012-11-22 06:53:14 -0500

You need to remap topic name on at least one of the nodes, and give deffirent names to them. Easiest way is use launch file:

<launch>
    <node name="hokuyo0" pkg="hokuyo_node" type="hokuyo_node">
        <param name="port" type="string" value="/dev/ttyACM0" />
        <remap from="scan" to="scan0" />
    </node>
    <node name="hokuyo1" pkg="hokuyo_node" type="hokuyo_node">
        <param name="port" type="string" value="/dev/ttyACM1" />
        <remap from="scan" to="scan1" />
    </node>
</launch>
edit flag offensive delete link more

Comments

How would one use tf in THIS code to rotate the frame of the second hokuyo by 180', so the messages publihsed to /scan by the second hokuyo are rotated?

kost9 gravatar image kost9  ( 2014-10-07 23:37:10 -0500 )edit
2

answered 2012-11-22 06:49:41 -0500

dornhege gravatar image

Just run both an remap the output topic. You might need to set the frame id too.

Here is an excerpt from the launch file that we use:

 <rosparam command="load" file="$(find matilda_bringup)/config/sensors.yaml" />

  <!-- Base Laser -->
  <group unless="$(arg disable_base_laser)" >
  <node pkg="hokuyo_node" type="hokuyo_node" name="base_hokuyo_node">
    <remap from="scan" to="base_scan" />
    <param name="frame_id" type="string" value="base_laser_link" />
    <param name="min_ang" type="double" value="-2.35619449019234492883" />
    <param name="max_ang" type="double" value="2.35619449019234492883" />
    <param name="skip" type="int" value="0" />
    <param name="intensity" value="false" />
  </node>
  </group>

  <!-- Vertical Laser -->
  <group unless="$(arg disable_vertical_laser)" >
  <node pkg="hokuyo_node" type="hokuyo_node" name="vertical_hokuyo_node">
    <remap from="scan" to="vertical_scan" />
    <param name="frame_id" type="string" value="vertical_laser_link" />
    <param name="min_ang" type="double" value="-2.09439510239319549227" />
    <param name="max_ang" type="double" value="2.09439510239319549227" />
    <param name="skip" type="int" value="0" />
    <param name="intensity" value="false" />
  </node>
  </group>

The sensors.yaml defines the ports to use, you could also symlink those if you like:

base_hokuyo_node/port: /dev/sensors/hokuyo_H0904092
vertical_hokuyo_node/port: /dev/sensors/hokuyo_H0507257

To get the names with serials for the Hokuyos you can use the following udev rules (using the getID node from the hokuyo driver package):

# Hokuyos
SUBSYSTEMS=="usb", KERNEL=="ttyACM[0-9]*", ATTRS{manufacturer}=="Hokuyo Data Flex for USB", ATTRS{product}=="URG-Series USB Driver", MODE="0666", GROUP="dialout", PROGRAM=="/etc/ros/run.sh hokuyo_node getID %N q", SYMLINK+="sensors/hokuyo_%c"

The run script needs to be available system-wide. It just sources setup.sh and rosruns the program:

#!/bin/sh
. /etc/ros/setup.sh 
rosrun $@
edit flag offensive delete link more

Comments

very helpful!

cat_in_box gravatar image cat_in_box  ( 2019-08-01 12:50:14 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2012-11-22 05:37:48 -0500

Seen: 3,194 times

Last updated: Nov 22 '12