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

gmapping and inverted (upside-down) laser

asked 2011-11-15 04:57:30 -0600

arebgun gravatar image

updated 2012-09-21 11:42:07 -0600

Ryan gravatar image

Hello folks, I am having trouble using gmapping with my robot which has an upside-down laser. Last time I was building a map was probably in cturtle and it worked just fine. But in electric it seems that gmapping doesn't detect that the laser is inverted.

Looking at gmapping node source I can see that it uses "angle_increment" value of the LaserScan message to determine if the laser is inverted, e.g. if it is negative then the laser is upside-down. I did echo the messages coming from the laser and angle_increment is indeed positive, and the map is mirrored.

In hokuyo node source code angle_increment parameter is populated from the raw scan message coming from the laser driver, which wouldn't know anything about how the laser is mounted.

Am I missing something or did something change/break from previous release in either gmapping or hokuyo_node?

edit retag flag offensive close merge delete

5 Answers

Sort by ยป oldest newest most voted
0

answered 2011-11-15 05:52:17 -0600

arebgun gravatar image

updated 2012-01-20 05:08:47 -0600

Ok, there was definitely a bug in gmapping node, ticket with a patch is here.

Update: I have uploaded our robot's bag file that can be used to test proposed patches to gmapping, use this command to run gmapping: rosrun gmapping slam_gmapping scan:=base_scan/scan _odom_frame:=odom_combined. The laser in use is a Hokuyo URG-04LX mounted upside down on the front of the robot.

edit flag offensive delete link more
0

answered 2012-02-28 14:05:16 -0600

Khiya gravatar image

Hello, I've been having the same sort of trouble as was originally posted - I've read this thread through but I'm new enough to ROS that I'm not sure what I ought to do. Here's my situation:

I'm using an inverted Hokuyo scanner at the center front of my robot, with ROS electric and an ASUS netbook. I've tried setting the transform to show gmapping that the laser is inverted by editing the transform from the laser to the base. I've tried changing yaw, pitch, and roll by 3.14 and by 180, I've tried changing them all separately and in combinations, all to no avail. I'm not sure from the patches listed here how to approach this - would someone be so kind as to give me a summary of guidelines?

Thanks,

Khiya

edit flag offensive delete link more

Comments

Have a look at my answer to this question: http://answers.ros.org/question/3598/gmapping-and-inversion-hokuyo-dont-work You have to check out the GMapping sources and then apply this patch: https://code.ros.org/trac/ros-pkg/attachment/ticket/5250/gmapping_inverted_laser_new.patch

Ben_S gravatar image Ben_S  ( 2012-02-28 21:41:29 -0600 )edit
0

answered 2011-11-15 09:33:21 -0600

Ben_S gravatar image

updated 2011-11-24 19:18:15 -0600

Did you publish an inverted tf for you laserscanner like suggested here: http://ros.org/wiki/gmapping#Parameters (note for ~inverted_laser)?

The patch you applied removed code that was explicitly added to handle upright laserscanners, that report the scans in an inverted order. Ticket: https://code.ros.org/trac/ros-pkg/ticket/4984

My guess would be a problem with your transform that does not reflect the correct (upside-down) position of your laserscanner. The sign of the angle_increment should only be used to check the scan-order (clockwise or ccw), but not to determine if the laser is inverted.


Update (18.11.2011): I think i have found the problem why our solution didnt work for you. In line 541 of https://code.ros.org/trac/ros-pkg/browser/stacks/slam_gmapping/tags/slam_gmapping-1.2.4/gmapping/src/slam_gmapping.cpp#L541">slam_gmapping.cpp the plain scan.angle_min is used. To get valid results with an upside-down scanner you should use the transformed angle_min from line 338. I am however not sure if this will break mapping for scanners which are not centered (angle_min == -angle_max) but are rotated along the z-axis (for example are looking to the left side of the robot).


Update (25.11.2011): I have uploaded a bag file and our gmapping launchfile here. These are the results: pre-patch and post-patch-5250

When you post your bag, I will try to implement my suggested solution from the last edit. Maybe we can get it to work under all circumstances.

edit flag offensive delete link more

Comments

My transforms are all correct, and an inverted CW laser basically becomes a CCW laser. The current gmapping node doesn't really work with upside-down CW lasers. Also, inverted_laser parameter was removed from gmapping_node since Diamnodback.
arebgun gravatar image arebgun  ( 2011-11-15 14:21:04 -0600 )edit
Could you eventually upload a bag file of your Bot driving around a bit so that we can help find a patch that suites all of us?
Ben_S gravatar image Ben_S  ( 2011-11-21 05:33:30 -0600 )edit
Will do, should get around to it next week or so.
arebgun gravatar image arebgun  ( 2011-11-22 00:55:30 -0600 )edit
0

