Git Product home page Git Product logo

urg_node's Introduction

urg_node

Branches

LaserScan Visualization

Until the launch API is sorted out, there are two ways to view the laserscan in RViz:

  1. use the static_transform_publisher tool from tf2_ros to publish a static transform for a fixed frame simultaneously with rviz and urg_node.
ros2 run tf2_ros static_transform_publisher --frame-id world --child-frame-id laser

where "laser" is the frame id, which you can set in your urg_node yaml file

  1. Run the robot_state_publisher along with a urdf file so that a fixed frame can be loaded in rviz
ros2 run robot_state_publisher robot_state_publisher <path to urdf file>

A urdf file is already included and if you have succesfully ran an colcon build, the path to urdf file will be:

<path to ros2_ws>/install/share/urg_node/launch/hokuyo_laser.urdf

Now run RViz:

ros2 run rviz2 rviz2

or simply rviz2

Add the LaserScan topic and change the global fixed frame from 'map' to 'world' to display the laser scan.

Parameters

A YAML file example is included in the launch folder, all the available parameters are listed in it. For example (note that the serial_port is commented because you can't set a param with an empty string):

urg_node:
  ros__parameters:
    ip_address: "192.168.0.10"
    ip_port: 10940
    #serial_port: ""
    serial_baud: 115200
    laser_frame_id: laser
    angle_max: 3.14
    angle_min: -3.14
    publish_intensity: false
    publish_multiecho: false
    calibrate_time: false
    default_user_latency: 0
    diagnostics_tolerance: 0.05
    diagnostics_window_time: 5.0
    error_limit: 4
    get_detailed_status: false
    cluster: 0
    skip: 1

To give parameters to urg_node :

ros2 run urg_node urg_node_driver --ros-args --params-file path/to/my/file.yaml

You can reconfigure parameters while the node is launched. For now, you can only reconfigure the following parameters:

laser_frame_id
error_limit
default_user_latency
angle_max
angle_min
cluster
skip

For example to reconfigure the cluster parameter using command line :

ros2 param set /urg_node cluster 1

How to use the ust-20lx (and other Ethernet-based laser)

To use ust-20lx you need to be on the same subnet as the laser. The ust-20lx default IP address is 192.168.0.10, so you might need to change your IP to something on the same subnet.

On Ubuntu :

  • Network settings
  • Wired connection
  • Under IPv4, change the IPv4 method from automatic to Manual and under Addresses, set the values:
    Address : 192.168.0.15
    Netmask : 255.255.255.0
    Gateway : 192.168.0.1
  • Turn the connection off and on again to apply the change
  • To check if it worked, open a terminal and type
ip --color address

or simply ip -c a

  • Under eth0 (or maybe something like enpxxxxx), your IP should be 192.168.0.15. You should now be able to ping the ust-20lx at its address (by default 192.168.0.10)
ping 192.168.0.10

If you don't receive any answer, you might have a connection problem or the IP of your laser might have changed. If the IP was changed, you can either change your computer's IP to the same subnet or reset the laser to factory settings.

  • Once you can ping the laser, launch the urg_node_driver:
ros2 run urg_node urg_node_driver --ros-args --params-file path/to/my/file.yaml

urg_node's People

Contributors

chadrockey avatar clalancette avatar cottsay avatar jeff-o avatar k-okada avatar karsten1987 avatar mikaelarguedas avatar mikeferguson avatar mikeodr avatar mikepurvis avatar mjcarroll avatar mjforan avatar richardw347 avatar tappan-at-git avatar tonybaltovski avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

urg_node's Issues

Could not calibrate time offset: Time is out of dual 32-bit range

While trying to run urg_node with Hokuyo UST-05LA (May, 2016), recieving the following error:

[ INFO] [1587784386.134593468]: Starting calibration. This will take a few seconds.
[ WARN] [1587784386.134724427]: Time calibration is still experimental.
[FATAL] [1587784386.152248769]: Could not calibrate time offset: Time is out of dual 32-bit range
[urg_node_back-2] process has died [pid 21152, exit code -6, cmd /home/kubot/catkin_ws/devel/lib/urg_node/urg_node __name:=urg_node_back __log:=/root/.ros/log/ad0866ba-86a2-11ea-b3c1-5eb80ed6475f/urg_node_back-2.log].
log file: /root/.ros/log/ad0866ba-86a2-11ea-b3c1-5eb80ed6475f/urg_node_back-2*.log

Launch node is the following:

<node name="urg_node_back" pkg="urg_node" type="urg_node" output="screen">
    <param name="ip_address" value=""/>
    <param name="ip_port" value="10941"/>
    <param name="serial_port" value="/dev/ttyACM1"/>
    <param name="serial_baud" value="115200"/>
    <param name="frame_id" value="horizontal_rear_laser_link"/>
    <param name="calibrate_time" value="true"/>
    <param name="publish_intensity" value="true"/>
    <param name="publish_multiecho" value="false"/>
    <param name="angle_min" value="-2.35619449"/>
    <param name="angle_max" value="2.35619449"/>
    <param name="topic_name" value="/scan_2"/>
    <param name="skip" value="1"/>
  </node>

I'd like to point out, when calibrate_time set to false, node seem to work. Error appears only when it's set to true.

I suspect, it's also related to 23, comment, but it seems like it has been fixed in 35, pull. Any ideas?

Bad initial connection disables intensity publishing

If our robots power on a laser after first starting urg_node, the first connection attempt sometimes fails with persistent checksum errors.
This causes the driver to fail the IsIntensitySupported() test, which permanently clears the publish_intensity_ flag.

After repeated checksum errors the driver will reset and connect successfully but publish_intensity_ will be clear so we will not receive intensity info.
The same logic appears to apply to multiecho, but we don't have a multiecho device to test with.

We're using #58 which appears to fix the issue.

Stopped working after updating to newest release

The urg_node seems to not work with Hokuyo URG-04LX on version 0.1.12. This is the output I get (on ROS Kinetic and Melodic):

[ INFO] [1585259043.693278963]: Connected to serial device with ID: H1100676
[ INFO] [1585259044.886972703]: Streaming data.
[ WARN] [1585259047.377126484]: Could not grab single echo scan.
[ERROR] [1585259054.246105277]: Error count exceeded limit, reconnecting.
Segmentation fault

Not a single message on /scan topic is sent.

The 0.1.11 version works fine for me.

Memory corrption

Hi,
i got an odroid XU4 and UST-10LX , when i launch urg_node i get following error :

process[urg_node-4]: started with pid [3614]
*** Error in `/opt/ros/indigo/lib/urg_node/urg_node': malloc(): memory corruption: 0x0005cb58 ***
[urg_node-4] process has died [pid 3614

err when run urg_node

hi
i connect laser scanner 04lx and type rosrun urg_node urg_node but this error occured
"terminate called after throwing an instance of 'std::length_error' what(): vector::_M_fill_insert Aborted (core dumped)"
what can i do?

ROS2 Support laser_proc Problem

i build urg_node on ros2.
use laser_proc by laser_proc.
but cmake happen error:
fatal error: laser_proc/LaserTransport.h No such file or directory

Environment:
ubuntu 18.04
ros2-dashing

Segfault after I git clone and build,however it's ok when i install by APT

Segfault after I git clone and build,however it's ok when i install by APT

  1. build and install by the source code
[ 62%] Linking CXX shared library /home/gy/Documents/ros/WeiMeng/devel/lib/liburg_c_wrapper.so
[ 62%] Built target urg_c_wrapper
[ 68%] Linking CXX executable /home/gy/Documents/ros/WeiMeng/devel/lib/urg_node/getID
[ 75%] Linking CXX shared library /home/gy/Documents/ros/WeiMeng/devel/lib/liburg_node_driver.so
[ 81%] Built target getID
[ 87%] Built target urg_node_driver
[ 93%] Linking CXX executable /home/gy/Documents/ros/WeiMeng/devel/lib/urg_node/urg_node
[100%] Built target urg_node
gy@gy-Default-string:~/Documents/ros/WeiMeng$ 

It,s ok when i build the file and it's ok to ping the device

gy@gy-Default-string:~/Documents/ros/WeiMeng$ ping 192.168.0.10
PING 192.168.0.10 (192.168.0.10) 56(84) bytes of data.
64 bytes from 192.168.0.10: icmp_seq=1 ttl=64 time=0.170 ms
64 bytes from 192.168.0.10: icmp_seq=2 ttl=64 time=0.189 ms
64 bytes from 192.168.0.10: icmp_seq=3 ttl=64 time=0.187 ms
64 bytes from 192.168.0.10: icmp_seq=4 ttl=64 time=0.152 ms
^C
--- 192.168.0.10 ping statistics ---
4 packets transmitted, 4 received, 0% packet loss, time 3048ms
rtt min/avg/max/mdev = 0.152/0.174/0.189/0.019 ms

but when i run the node

gy@gy-Default-string:~$ rosrun urg_node urg_node _ip_address:=192.168.0.10
[ INFO] [1603868340.363169912]: Connected to network device with intensity and ID: H1642385
Segmentation fault (core dumped)

so it,s something wrong about the source code?

  1. install by use sudo apt-get install ros-kinetic-urg-node
[ INFO] [1603867460.253374970]: Connected to network device with intensity and ID: H1642385
[ INFO] [1603867460.320499879]: Streaming data.

Everything is OK

dynamic reconfigure Error

when I reconfigure the angle_min or angle_max by dynamic_reconfigure gui, urg_node will report 'Error count exceeded limit, reconnecting.' . then the node will run 'urg_.reset();'.
image

Noetic: segfault after connection success with package from APT

I have installed urg_node from APT (ros-neotic-urg-node), but when I run rosrun urg_node urg_node _serial_port:=/dev/ttyACM1 it crashes after the connection to the device:

[/urg_node: INFO] [1599296638.701332302] : Connected to serial device with ID: H1102605
[/urg_node:DEBUG] [1599296639.596760024] : Unable to update reconfigure limits. Not Ready.
[1]    30627 segmentation fault (core dumped)  rosrun urg_node urg_node _serial_port:=/dev/ttyACM1

However, if I clone this repository and build myself the package it works smoothly :

[/urg_node: INFO] [1599295313.022726465] : Connected to serial device with ID: H1102605
[/urg_node: INFO] [1599295314.117096183] : Streaming data.
  • OS : Ubuntu 20.04
  • Device : URG-04LX-UG01
  • urg_node version: 0.1.14
  • urg_c version: 1.0.405 (from APT ros-neotic-urg-c)
  • GCC version: 9.3.0-10ubuntu2

GDB info:

Starting program: /opt/ros/noetic/lib/urg_node/urg_node 
[Thread debugging using libthread_db enabled]
Using host libthread_db library "/lib/x86_64-linux-gnu/libthread_db.so.1".
[New Thread 0x7ffff4981700 (LWP 32503)]
[New Thread 0x7fffeffff700 (LWP 32504)]
[New Thread 0x7fffef7fe700 (LWP 32505)]
[New Thread 0x7fffeeffd700 (LWP 32506)]
[/urg_node: INFO] [1599297220.564435432] : Connected to serial device with ID: H1102605
[New Thread 0x7fffee7fc700 (LWP 32509)]
[New Thread 0x7fffedffb700 (LWP 32510)]

Thread 7 "urg_node" received signal SIGSEGV, Segmentation fault.
[Switching to Thread 0x7fffedffb700 (LWP 32510)]
0x00007ffff7c566bd in std::runtime_error::runtime_error(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&) () from /lib/x86_64-linux-gnu/libstdc++.so.6
(gdb) backtrace
#0  0x00007ffff7c566bd in std::runtime_error::runtime_error(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&) () from /lib/x86_64-linux-gnu/libstdc++.so.6
#1  0x00007ffff79522b5 in urg_node::URGCWrapper::start (this=0x7fffdc0010a8) at ./src/urg_c_wrapper.cpp:870
#2  0x0000000000000000 in ?? ()

Adjust scan publish frequency

Hi! I'm having some trouble in Rviz related to the difference in the timestamp between /odom and /laser (/hokuyo in my case) reference frames. I know that the problem is related to this because when I set "time_offset" and "skip" options I am able to visualize the scan point cloud for a short time, until I get the error "lookup would require extrapolation into the future". This is because of the urg_node is publishing a topic in the /laser ref frame faster than the time required to publish /odom.
I don't want to create tf_listeners or tf_filters nodes, is there a possibility to set the publishing frequency of the /scan topic of the urg_node? Thanks in advance for helping

urg_node config does not match hokuyo_node config

I'm having issues using urg_node in place of hokuyo_node with hector_slam. My best guess is differences in config which can be noted by comparing URGConfig.dox to HokuyoConfig.dox. Config can be changed for the hokuyo at Hokuyo.cfg (if I'm remembering correctly) but there is no urg.cfg that I can find. Where can I change config for the urg_node to see if getting the urg set up the same as the hokuyo will resolve issues?

I have posted this on answers.ros but I'm getting no responses.

urg_node error

When I try to run roslaunch
It gives error
[ INFO] [1508379073.935796538]: Connected to network device with ID: H1630569
[ INFO] [1508379073.948971760]: Starting calibration. This will take a few seconds.
[ WARN] [1508379073.949088653]: Time calibration is still experimental.
[ INFO] [1508379074.950741097]: Calibration finished. Latency is: -0.0210.
terminate called after throwing an instance of 'std::length_error'
what(): basic_string::_M_create

Any idea what is that?

What could cause an "Abnormal status" error?

Hello,

On Ubuntu 14.04 with ros-indigo, I'm seeing a weird "Abnormal status" error. Here's a screenshot of rqt_robot_monitor -

Physically, the LIDAR seems to be fine. The LIDAR's LED panel doesn't show any error codes, and I receive data points as expected -

What could cause the URG driver to send out this error?

Thanks!

Time calibration not working on UST 20lx

The driver output is this:

[ INFO] [/base_laser] [1413847603.907442318]: Connected to network device with ID: H0000108
[ INFO] [/base_laser] [1413847603.982513060]: Starting calibration. This will take a few seconds.
[ WARN] [/base_laser] [1413847603.982561649]: Time calibration is still experimental.
[ INFO] [/base_laser] [1413847604.508127111]: Calibration finished. Latency is: -402.6954.
[ INFO] [/base_laser] [1413847604.527380193]: Streaming data.

After that the timestamp of the laser messages is about 402s off of ROS time.

udev rule don't work

Hi, in the wiki documentation you give a tips usign udev and getID, but for some people it don't work. I found the problem : udev run a root and don't have the opt/ros/distro/lib in the shared library.
To add it you must run ldconfig as root so :
$ su

ldconfig /opt/ros/melodic/lib

I was in the /opt/ros/melodic/lib directory when I did the command but it seem not to be necessary
It works for me.

ROS 2 support

There is a fork of urg_node (https://github.com/bponsler/urg_node) that ports urg_node to ROS 2. @Karsten1987 had a great suggestion of trying to push the ros2 changes upstream so everything is located here.

What are your thoughts on doing this and how best to go about doing it? There are several repos that had to be ported and the messages were split it to be a separate package.

Request on releasing on jade

Recent bloom-release script helps a lot, it automatically estimate necessary information from hydro information. So it should be super easy

Noetic release

Will this package be released for Noetic anytime soon?

max & min distance parameters are needed

As max&min angle values of scan data can be set by giving ros parameter values, I wonder if you have any plan to implement the max&min distance value setting function.

Jaehyun

uam-05lp stops publishing data

I've been running into an issue with urg_node stops publishing data without spitting out any errors when running with uam-05lp.

Would a bandwidth issue cause something like this? I have 3 urg-20lx and 2 uam-05lp on the machine. the uam-05lp are the only ones this seems to happen with.

In order for it to start back up again, i need to kill and restart the uam-05lp rosnodes.

Any thoughts as to what might be going on? Thanks!

Error count exceeded limit

Hi all!
I'm using Hokuyo UST 20LX for my navigation robot project but sometimes i got this error: "ERROR count exceeded limit, reconnecting". When the error happen the robot loses it's position. Why this error happen and how can i fix this. Many thanks.

Could not open network Hokuyo

When I try to run
rosrun urg_node urg_node _ip_address:=192.168.0.10,
it outputs
[ERROR] [1578732088.876290125]: Error connecting to Hokuyo: Could not open network Hokuyo: 192.168.0.10:10940 could not open ethernet port.
I am sure the ip address 192.168.0.10 could be pinged.
And I also tried to modify the local ip address to 192.168.0.XXX, netmask 255.255.255.0, it could not work either.
Do some buddies give some help?

Additionally, my configurations is given follows:

  • Hokuyo ust-10lx
  • ROS melodic

Cannot get Hokuyo status

I am using UAM-05LP, it has a lcd screen which give the area number, the warning status and the error code. I would like to access these value via the driver. Fortunately is already implemented it is the updateStatus which send an AR00 and a DL00 request to the Hokuyo. To publish this status it is needed to call a service which will call these function and publish in latched mode.
However, when I listen to this topic the value a messed up meaning it did not match the reality. it more or less somewhere in the past. Moreover it get updated only if an error triggers the Hokuyo.
I sniffed the serial com between Hokuyo and the official Hokuyo software it looks like only AR00 is sent to be able to retrieve the laser status but in the final installation I use ethernet communication but I do not think that the request change if it is USB or ethernet.

Melodic release please!

Sure would be nice to keep up with the ROS releases. Melodic is the stable long term release now.

ROS2 Maintainer?

I notice @tonybaltovski is still listed as maintainer for ROS2 package.xml, but hasn't really been involved in the ROS2 side of things. @clalancette has recently done the last release - are you planning to maintain this going forward or are you looking for a maintainer? I'm happy to be a maintainer of this package in ROS2 (debs/master are currently broken - I've opened PRs to fix that).

All I really would need is a thumbs up - I've already got permissions on ros-drivers since I maintain a few other repos here.

CMake Error

When I copied urg_node-groovy-devel package into my catkin_ws/src folder and tried to compile it, I got the following errors:

CMake Error at /opt/ros/groovy/share/catkin/cmake/catkinConfig.cmake:75 (find_package): Could not find a configuration file for package urg_c.
Set urg_c_DIR to the directory containing a CMake configuration file for urg_c. The file will have one of the following names:
urg_cConfig.cmake
urg_c-config.cmake
Call Stack (most recent call first): urg_node-groovy-devel/CMakeLists.txt:7 (find_package)
CMake Error at /opt/ros/groovy/share/catkin/cmake/catkinConfig.cmake:75 (find_package): Could not find a configuration file for package laser_proc.
Set laser_proc_DIR to the directory containing a CMake configuration file for laser_proc. The file will have one of the following names:
laser_procConfig.cmake
laser_proc-config.cmake
Call Stack (most recent call first): urg_node-groovy-devel/CMakeLists.txt:7 (find_package)
-- Configuring incomplete, errors occurred! Invoking "cmake" failed

Could you please tell me what is going wrong? And How can I solve this?

Update maintainers?

I believe that @chadrockey hasn't had much time for maintenance lately. @tfoote, I would be interested in maintaining this since it is the default laser on the Ridgeback.

ros parametor angle_min&angle_max are not valid

I tried using with reference to "urg_lidar.launch", and it seems that angle_min and angle_max are not effective.

<launch>
  <node name="urg_node" pkg="urg_node" type="urg_node" output="screen">
    <param name="angle_min" value="-1.5707963"/>
    <param name="angle_max" value="1.5707963"/>
  </node>
</launch>

Looking at urg_node_driver.cpp
, there are no ros parametor, angle_min" and "angle_max", in pnh_.param.

urg_node failed on Intel NUC / swapping issue

I am facing a problem running urg_node with an Hokuyo 10LX on an embedded computer.

Here is the environment, I am running ROS kinetics on Ubuntu 16.06LTS on an INTEL NUC 5ITRYH with 8GO DDR4 and SSD 200Go.

When I start urg_node, it works perfectly but as soon as I open a terminal for instance, I got the following warning:

process[urg_node-2]: started with pid [5099] [ INFO] [1511171038.966908047]: Connected to network device with ID: H1642740 [ INFO] [1511171038.979387775]: Starting calibration. This will take a few seconds. [ WARN] [1511171038.979419672]: Time calibration is still experimental. [ INFO] [1511171039.982890964]: Calibration finished. Latency is: -0.0208. [ INFO] [1511171039.998174108]: Streaming data. [ WARN] [1511171050.027225044]: Could not grab single echo scan. [ERROR] [1511171051.692534732]: Error count exceeded limit, reconnecting. [ INFO] [1511171053.704590758]: Connected to network device with ID: H1642740 [ INFO] [1511171053.716937334]: Starting calibration. This will take a few seconds. [ WARN] [1511171053.717063649]: Time calibration is still experimental. [ INFO] [1511171054.718481924]: Calibration finished. Latency is: -0.0212. [ INFO] [1511171054.734664754]: Streaming data.

And it if I start a slam with RVIZ, i finally ended up with:

[ WARN] [1511170394.929138196]: Time calibration is still experimental. [FATAL] [1511170395.851344341]: Could not calibrate time offset: Cannot get scan to measure time stamp offset. [urg_node-2] process has died [pid 4389, exit code -5, cmd /home/fabrice/catkin_demo_lidar_ws/devel/lib/urg_node/urg_node __name:=urg_node __log:=/home/fabrice/.ros/log/c61d770e-cdd5-11e7-b1f1-94c691132292/urg_node-2.log]. log file: /home/fabrice/.ros/log/c61d770e-cdd5-11e7-b1f1-94c691132292/urg_node-2*.log

It looks like, at first glance, that the NUC takes too much time to swap between tasks but I am I have to admit that I am surprise.

I tried to change the priority between tasks with renice, but without success.

The same programs (urg_node, hector slam...) work perfectly on my laptop with ROS kinetics/Ubuntu 16.04LTS

Does anybody had the same experience and can share how to handle it?

Thank you very much

Fabrice

No executable found with `ros2 run urg_node urg_node` command on ROS 2 dashing

Describe the bug

I ran a command ros2 run urg_node urg_node on ROS2 dashing environment.
That results the message No executable found.

Environments

  • OS: Ubuntu 18.04
  • Software Version: latest of ros2-devel branch (cb0efdc)
  • LiDAR: URG-04LX-UG01

To Reproduce

  1. Clone this repo locally and checkout to ros2-devel branch
  2. Run colcon build --symlink-install then run source install/setup.zsh
  3. Run ros2 run urg_node urg_node
  4. See error No executable found

Expected behavior

The urg_node will be running then publishing /scan topics.

Additional context

The correct executable node name is urg_node_driver that CMakeLists.txt shows.

urg_node/CMakeLists.txt

Lines 54 to 56 in cb0efdc

rclcpp_components_register_node(urg_node
PLUGIN "urg_node::UrgNode"
EXECUTABLE urg_node_driver)

So, I ran a command ros2 urg_node urg_node_driver but no /scan topic published.
This problem same as #66.

Problems with Hokuyo 04LX

Hi,
I'm trying to use the URG-04LX sensor, with the new urg_node. When I try to connect I get:
[ERROR] [1481563459.541562213]: Unknown error connecting to Hokuyo

While, if I'm using the old hokuyo_node, the sensor just work correctly.
Also, if I try to connect using the urg_node after killing the hokuyo node, the new node works.

I've tried with different parameters and disabling/enabling calibration

Also I've updated the sensor to the latest version (Ver3.4.03) without success.

Restarting the sensor doesn't work, as it enters in a loop of error states.

rosrun urg_node urg_node
[ INFO] [1481562698.401506634]: Connected to serial device with ID: receive error.
[ INFO] [1481562698.528700165]: Streaming data.
[ WARN] [1481562700.164722195]: Could not grab single echo scan.
[ERROR] [1481562706.575695889]: Error count exceeded limit, reconnecting.
[ INFO] [1481562710.064727728]: Connected to serial device with ID: receive error.
[ERROR] [1481562710.165523797]: Tried to advertise a service that is already advertised in this node [/urg_node/set_parameters]
[ INFO] [1481562710.187120186]: Streaming data.
[ WARN] [1481562711.828255910]: Could not grab single echo scan.
[ERROR] [1481562718.239361077]: Error count exceeded limit, reconnecting.
[ INFO] [1481562721.728254595]: Connected to serial device with ID: receive error.
[ INFO] [1481562721.849091216]: Streaming data.
[ WARN] [1481562723.491826093]: Could not grab single echo scan.
[ERROR] [1481562729.903079945]: Error count exceeded limit, reconnecting.
[ INFO] [1481562733.392075814]: Connected to serial device with ID: receive error.
[ERROR] [1481562733.492562034]: Tried to advertise a service that is already advertised in this node [/urg_node/set_parameters]
[ INFO] [1481562733.516776507]: Streaming data.
[ WARN] [1481562735.155774107]: Could not grab single echo scan.
[ERROR] [1481562741.566833458]: Error count exceeded limit, reconnecting.

ARM vs X86

Running ROS Indigo on ARM (Odroid XU4) i cannot get any data from the scanner:

[ INFO] [1454179348.727796454]: Connected to network device with intensity and ID: H1513161
[ INFO] [1454179348.801499047]: Streaming data.
[ WARN] [1454179350.111422222]: Could not grab single echo scan.
[ERROR] [1454179350.893385932]: Error count exceeded limit, reconnecting.
[ERROR] [1454179353.900147769]: Unknown error connecting to Hokuyo

While, the same scanner, same network, same settings, works fine on the X86.

Any insight on this ?

Add support for use_unsafe_settings

Port the use_unsafe_settings functionality from the hokuyo_node.

Use unsafe settings allowed for a workaround to the UTM-30 (USB version) glitch.

How do call "UrgNode::run()" in latest code on ros2-devel branch

I'm trying to test "LaserScan Visualization" following this link(https://index.ros.org/p/urg_node/#dashing), but it doesn't work. (use UTM-30LX-EW)
The result of debugging, "UrgNode::run()" is not called.(I set break point by GDB but not stopped, and not called from anywhere in source code)

With refering to commit log, I guess it seems disappeared when "urg_node" modified to component node.
(ad15f23)

I added "UrgNode::run()" caller, then it works.

In latest code on ros2-devel branch, How do call "UrgNode::run()"?
"UrgNode::run()" caller is not necessary?

I'd appreciate it if someone could answer my questions.

hokuyo UST-10lx LiDAR data not consistent

Hi: I am using hokuyo UST-10LX LiDAR on my robot moving in an indoor environment. I found the data is not consistent. At one moment, the data is like the left part of the image below:

http://artlystyles.com/tmp/pp.JPG

The robot is the green bar in the image, moving at a slow speed, about 10mph, toward the bottom of the image. Yellow dots are LiDAR points. One side of the wall is pointed by the red array and is at the correct location in this image. The wall is kind of at the back of the robot. The LiDAR has 270 degree view.

At the next moment, however, the data is like the right part of the image above. The wall location is too close to the robot and is totally wrong.

Anyone knows why?

Compiling error

Hello,
When I tried to build urg_node, I got this error:

Errors << urg_node:make /home/kubot/catkin_ws/logs/urg_node/build.make.000.log
/home/kubot/catkin_ws/devel/.private/urg_node/lib/liburg_node_driver.so: undefined reference to boost::this_thread::hidden::sleep_until(timespec const&)' /home/kubot/catkin_ws/devel/.private/urg_node/lib/liburg_node_driver.so: undefined reference to boost::this_thread::hidden::sleep_for(timespec const&)'
collect2: error: ld returned 1 exit status
make[2]: *** [/home/kubot/catkin_ws/devel/.private/urg_node/lib/urg_node/urg_node] Error 1
make[1]: *** [CMakeFiles/urg_node.dir/all] Error 2
make: *** [all] Error 2

What could be the reason? Boost version or what?

connecting multiple hokuyo UTM-30LX

hey guys, i am having trouble connecting multiple hokuyo sensors.
I tried various type of launch files.
down below isthe slightly modified default launch file

launch

group ns="left"
node name="urg_node" pkg="urg_node" type="urg_node" output="screen"
param name="ip_address" value=""/
param name="serial_port" value="/dev/ttyACM0"/>
param name="serial_baud" value="115200"/>
param name="frame_id" value="laser"/>
param name="calibrate_time" value="false"/>
param name="publish_intensity" value="true"/>
param name="publish_multiecho" value="false"/>
param name="angle_min" value="-1.5707963"/>
param name="angle_max" value="1.5707963"/>
remap from="scan" to="left_scan"/>
/node>
/group>

group ns="right">
node name="urg_node" pkg="urg_node" type="urg_node" output="screen">
param name="ip_address" value=""/>
param name="serial_port" value="/dev/ttyACM1"/>
param name="serial_baud" value="115200"/>
param name="frame_id" value="laser"/>
param name="calibrate_time" value="false"/>
param name="publish_intensity" value="true"/>
param name="publish_multiecho" value="false"/>
param name="angle_min" value="-1.5707963"/>
param name="angle_max" value="1.5707963"/>
remap from="scan" to="right_scan"/>
/node>
/group>

</launch

(I have no idea why it doesn't show launch file correctly so I erased "<")

then second one runs for a instance and makes an error. like down below

[ INFO] [1511419973.276698778]: Streaming data.
[ WARN] [1511419974.989649912]: Could not grab single echo scan.
[ERROR] [1511419978.506572805]: Error count exceeded limit, reconnecting.
[ERROR] [1511419984.335448520]: Error connecting to Hokuyo: Could not initialize Hokuyo:
not connected.
[ERROR] [1511419996.835947865]: Error connecting to Hokuyo: Could not initialize Hokuyo:
not connected.

Any ideas??

Startup failure

Hey,

I used a urg-04lx-ug01 on a mobile robot. I added urg_node in startup application in ubuntu 16.04, and added chmod 666 /dev/ttyACM0 in the script and sleep for 2 seconds before launching the node. However, the urg lidar cannot be opened sometimes, one failure out of ten boots. When it failed, I could see /dev/ttyACM0, but was not able to launch the node manually. All I need to do is unplug the usb cable and replug it, and then the lidar resume working.

Is this a driver issue or a hardware issue? How can I avoid this issue?

Thanks in advance!

The new AR00 function breaks urg_node

Hello,

It seems that the recent commit "Add getAR00 status command" breaks urg_node, at least using my version of the UST-20LX over ethernet. I suspect #29 (maybe) and http://answers.ros.org/question/261367/problem-with-running-urg_node-with-ust-20lx/ (almost surely) are issues related to this problem.

How to reproduce (tried on 3 different computers, with the same Hokuyo unit): on a fresh install of Kinetic on 16.04, clone urg_c, urg_node and laser_proc, then catkin_make. (I got the same problem with the apt install.)
The command:
rosrun urg_node urg_node _ip_address:="192.168.0.10"
fails with the following message:
Connected to network device with intensity and ID: H1528xxx
terminate called after throwing an instance of 'std::length_error'
what(): basic_string::_M_create
Aborted

On Ubuntu 14, I get the same message with basic_string::_S_create instead of M.

Temporary f0ix: in file urg_node_driver.cpp, comment the line (number 466):
// Before starting, update the status
updateStatus();

My comments:
Using Wireshark, it seems the sensor does not reply to the AR00 command, which causes the call in line 555 of urg_c_wrapper.cpp
read_len = read(sock, recvb + total_read_len, expected_read - total_read_len);
in URGCWrapper::sendCommand to return -1. However, since read_len is unsigned, it loops back to MAX_INT and so the verification:
if (read_len <= 0)
is never triggered, causing a crash on the line:
std::string recv_header(recvb, read_len);

Looking at the Hokuyo documentation, I see no reference to an "AR" command, which could explain the lack of response from the sensor.

Hope this will help

ros2 urg_node parameter file

installed sudo apt install ros-foxy-urg-node.
ros2 run urg_node getID works fine and returns ID.
ros2 run urg_node urg_node_driver __params:=/opt/ros/foxy/share/urg_node/launch/urg_node_ethernet.yaml

returns can't find serial port 115200 /dev/cu.usbmodemxxxxx

I've set the ip address in the yaml file and it just doesent seem to be reading the paramtere file anywere. Any idea on why its not readin the parameter file and using the IP address of the hokuyo (since thats the model I have) ?

Tried to git clone and build, but colcon build comes out with a bunch of catkin (ros1) type of errors.

Thanks for any assistance. Apologies if this is an idiot request. I've read everything I could find and search upon. Thanks

urg_node_ethernet.yaml file :

urg_node:
  ros__parameters:
    angle_max: 3.14
    angle_min: -3.14
    ip_address: "192.168.1.68"
    ip_port: 10940
    serial_baud: 57600
    laser_frame_id: "laser"
    calibrate_time: false
    default_user_latency: 0.0
    diagnostics_tolerance: 0.05
    diagnostics_window_time: 5.0
    error_limit: 4
    get_detailed_status: false
    publish_intensity: false
    publish_multiecho: false
    cluster: 1
    skip: 0

getID is not created

I've installed the urg_node package using apt-get and manually, and in either case it seems as though getID.cpp is not compiled into an executable. I am running ROS Hydro in Ubuntu 12.04LTS.

Thanks!

No scan topic being published.

I am trying to get the Hokuyo UTM-30LX-EW working with my robot but when ever i try to run the lidar, i dont see any scan topic being published. I have /echoes /first /last /urg/update parameters and others being published but no /scan.

Any help ??

Problem with Hokuyo UBG-04LX-F01

It seems that the current version of urg_node does not work with UBG-04LX-F01 on Kinetic/Ubuntu 16.04, but it does work when reverting to commit 51d33ea from Dec 9, 2016. Could that be a problem?

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    ๐Ÿ–– Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. ๐Ÿ“Š๐Ÿ“ˆ๐ŸŽ‰

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google โค๏ธ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.