[ros-users] Navigation Stack on tight places

Eitan Marder-Eppstein eitan at willowgarage.com
Mon Nov 29 19:18:32 UTC 2010


Hey all,

So, first off, I finally got around to taking some time to try out the
simulation that Gonçalo was having trouble with. A few things I noticed:

1) For robots with really low acceleration limits, it seems like using
Trajectory Rollout gives much better performance than using the Dynamic
Window Approach. I did a number of tests on this a long time ago, but I
think that there was actually a sweet bug in the way that I was specifying
the acceleration limits involving me spelling a parameter name incorrectly,
long since fixed, that was present during the tests. This meant that I
thought I was changing the acceleration limits for my tests, but was just
actually using the defaults. I feel like an idiot for this, because I came
to the conclusion that DWA and Trajectory Rollout lead to more or less the
same behavior in all situations I tested. Now, I'll say that DWA and
Trajectory Rollout are more or less equivalent when the robot's acceleration
limits are relatively high, but with lower acceleration limits, Trajectory
Rollout can perform better. This also lines up with literature comparing the
two approaches. For those who want a description of the differences between
the two approaches... I'll refer you here:
http://www.ros.org/wiki/base_local_planner#Overview. So, for the Creates,
which have low acceleration limits, Trajectory Rollout leads to better
performance.

2) Rolling out trajectories far enough is important, especially with a low
maximum velocity. Setting the sim_time parameter a bit higher can help
guarantee this since a low maximum velocity means it takes more time for the
simulated trajectories to diverge from each other significantly. If I were
to do things over again, I might specify the length of the rollout in meters
and then add a parameter to the cost function corresponding to the robot's
velocity on a given trajectory, but changing sim_time is the only way to
force trajectories to spread out a bit more at this time.

3) With a little bit of tweaking, I was able to get reasonable performance
for the Create in the environment that Gonçalo sent. Since I'm using
Trajectory Rollout... the rollout won't be quite as efficient as it was with
DWA. I'm exploring about twice as many trajectories. You can find my
parameters for the base_local_planner below:

controller_frequency: 5.0
TrajectoryPlannerROS:
  max_vel_x: 0.20
  min_vel_x: 0.10
  max_rotational_vel: 1.5
  min_in_place_rotational_vel: 0.1
  acc_lim_th: 0.75
  acc_lim_x: 0.50
  acc_lim_y: 0.50

  holonomic_robot: false
  yaw_goal_tolerance: 0.05
  xy_goal_tolerance: 0.1
  goal_distance_bias: 0.8
  path_distance_bias: 0.6
  sim_time: 1.5
  heading_lookahead: 0.325
  oscillation_reset_dist: 0.05

  vx_samples: 6
  vtheta_samples: 20
  dwa: false

Hopefully, this improves the experiences people have with running the
navigation stack on the Creates. I haven't really messed with things
extensively, but I'm planning on trying things out on a real Create in the
near future as we just got some at Willow that we can mess around with.

Hope all is well,

Eitan

2010/11/19 Gonçalo Cabrita <goncabrita at gmail.com>

