Gonçalo,<br><br>I've done some work with sonars. The answer to your question is going to depend on what exactly you want the sonars to do and their characteristics. If you want precise navigation around obstacles in the world, sonars may be a bit too fuzzy without some sort of probabilistic fusion in order to pinpoint obstacles. If you just want close range obstacle detectors, they definitely can help there.<div>
<br></div><div>The largest challenge we (<a href="http://mobilerobots.case.edu">mobilerobots.case.edu</a>) had with sonars was twofold: <br><ol><li>They can mark a lot of the space we want to traverse at longer ranges (3-4 meters) with a 20-30 degree beam angle</li>
<li>LIDAR and SONAR may not agree and so marking and clearing got complicated.</li></ol>The first was improved by switching to sonars with narrower beam widths and/or not using the sonar out to its max distance. The second is actually the main reason we cared about sonar - while they aren't as precise as a laser, they can detect glass, black objects and objects outside the horizontal plane of our laser scanner. This makes them ideal close range obstacle detectors to prevent the robot damaging anything or injuring someone.<div>
<br></div><div>In order to overcome the marking/clearing thing, I ended up feeding in both the LIDAR and sonar as LaserScan messages (quicker than doing PointClouds myself) at different z heights. By setting the min and max heights for each sensor, I was able to get the voxel grid costmap to essentially maintain a LIDAR layer and a sonar layer. Because it does a 2D projection for the planner, this worked nicely for my use case. Definitely a bit hacky though...</div>
<div><br></div><div>- Eric<br><br>2010/7/7 Gonçalo Cabrita <<a href="mailto:goncabrita@gmail.com">goncabrita@gmail.com</a>>:<br>> Thanks for your help on this matter Eitan and Eric!<br>> I'll run a few experiments with various settings and report back the results<br>
> soon.<br>> Also on this subject, some of our Roombas are equipped with sonar arrays of<br>> 5 sonars arranged in<br>> -PI/2 -PI/4 0 PI/4 PI/2<br>> Do you think it would be a viable option to feed the sonar data into the nav<br>
> stack in the form of a point cloud? Or is it not even worth trying as the<br>> amount of data produced is extremely small when compared to that of a laser<br>> range finder?<br>> Thanks,<br>> Gonçalo Cabrita<br>
> ISR - University of Coimbra<br>> Portugal<br>> On Jul 7, 2010, at 7:08 PM, Eitan Marder-Eppstein wrote:<br>><br>> Goncalo,<br>><br>> There are a few basic things that you can do to help with performance:<br>
><br>> 1) You can increase the resolution of the costmaps. Since a Roomba is so<br>> small, even 10cm resolution should probably be sufficient for navigation.<br>> See the resolution parameter of the costmap:<br>
> <a href="http://www.ros.org/wiki/costmap_2d#Map_management_parameters">http://www.ros.org/wiki/costmap_2d#Map_management_parameters</a><br>><br>> 2) You can decrease the update rate of the costmaps from 5Hz to something<br>
> lower depending on your tolerance for seeing an obstacle. At 5Hz, it'll take<br>> about 1/5th of a second to react to an obstacle, at 3Hz 1/3rd of a second,<br>> etc. See the update_frequency parameter for the costmap:<br>
> <a href="http://www.ros.org/wiki/costmap_2d#Rate_parameters">http://www.ros.org/wiki/costmap_2d#Rate_parameters</a>.<br>><br>> 3) You can control the Roomba at a lower rate... maybe something like 10Hz<br>> instead of 20Hz. For that you can set the controller_frequency parameter on<br>
> move_base: <a href="http://www.ros.org/wiki/move_base#Parameters">http://www.ros.org/wiki/move_base#Parameters</a>.<br>><br>> Hope this helps,<br>><br>> Eitan<br>><br>> 2010/7/7 Gonçalo Cabrita <<a href="mailto:goncabrita@gmail.com">goncabrita@gmail.com</a>><br>
>><br>>> Hi everyone!<br>>> Here at the lab we use Roomba robots with Eee PCs on top. The Eee PCs have<br>>> a single core Intel Atom processor, not the quickest thing around! Each<br>>> Roomba is also equiped with an Hokuyo laser. <br>
>> So I've recently been playing around with the ROS nav stack. I've tried to<br>>> make it as simple as possible according to the various tutorials and mailing<br>>> list msgs I've came across with, however I'm always getting a warning that<br>
>> it is running below the 20Hz frequency. It is also noticeable the fact that<br>>> the robot does not move properly, and eventually crashes.<br>>> Previously I experimented the same setup on an Erratic robot with a<br>
>> Celeron, and although it was taking pretty much all of the processor to run<br>>> the nav stack, it was able to move pretty well around the lab according to<br>>> the commands I was issuing from rviz.<br>
>> So my question is, how can I use the nav stack in its simplest form, in<br>>> order to have it running smoothly on the Eee PCs?<br>>> I'm attaching the .yaml files I'm using for configuring the nav stack.<br>
>> Thanks in advance!<br>>> Gonçalo Cabrita<br>>><br>>><br>>> _______________________________________________<br>>> ros-users mailing list<br>>> <a href="mailto:ros-users@code.ros.org">ros-users@code.ros.org</a><br>
>> <a href="https://code.ros.org/mailman/listinfo/ros-users">https://code.ros.org/mailman/listinfo/ros-users</a><br>>><br>><br>> _______________________________________________<br>> ros-users mailing list<br>
> <a href="mailto:ros-users@code.ros.org">ros-users@code.ros.org</a><br>> <a href="https://code.ros.org/mailman/listinfo/ros-users">https://code.ros.org/mailman/listinfo/ros-users</a><br>><br>><br>> _______________________________________________<br>
> ros-users mailing list<br>> <a href="mailto:ros-users@code.ros.org">ros-users@code.ros.org</a><br>> <a href="https://code.ros.org/mailman/listinfo/ros-users">https://code.ros.org/mailman/listinfo/ros-users</a><br>
><br>><br><br></div></div>