[ros-users] Navigation Stack performance
Eric Perko
wisesage5001 at gmail.com
Thu Jul 8 16:14:32 UTC 2010
Gonçalo,
Glad you were able to get the nav stack functioning on the EEE PCs.
For the problem backing into a wall, can you display the paths in RVIZ along
with the costmaps? Some details here:
http://www.ros.org/wiki/navigation/Tutorials/Using%20rviz%20with%20the%20Navigation%20Stack
I'm wondering if, for some reason, the global planner is just not planning
around the wall - that could cause the sort of repetitive behavior you are
seeing. If the plan output by the global planner is actually good looking,
then there are other problems to deal with.
- Eric
2010/7/8 Gonçalo Cabrita <goncabrita at gmail.com>
> Hi guys!
>
> I've been experimenting with the nav stack on the Roomba and this is what
> I've come up with:
>
> I found out that the controller_frequency parameter was the one that had
> the bigger impact on processor time when made smaller. I experimented with
> 10Hz and then 5Hz and everything works fine.
>
> I also reduced the update frequency of both the local and global costmaps
> to 3Hz, but ended up bringing them back to 5Hz has I did not notice much
> difference.
>
> I also played around with the maps sizes and resolution, however with a
> resolution of 0.1 the robot is not able to go through tighter spaces, so I'm
> back at 0.05 resolution.
>
> To sum up the nav stack was not running at 20Hz controller_frequency,
> however now that it is at 10Hz or 5Hz it always works, even when I push it
> on the rest of the parameters.
>
> There is only one issue. Sometimes the robot goes into a wall, and when it
> is too close, it backs up, and then it tries to go against the wall again,
> only to back up once more, and it just stays there going back and forth.
> Could that be related to the low controller_frequency?
>
> Next I will turn the laser off and connect the sonars (outputting data as
> point cloud) to see what happens.
>
> Gonçalo Cabrita
> ISR - University of Coimbra
> Portugal
>
> On Wed, Jul 7, 2010 at 8:22 PM, Eric Perko <wisesage5001 at gmail.com> wrote:
>
>> Gonçalo,
>>
>> 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.
>>
>> The largest challenge we (mobilerobots.case.edu) had with sonars was
>> twofold:
>>
>> 1. 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
>> 2. LIDAR and SONAR may not agree and so marking and clearing got
>> complicated.
>>
>> 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.
>>
>> 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...
>>
>> - Eric
>>
>> 2010/7/7 Gonçalo Cabrita <goncabrita at gmail.com>:
>>
>> > Thanks for your help on this matter Eitan and Eric!
>> > I'll run a few experiments with various settings and report back the
>> results
>> > soon.
>> > Also on this subject, some of our Roombas are equipped with sonar arrays
>> of
>> > 5 sonars arranged in
>> > -PI/2 -PI/4 0 PI/4 PI/2
>> > Do you think it would be a viable option to feed the sonar data into the
>> nav
>> > stack in the form of a point cloud? Or is it not even worth trying as
>> the
>> > amount of data produced is extremely small when compared to that of a
>> laser
>> > range finder?
>> > Thanks,
>> > Gonçalo Cabrita
>> > ISR - University of Coimbra
>> > Portugal
>> > On Jul 7, 2010, at 7:08 PM, Eitan Marder-Eppstein wrote:
>> >
>> > Goncalo,
>> >
>> > There are a few basic things that you can do to help with performance:
>> >
>> > 1) You can increase the resolution of the costmaps. Since a Roomba is so
>> > small, even 10cm resolution should probably be sufficient for
>> navigation.
>> > See the resolution parameter of the costmap:
>> > http://www.ros.org/wiki/costmap_2d#Map_management_parameters
>> >
>> > 2) You can decrease the update rate of the costmaps from 5Hz to
>> something
>> > lower depending on your tolerance for seeing an obstacle. At 5Hz, it'll
>> take
>> > about 1/5th of a second to react to an obstacle, at 3Hz 1/3rd of a
>> second,
>> > etc. See the update_frequency parameter for the costmap:
>> > http://www.ros.org/wiki/costmap_2d#Rate_parameters.
>> >
>> > 3) You can control the Roomba at a lower rate... maybe something like
>> 10Hz
>> > instead of 20Hz. For that you can set the controller_frequency parameter
>> on
>> > move_base: http://www.ros.org/wiki/move_base#Parameters.
>> >
>> > Hope this helps,
>> >
>> > Eitan
>> >
>> > 2010/7/7 Gonçalo Cabrita <goncabrita at gmail.com>
>> >>
>> >> Hi everyone!
>> >> Here at the lab we use Roomba robots with Eee PCs on top. The Eee PCs
>> have
>> >> a single core Intel Atom processor, not the quickest thing around! Each
>> >> Roomba is also equiped with an Hokuyo laser.
>> >> So I've recently been playing around with the ROS nav stack. I've tried
>> to
>> >> make it as simple as possible according to the various tutorials and
>> mailing
>> >> list msgs I've came across with, however I'm always getting a warning
>> that
>> >> it is running below the 20Hz frequency. It is also noticeable the fact
>> that
>> >> the robot does not move properly, and eventually crashes.
>> >> Previously I experimented the same setup on an Erratic robot with a
>> >> Celeron, and although it was taking pretty much all of the processor to
>> run
>> >> the nav stack, it was able to move pretty well around the lab according
>> to
>> >> the commands I was issuing from rviz.
>> >> So my question is, how can I use the nav stack in its simplest form, in
>> >> order to have it running smoothly on the Eee PCs?
>> >> I'm attaching the .yaml files I'm using for configuring the nav stack.
>> >> Thanks in advance!
>> >> Gonçalo Cabrita
>> >>
>> >>
>> >> _______________________________________________
>> >> ros-users mailing list
>> >> ros-users at code.ros.org
>> >> https://code.ros.org/mailman/listinfo/ros-users
>> >>
>> >
>> > _______________________________________________
>> > ros-users mailing list
>> > ros-users at code.ros.org
>> > https://code.ros.org/mailman/listinfo/ros-users
>> >
>> >
>> > _______________________________________________
>> > ros-users mailing list
>> > ros-users at code.ros.org
>> > https://code.ros.org/mailman/listinfo/ros-users
>> >
>> >
>>
>>
>> _______________________________________________
>> ros-users mailing list
>> ros-users at code.ros.org
>> https://code.ros.org/mailman/listinfo/ros-users
>>
>>
>
> _______________________________________________
> ros-users mailing list
> ros-users at code.ros.org
> https://code.ros.org/mailman/listinfo/ros-users
>
>
-------------- next part --------------
An HTML attachment was scrubbed...
URL: <http://lists.ros.org/pipermail/ros-users/attachments/20100708/2d000b9e/attachment-0003.html>
More information about the ros-users
mailing list