2011/1/5 Brian Gerkey : > On Wed, Jan 5, 2011 at 8:37 AM, Steven Bellens > wrote: > >> I've figured out the problem occurs the moment I start running the >> navigation stack. I've been able to build a map using gmapping >> (running the gmapping mode on the groundstation), and the ping >> responses were constantly okay. When I start up navigation without a >> pre-build map (amcl - move base - gmapping), the ping responses >> suddenly increase (from 2 - 8 ms to 1000+ ms). When I try the same >> with a static map, everything goes well. Am I doing something wrong in >> this setup, e.g. can I run amcl and gmapping at the same time? If not, >> how should I run the navigation stack without a prebuild map? > > You should not run amcl and gmapping simultaneously.  They're both > estimating the map->odom transform, and you only want one source of > that information.  If you want to run without an a priori map, you > should use only gmapping, not amcl.  If you save the map produced by > gmapping (e.g., using the map_server/map_saver tool), you can then > localize against that map with amcl, and not run gmapping. > > But the gmapping / amcl transform conflict shouldn't cause network > latency.  Instead, I would suspect that it's the bandwidth being > consumed by sending the updated map from gmapping to move_base; > move_base subscribes to the map, which gmapping publishes as a latched > topic.  Maps can be big, and the map produced by gmapping is > automatically something like 4000x4000 cells, regardless of how much > space has actually been observed by the robot (there's an opportunity > to optimize gmapping's behavior, to be sure).  An experiment to try: > increase the gmapping/map_update_interval parameter.  Then the map > will be published less often, and soak up less bandwidth.  The > tradeoff, of course, is that move_base will receive updated maps less > frequently. When running all except the hokuyo_node on the groundstation (no gmapping, only amcl), the network traffic is still about 8MB / s from the robot to the ground station. I didn't check which nodes are the main consumers here yet, but the /scan topic only takes around 20kB / s of this. This 8 MB / s is way too much as only laser scan data needs to be send, right? The ROS master is running on the groundstation. > >> Another problem I face is about the navigation: the holonomic robot >> localizes itself OK, but the goals I send with rviz only manage to let >> it rotate (there is never a translational velocity command), so the >> robot starts rotating, but never gets anywhere close where I want him >> to go :). Any ideas on that? > > This is probably caused by the tf conflict between amcl and gmapping. > When you bring up the navigation stack on top of gmapping, don't run > amcl. This also happens when only running amcl. I found this to be a problem of the map origin coordinates or something related, but might need some help solving it. I've build a map using gmapping and saved it with the map_saver functionality. The map.yaml file places the origin of the map at [-50.0 , -50.0, 0.0], which is in the middle of the map. However the costmap always complains: [ WARN] [1294326503.260648549]: The origin for the sensor at (-0.97, 0.16, 0.00) is out of map bounds. So, the costmap cannot raytrace for it. As the map building goes fine, I expect the tf frames to be OK (there are no errors displayed). Do I need some more transformations to get the sensor frame updated with this map origin values? Steven > >        brian. > _______________________________________________ > ros-users mailing list > ros-users@code.ros.org > https://code.ros.org/mailman/listinfo/ros-users >