answered 2011-11-15 09:32:35 -0600

felix k gravatar image

updated 2011-11-18 02:15:01 -0600

As far as I understood this (my colleague and I did this patch), gmapping does not use the angle_increment to check whether the laser is inverted, but uses the transform information. The laser nodes send their data regardless of the laser placement, as this is done through tf. (And I cannot see an inverting option in hokuyu_node).

Wiki proove: link:http://ros.org/wiki/gmapping#Parameters Did you set your transform correct?

The angle_increment-check is for those laser nodes which send their scan data with an negative step increment, as this has to be reverted for the gmapping lib, which cannot handle a negative increment. At least that's what the slam_gmapping.cpp comment says.

So if you modified gmapping, and the behaviour changed, I doubt it will work everywhere else.


Your patch isn't working with our laser (which btw seems to be a CW one), it's like it was before our patch. As the laser message description (http://www.ros.org/doc/api/sensor_msgs/html/msg/LaserScan.html) says, its usual view is CCW, as the Z axis usally points upwards (http://ros.org/wiki/gmapping#Parameters says the same). The real laser direction is unimportant for that, but some lasers are CW, and the rod4-author didn't want to reverse the range data, so the range array is going from a positive min to a negative max, hence the negative inc, which results in from left to right, CW. Your message should be the exact opposite, you may test a echo for that.

I couldn't find the part where gmapping checks for the transform (IMO roll has to be like 3.14..) but you should check that. In 3 lines from 414 on it implies that variable as the flag to check for invertion, but I cannot see this variable being set in dependence of a tf condition. Maybe you can find the part, or we have to ask the authors.

edit flag offensive delete link more

Comments

You are right, it is supposed to use transform information to figure out if the laser is mounted upside-down, but it really doesn't. All it does is change the sign on min/max limits, e.g. if my laser is upside-down my min will become positive and max will become negative (in case of Hokuyo laser).
arebgun gravatar image arebgun  ( 2011-11-15 14:15:46 -0600 )edit
You are also correct that my patch in its current form will break CCW laser (like the ROD4), although it fixes it for all CW lasers (like Hokuyo URG) :) I think I need just a small correction to make it work properly for both. Do you still have access to ROD4 to test it out?
arebgun gravatar image arebgun  ( 2011-11-15 14:18:19 -0600 )edit
I posted an updated patch. Looking at ROD4 source I think it should work for both CW and CCW, inverted and not.
arebgun gravatar image arebgun  ( 2011-11-15 14:24:42 -0600 )edit
Your patch isn't working with our laser, see my edit above.
felix k gravatar image felix k  ( 2011-11-18 02:15:11 -0600 )edit
Oh, I forgot: If you are using a common or compatible laser with the common node, there is no chance to detect a inversion only from the laser message content, so you have to either twist the message data or get the tf condition to work.
felix k gravatar image felix k  ( 2011-11-18 02:18:53 -0600 )edit
0

answered 2011-11-23 12:16:57 -0600

updated 2011-11-24 11:56:33 -0600

Patch 5250 works for me: I have an inverted SICK, set the 'inverted' parameter to true in sicktoolbox wrapper, my transform has 0 0 0 on roll/pitch/yaw.

File is here, Min angle is 1.5707, Max angle is -1.5707, increment is -0.01745

edit flag offensive delete link more

Comments

Would it be possible for you to post a small bag file? I will try to provide a bag file of our robot too, but this may have to wait until monday. Which parameters does your laser scan contain for min-angle, max-angle and angle-increment?
Ben_S gravatar image Ben_S  ( 2011-11-23 19:18:14 -0600 )edit
No worries, edited answer contains a link.
Liz Murphy gravatar image Liz Murphy  ( 2011-11-24 11:57:38 -0600 )edit
Are you sure you applied the patch correctly? This are the results i am getting with your bag pre-patch (latest version from svn): http://bit.ly/sauuMG and with patch 5250: http://bit.ly/s41tKq You may decide for yourself which one is more similar to your lab. :-)
Ben_S gravatar image Ben_S  ( 2011-11-24 18:57:18 -0600 )edit
Yes, apologies - it's the pre-patch version that works!
Liz Murphy gravatar image Liz Murphy  ( 2011-11-27 14:17:10 -0600 )edit
Thanks for the clarification. Since you really have an inverted laser (while our does only rotate cw) could you try the other variant gmapping offers? Set inverted in the sick-wrapper to false and invert your laser through tf (set roll to pi/2) and provide another bag file of that? thanks a lot!
Ben_S gravatar image Ben_S  ( 2011-11-27 18:43:21 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2011-11-15 04:57:30 -0600

Seen: 4,090 times

Last updated: Feb 28 '12