> Hi Eitan,
>
> Thanks for the tip! That on-the-fly tweaking is just what I needed!!! You
> guys really think it all through!
>
> I was playing with the params all afternoon and I managed to get the
> Roombas moving pretty well. The only problem is that when the robot reaches
> the goal but needs to adjust the heading, instead of turning in place it
> tries to make some sort of turn to come back at the goal in the proper
> heading. In tight places it ends getting stuck inside the inflated
> obstacles, where it sits very comfortably and refuses to leave. This also
> happens when the robot is stopped and I give it a new goal that implies a
> radical change of heading, instead of turning in place for starters, it just
> goes mental and drives away into a wall!!! Other than that I'm loving
> dwa_local_planner.
>
> Could you please point me to the functions I could edit in
> dwa_local_planner to change this behavior (turning in place instead of going
> for the roundabout when correcting the heading at the start or end of path)?
>
> And we have some even more cluttered versions of our tiny Roomba arena :)
>
> Sorry for the trouble and thanks for the help!!
>
> Gonçalo Cabrita
> ISR - University of Coimbra
> Portugal
>
> On Fri, Nov 19, 2010 at 11:57 PM, Eitan Marder-Eppstein <
> eitan at willowgarage.com> wrote:
>
>> Gonçalo,
>>
>> First, off I've been able to reproduce the problem you described in the
>> simulation you sent, but I haven't had a chance to dig too deeply yet. I'll
>> get to that over the next couple of days. As far as the parameters you've
>> set for your robot with the dwa_local_planner, you might be interested in
>> using dynamic reconfigure to tune them. To do this, just "rosrun
>> dynamic_reconfigure reconfigure_gui" and select move_base/DWAPlannerROS.
>> (see http://www.ros.org/wiki/dynamic_reconfigure) This should display the
>> parameters that you can tweak on the fly for the local planner which, I
>> believe, is everything but the acceleration limits.... acc_lim_x, acc_lim_y,
>> and acc_lim_th which you should make sure to set in your launch file.
>>
>> Hope this helps,
>>
>> Eitan
>>
>> 2010/11/19 Gonçalo Cabrita <goncabrita at gmail.com>
>>
>>> Hi Steve!
>>>
>>> Thanks for the tip Steve, its working now!
>>>
>>> I'm currently using dwa_local_planner on the roombas in our cluttered
>>> arena. Globally it seems to work better than base_local_planner. However I'm
>>> having the same problem. The robot eventually gets too close to a wall,
>>> crossing the inflated obstacles. But instead of backing up and going for the
>>> wall in an endless loop, the robot just stops. I've been playing around with
>>> the params but I'm not even sure if I'm using the right ones! I looked into
>>> the code and also ran dwa_local_planner/DWAPlannerROS with no params to take
>>> a look at what was being set automatically. I hope I'm not playing around
>>> with non-existent params :P hehehe
>>>
>>> Could you please confirm my list of params Eitan?
>>>
>>> base_local_planner: dwa_local_planner/DWAPlannerROS
>>> controller_frequency: 5.0
>>> DWAPlannerROS:
>>>   holonomic_robot: false
>>>
>>>   max_rotational_vel: 1.5
>>>   max_rot_vel: 1.5
>>>   max_trans_vel: 0.16
>>>   min_rot_vel: 0.785
>>>   min_trans_vel: 0.08
>>>
>>>   rot_stopped_vel: 0.01
>>>   trans_stopped_vel: 0.01
>>>
>>>   max_vel_x: 0.16
>>>   max_vel_y: 0.0
>>>   min_vel_x: 0.08
>>>   min_vel_y: 0.0
>>>
>>>   xy_goal_tolerance: 0.10
>>>   yaw_goal_tolerance: 0.05
>>>
>>>   path_distance_bias: 4.0
>>>   goal_distance_bias: 0.7
>>>   occdist_scale: 0.10
>>>
>>>   oscillation_reset_dist: 0.05
>>>
>>>   prune_plan: true
>>>
>>>   #forward_point_distance:
>>>   #max_scaling_factor:
>>>   #penalize_negative_x:
>>>   #scaling_speed:
>>>
>>>   #sim_granularity: 0.025
>>>   #sim_period:
>>>   #sim_time: 1.0
>>>   #vth_samples: 20
>>>   #vx_samples: 3
>>>   #vy_samples: 3
>>>
>>> Thanks for the help!
>>>
>>> Gonçalo Cabrita
>>> ISR - University of Coimbra
>>> Portugal
>>>
>>> On Fri, Nov 19, 2010 at 3:32 PM, Steven Martin <
>>> s34.martin at connect.qut.edu.au> wrote:
>>>
>>>> My guess is you need to increase your min turn in place parameter. I
>>>> checked out creates a bit more today and I think they have same encoder
>>>> setup as the roombas. Anyway basically if you set a low speed the odom
>>>> reports that the create is rotating but the force is too low to overcome
>>>> friction,  so it just sits in place.
>>>>
>>>> Sent from my iPhone
>>>>
>>>> On 20/11/2010, at 12:32 AM, Gonçalo Cabrita <goncabrita at gmail.com>
>>>> wrote:
>>>>
>>>> Hi everyone!
>>>>
>>>> I've been doing some more experiments on the Roombas in the lab arena,
>>>> testing the nav stack on tight places. I'm currently using the following
>>>> params for the planner:
>>>>
>>>> controller_frequency: 5.0
>>>> TrajectoryPlannerROS:
>>>>
>>>>   max_vel_x: 0.20
>>>>   min_vel_x: 0.10
>>>>   max_rotational_vel: 1.5
>>>>   min_in_place_rotational_vel: 0.8
>>>>   acc_lim_th: 0.75
>>>>   acc_lim_x: 0.50
>>>>   acc_lim_y: 0.50
>>>>
>>>>   holonomic_robot: false
>>>>
>>>>   yaw_goal_tolerance: 0.05
>>>>   xy_goal_tolerance: 0.05
>>>>
>>>>   path_distance_bias: 1.0 #0.6
>>>>   goal_distance_bias: 0.8
>>>>   occdist_scale: 0.01
>>>>   heading_lookahead: 0.50 #0.325
>>>>   heading_scoring: false
>>>>   heading_scoring_timestep: 1.0 #0.8
>>>>   dwa: true
>>>>
>>>> I'm noticing a big difference between the sim on Stage and the real
>>>> thing, when the robot stops on Stage it turns in place to face the direction
>>>> I set in the goal, however on the real robots when the robot reaches the
>>>> goal it just stops and doesn't correct the heading, even if it stays 180
>>>> degrees from the goal heading. Any ideas on why this could be happening with
>>>> the same params for sim and real robot?
>>>>
>>>> Thanks,
>>>>
>>>> Gonçalo Cabrita
>>>> ISR - University of Coimbra
>>>> Portugal
>>>>
>>>> 2010/11/19 Gonçalo Cabrita < <goncabrita at gmail.com>goncabrita at gmail.com
>>>> >
>>>>
>>>>> Eitan,
>>>>>
>>>>> I've been playing around with move_base params on the simulation and I
>>>>> got better results by increasing path_distance_bias to 6.0
>>>>>
>>>>> Since my planner runs really slow I also increased the
>>>>> heading_scoring_timestep to 1
>>>>>
>>>>> Although I guess the path_distance_bias value is a bit exaggerated the
>>>>> robot doesn't get stuck so often since it sticks to the path. However if I
>>>>> set a goal too close to a wall with the robot facing it the roomba just
>>>>> stays there forever.
>>>>>
>>>>> I also tried setting dwa to false to use Trajectory Rollout but it made
>>>>> things worst. Still I will also try that with different params.
>>>>>
>>>>> When I get back to the lab in the morning I'll test these params on the
>>>>> real robots. Also I'll try to run them with the dwa_local_planner to see
>>>>> what happens.
>>>>>
>>>>> Thanks for all the help,
>>>>>
>>>>> Gonçalo Cabrita
>>>>> ISR - University of Coimbra
>>>>> Portugal
>>>>>
>>>>> On Nov 18, 2010, at 9:01 PM, Eitan Marder-Eppstein wrote:
>>>>>
>>>>> Gonçalo,
>>>>>
>>>>> Thanks for the package, I'll take a look at things.
>>>>>
>>>>> To run a different local planner, you'll want to change the plugin that
>>>>> move_base loads. The relevant parameters are documented here: <http://www.ros.org/wiki/move_base#Parameters>
>>>>> http://www.ros.org/wiki/move_base#Parameters
>>>>>
>>>>> <http://www.ros.org/wiki/move_base#Parameters>You'll set
>>>>> base_local_planner to be something like dwa_local_planner/DWAPlannerROS.
>>>>>
>>>>> You'll also need to make sure the dwa_local_planner library is made
>>>>> before running move_base as it'll be loaded at runtime.
>>>>>
>>>>> Hope this helps,
>>>>>
>>>>> Eitan
>>>>>
>>>>> 2010/11/18 Gonçalo Cabrita < <goncabrita at gmail.com>
>>>>> goncabrita at gmail.com>
>>>>>
>>>>>> Sorry Eitan!
>>>>>>
>>>>>> I should have sent everything compressed the first time! I compressed
>>>>>> the pkg. To run it just put it on your ROS_PACKAGE_PATH, roscore, roscd
>>>>>> roomba_stage and then open stage, launch move_base and open rviz (also
>>>>>> sending a roomba_stage.vcg file):
>>>>>>
>>>>>> rosrun stage stageros roomba_lse_arena.world
>>>>>> roslaunch roomba_stage move_base_lse_arena.launch
>>>>>>
>>>>>> Just send the robot to the top right corner and it will likely stall
>>>>>> on the wall.
>>>>>>
>>>>>> Anyways I just downloaded navigation_experimental!
>>>>>> So dwa_local_planner seems to be a lib, how should I use it to get the robot
>>>>>> up and running with it? Just give me some quick pointers.
>>>>>>
>>>>>>  Cheers,
>>>>>>
>>>>>> Gonçalo Cabrita
>>>>>> ISR - University of Coimbra
>>>>>> Portugal
>>>>>>
>>>>>> On Thu, Nov 18, 2010 at 7:02 PM, Eitan Marder-Eppstein <<eitan at willowgarage.com>
>>>>>> eitan at willowgarage.com> wrote:
>>>>>>
>>>>>>> Gonçalo,
>>>>>>>
>>>>>>> It looks like you missed a file called "arena_obstalces.pgm" in what
>>>>>>> you sent which is needed by the roomba_ise_arena.world file. Is there any
>>>>>>> way you can just tar up the package you use to bring things up? Ideally this
>>>>>>> would include all the configuration files and launch files you're using to
>>>>>>> bring up stage and the navigation stack and would save a bit of grief in me
>>>>>>> recreating the same package on my end.
>>>>>>>
>>>>>>> Thanks a bunch,
>>>>>>>
>>>>>>> Eitan
>>>>>>>
>>>>>>> 2010/11/18 Gonçalo Cabrita < <goncabrita at gmail.com>
>>>>>>> goncabrita at gmail.com>
>>>>>>>
>>>>>>>> Hi Eitan!
>>>>>>>>
>>>>>>>> Thanks for your reply.
>>>>>>>>
>>>>>>>> I'm attaching the files needed to run the sim on Stage. It is the
>>>>>>>> same setup we have on the real arena right now, and the results on the real
>>>>>>>> robot are pretty similar to the simulation.
>>>>>>>>
>>>>>>>> I'll most definitely take a look at the experimental nav stack. I'd
>>>>>>>> like to try the dwa_local_planner on the roomba to see what
>>>>>>>> happens! I'll be posting some feedback and most likely a bunch of questions!
>>>>>>>>
>>>>>>>> Gonçalo Cabrita
>>>>>>>> ISR - University of Coimbra
>>>>>>>> Portugal
>>>>>>>>
>>>>>>>>
>>>>>>>> On Thu, Nov 18, 2010 at 5:54 PM, Eitan Marder-Eppstein <<eitan at willowgarage.com>
>>>>>>>> eitan at willowgarage.com> wrote:
>>>>>>>>
>>>>>>>>> Hey guys,
>>>>>>>>>
>>>>>>>>> So, to join in the discussion. From the video, it looks like the
>>>>>>>>> base_local_planner gets stuck in a local minimum with the parameters
>>>>>>>>> configured as they are. Is there any way that you can post the package used
>>>>>>>>> to create that video so that I can play around a little bit? I've wanted to
>>>>>>>>> have a case in simulation where a diff drive robot behaves badly and it
>>>>>>>>> seems like this is a simple one that could help me track down some issues
>>>>>>>>> the navigation stack has with diff drive robots. With that said, its true
>>>>>>>>> that no one local planner is going to fit all robots.
>>>>>>>>>
>>>>>>>>> We've started development of some other local planners in the
>>>>>>>>> navigation_experimental stack that might also be worth checking out. One is
>>>>>>>>> called dwa_local_planner and is a much cleaner version of the
>>>>>>>>> base_local_planner that includes things like scaling the robot's footprint
>>>>>>>>> based on speed, allowing for holonomic robots to explore more of the y
>>>>>>>>> velocity space, and exposing parameters via dynamic reconfigure to make
>>>>>>>>> tuning them a lot easier... we're testing it on the PR2 right now, not sure
>>>>>>>>> how it'll work on a diff-drive robot. There's also the pose_follower which
>>>>>>>>> attempts to follow a plan exactly, stopping in the presence of obstacles.
>>>>>>>>> This also hasn't been tested on diff-drive robots and I'd expect it could
>>>>>>>>> use a few tweaks to really work well, but it might be something to look at.
>>>>>>>>> One thing to keep in mind with all this, however, is that the packages in
>>>>>>>>> navigation_experimental are, well, experimental, so you're likely to run
>>>>>>>>> into some issues from time to time, there are no guarantees about API
>>>>>>>>> stability yet, and documentation isn't great.
>>>>>>>>>
>>>>>>>>> Hope all is well and please do post the simulation package as I'd
>>>>>>>>> love to take a look at things,
>>>>>>>>>
>>>>>>>>> Eitan
>>>>>>>>>
>>>>>>>>> 2010/11/18 Gonçalo Cabrita < <goncabrita at gmail.com>
>>>>>>>>> goncabrita at gmail.com>
>>>>>>>>>
>>>>>>>>> We've been a bit busy porting everything that moves around here to
>>>>>>>>>> ROS! We'll update our repository in the next week with everything we've got!
>>>>>>>>>>
>>>>>>>>>> I'm attaching the param files we use for the roombas.
>>>>>>>>>>
>>>>>>>>>> I'm surprised the creates don't have decent odometry since they
>>>>>>>>>> were design for research. We have considered using cheap webcams with visual
>>>>>>>>>> odometry to replace the roomba's odometry, but I haven't had time to look
>>>>>>>>>> into it. If my memory serves me when we opened a roomba we found a hall
>>>>>>>>>> sensor with 4 magnets tied to the motor shaft. So I'm guessing direction is
>>>>>>>>>> determined by the motor speed. And that why when you push the roomba the
>>>>>>>>>> odometry doesn't count back!
>>>>>>>>>>
>>>>>>>>>> I'm really interested in solving this matter. If the problem
>>>>>>>>>> really is from the nav stack we're in big trouble since everything here is
>>>>>>>>>> diff drive! We have roombas, erratics and scouts!
>>>>>>>>>>
>>>>>>>>>> Gonçalo Cabrita
>>>>>>>>>> ISR - University of Coimbra
>>>>>>>>>> Portugal
>>>>>>>>>>
>>>>>>>>>>
>>>>>>>>>> On Thu, Nov 18, 2010 at 3:45 PM, Steven Martin <<s34.martin at connect.qut.edu.au>
>>>>>>>>>> s34.martin at connect.qut.edu.au> wrote:
>>>>>>>>>>
>>>>>>>>>>>  Yeh I think my problem is related to odometry, the iCreates
>>>>>>>>>>> don't have any encoders. I thought they did but after looking closer at the
>>>>>>>>>>> driver I am pretty sure its just openloop. Do you have the parameters for
>>>>>>>>>>> amcl in your repository? I had a look but couldn't see them anywhere.
>>>>>>>>>>>
>>>>>>>>>>> I have the code for the pursuit path follower checked in @
>>>>>>>>>>> <http://launchpad.net/cmr>launchpad.net/cmr but its very
>>>>>>>>>>> incomplete. It will compile, you can launch it and it will try and follow a
>>>>>>>>>>> path but it doesn't have any obstacle avoidance and I think I have one of my
>>>>>>>>>>> signs wrong in the code as it  didn't appear to do much following  from the
>>>>>>>>>>> very limited testing I have done.
>>>>>>>>>>>
>>>>>>>>>>> Have a look, its basically as stripped down as I could make a
>>>>>>>>>>> local path planner while still fitting in the ROS framework. Also due to the
>>>>>>>>>>> pretty well useless iCreate odometry I chose to implement this in the global
>>>>>>>>>>> frame and this may have some adverse affects if you are only running
>>>>>>>>>>> localiser @ 3Hz.
>>>>>>>>>>>
>>>>>>>>>>> I will probably have time to look at this next week but I think
>>>>>>>>>>> this is a problem for anybody using nonholonomic robots with the Nav Stack
>>>>>>>>>>> so I would be surprised if someone else hasn't already got a better
>>>>>>>>>>> solution.
>>>>>>>>>>>
>>>>>>>>>>> Steve
>>>>>>>>>>>
>>>>>>>>>>>  ------------------------------
>>>>>>>>>>> *From:* <ros-users-bounces at code.ros.org>
>>>>>>>>>>> ros-users-bounces at code.ros.org [<ros-users-bounces at code.ros.org>
>>>>>>>>>>> ros-users-bounces at code.ros.org] on behalf of Gonçalo Cabrita [<goncabrita at gmail.com>
>>>>>>>>>>> goncabrita at gmail.com]
>>>>>>>>>>> *Sent:* Friday, 19 November 2010 12:52 AM
>>>>>>>>>>> *To:* User discussions
>>>>>>>>>>> *Subject:* Re: [ros-users] Navigation Stack on tight places
>>>>>>>>>>>
>>>>>>>>>>>  Hi Steven!
>>>>>>>>>>>
>>>>>>>>>>>  "ts not a failure case but do you also see the one where it
>>>>>>>>>>> turns a little bit away from the path then does loop around to rejoin it.?"
>>>>>>>>>>>
>>>>>>>>>>>  You we also get that a lot! The robot never sticks to the path
>>>>>>>>>>> the planner outputs, it wonders around a lot.
>>>>>>>>>>>
>>>>>>>>>>>  We are using Roombas 560 with Eee PCs and Hokuyo lasers. We
>>>>>>>>>>> launch the Roomba the laser and the tf broadcaster on one file and map
>>>>>>>>>>> server, amcl and move base on another one. We have the map updaters running
>>>>>>>>>>> at 3Hz and the path planner at 5Hz. Still sometimes the EeePC skips a loop!
>>>>>>>>>>> Furthermore, I dunno how the Create is but our Roombas have nasty odometry!
>>>>>>>>>>> The encoders have only 1 channel with 4 pulses per motor turn!
>>>>>>>>>>>
>>>>>>>>>>>  Anyways, I'm not familiar with the nav stack code, but I would
>>>>>>>>>>> like to help if possible!
>>>>>>>>>>>
>>>>>>>>>>>  Gonçalo Cabrita
>>>>>>>>>>> ISR - University of Coimbra
>>>>>>>>>>> Portugal
>>>>>>>>>>>
>>>>>>>>>>> On Thu, Nov 18, 2010 at 2:35 PM, Steven Martin <<s34.martin at connect.qut.edu.au>
>>>>>>>>>>> s34.martin at connect.qut.edu.au> wrote:
>>>>>>>>>>>
>>>>>>>>>>>>  Yep see that one all the time. I think the implementation of
>>>>>>>>>>>> DWA is flawed for tank steer robots.
>>>>>>>>>>>>
>>>>>>>>>>>> Its not a failure case but do you also see the one where it
>>>>>>>>>>>> turns a little bit away from the path then does loop around to rejoin it.?
>>>>>>>>>>>>
>>>>>>>>>>>> I started implementing just pure pursuit path follower to
>>>>>>>>>>>> replace DWA but haven't quite got it working and been too busy with other
>>>>>>>>>>>> stuff. I think we need to implement some other local planners or just path
>>>>>>>>>>>> followers.
>>>>>>>>>>>>
>>>>>>>>>>>> Also what are you using for the localization? I haven't been
>>>>>>>>>>>> able to get AMCL to work reliably on the iCreates.
>>>>>>>>>>>>  ------------------------------
>>>>>>>>>>>> *From:* <ros-users-bounces at code.ros.org>
>>>>>>>>>>>> ros-users-bounces at code.ros.org [<ros-users-bounces at code.ros.org>
>>>>>>>>>>>> ros-users-bounces at code.ros.org] on behalf of Gonçalo Cabrita [<goncabrita at gmail.com>
>>>>>>>>>>>> goncabrita at gmail.com]
>>>>>>>>>>>> *Sent:* Thursday, 18 November 2010 11:51 PM
>>>>>>>>>>>> *To:* <ros-users at code.ros.org>ros-users at code.ros.org
>>>>>>>>>>>> *Subject:* [ros-users] Navigation Stack on tight places
>>>>>>>>>>>>
>>>>>>>>>>>>    Hi everyone!
>>>>>>>>>>>>
>>>>>>>>>>>>  We've been using the nav stack on our Roombas for quite a
>>>>>>>>>>>> while now, mostly on the corridors of ISR without any problems.
>>>>>>>>>>>>
>>>>>>>>>>>>  However we have a small 4mx3m arena we built specifically for
>>>>>>>>>>>> testing odor search algorithms in which we recently started to run some
>>>>>>>>>>>> experiments. We quickly found out that the nav stack has some problems
>>>>>>>>>>>> moving the robot around in tight places. Quite often we get
>>>>>>>>>>>> the behavior that can be seen in the following video...
>>>>>>>>>>>>
>>>>>>>>>>>>  <http://www.youtube.com/watch?v=vy9xoNvmktg>
>>>>>>>>>>>> http://www.youtube.com/watch?v=vy9xoNvmktg
>>>>>>>>>>>>
>>>>>>>>>>>>  In the video we are running a Roomba inside our arena in Stage
>>>>>>>>>>>> with perfect odometry. The robot stalls against a wall and stays there for
>>>>>>>>>>>> 30mins until we stop it. On occasion the robot eventually gets out after a
>>>>>>>>>>>> while.
>>>>>>>>>>>>
>>>>>>>>>>>>  At first I thought this could be happening because of the poor
>>>>>>>>>>>> performance of the EeePCs the Roombas carry around or because of the
>>>>>>>>>>>> Roomba's crappy odometry, but in Stage on a Core2Duo laptop we were able to
>>>>>>>>>>>> see the same behavior.
>>>>>>>>>>>>
>>>>>>>>>>>>  Has anyone experienced this behavior before?
>>>>>>>>>>>>
>>>>>>>>>>>> _______________________________________________
>>>>>>>>>>>> ros-users mailing list
>>>>>>>>>>>>  <ros-users at code.ros.org>ros-users at code.ros.org
>>>>>>>>>>>>  <https://code.ros.org/mailman/listinfo/ros-users>
>>>>>>>>>>>> https://code.ros.org/mailman/listinfo/ros-users
>>>>>>>>>>>>
>>>>>>>>>>>>
>>>>>>>>>>>
>>>>>>>>>>> _______________________________________________
>>>>>>>>>>> ros-users mailing list
>>>>>>>>>>>  <ros-users at code.ros.org>ros-users at code.ros.org
>>>>>>>>>>>  <https://code.ros.org/mailman/listinfo/ros-users>
>>>>>>>>>>> https://code.ros.org/mailman/listinfo/ros-users
>>>>>>>>>>>
>>>>>>>>>>>
>>>>>>>>>>
>>>>>>>>>> _______________________________________________
>>>>>>>>>> ros-users mailing list
>>>>>>>>>>  <ros-users at code.ros.org>ros-users at code.ros.org
>>>>>>>>>>  <https://code.ros.org/mailman/listinfo/ros-users>
>>>>>>>>>> https://code.ros.org/mailman/listinfo/ros-users
>>>>>>>>>>
>>>>>>>>>>
>>>>>>>>>
>>>>>>>>> _______________________________________________
>>>>>>>>> ros-users mailing list
>>>>>>>>>  <ros-users at code.ros.org>ros-users at code.ros.org
>>>>>>>>>  <https://code.ros.org/mailman/listinfo/ros-users>
>>>>>>>>> https://code.ros.org/mailman/listinfo/ros-users
>>>>>>>>>
>>>>>>>>>
>>>>>>>>
>>>>>>>> _______________________________________________
>>>>>>>> ros-users mailing list
>>>>>>>>  <ros-users at code.ros.org>ros-users at code.ros.org
>>>>>>>>  <https://code.ros.org/mailman/listinfo/ros-users>
>>>>>>>> https://code.ros.org/mailman/listinfo/ros-users
>>>>>>>>
>>>>>>>>
>>>>>>>
>>>>>>> _______________________________________________
>>>>>>> ros-users mailing list
>>>>>>>  <ros-users at code.ros.org>ros-users at code.ros.org
>>>>>>>  <https://code.ros.org/mailman/listinfo/ros-users>
>>>>>>> https://code.ros.org/mailman/listinfo/ros-users
>>>>>>>
>>>>>>>
>>>>>>
>>>>>> _______________________________________________
>>>>>> ros-users mailing list
>>>>>>  <ros-users at code.ros.org>ros-users at code.ros.org
>>>>>>  <https://code.ros.org/mailman/listinfo/ros-users>
>>>>>> https://code.ros.org/mailman/listinfo/ros-users
>>>>>>
>>>>>>
>>>>> _______________________________________________
>>>>> ros-users mailing list
>>>>> <ros-users at code.ros.org>ros-users at code.ros.org
>>>>>  <https://code.ros.org/mailman/listinfo/ros-users>
>>>>> 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
>>
>>
>
> _______________________________________________
> 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/20101129/0c2aee5c/attachment-0003.html>


More information about the ros-users mailing list