[ros-users] base_local_planner
Eitan Marder-Eppstein
eitan at willowgarage.com
Fri May 28 15:29:26 UTC 2010
Andreas,
Instead of
acc_limit_th: 0.05
acc_limit_x: 0.05
acc_limit_y: 0.05
Can you try using:
acc_lim_th: 0.05
acc_lim_x: 0.05
acc_lim_y: 0.05
It turns out that I used the wrong names for these parameters in the
http://www.ros.org/wiki/navigation/Tutorials/RobotSetup tutorial that tells
you how to set up your robot. I've just fixed the page. The documentation
here: http://www.ros.org/wiki/base_local_planner#Parameters is correct, but
I apologize for the confusion I've caused. There are probably a number of
robots out there using the wrong parameter names.
Try changing those parameters to be correct and let me know what happens.
Hope all is well,
Eitan
On Fri, May 28, 2010 at 5:22 AM, Andreas Vogt <andreas.vogt at dfki.de> wrote:
>
> Hi,
>
> thanks for the code but the velocity are still jumps.
>
> Andreas
>
> Eitan Marder-Eppstein schrieb:
> > Eric,
> >
> > That ticket didn't include the linear case originally, but it does
> > now. Thanks for pointing it out. The PR2 has such high acceleration
> > limits that its easy for me to overlook this stuff, but it really
> > matters for robots with lower acceleration limits.
> >
> > Hope all is well,
> >
> > Eitan
> >
> > On Thu, May 27, 2010 at 11:09 AM, Eric Perko <wisesage5001 at gmail.com
> > <mailto:wisesage5001 at gmail.com>> wrote:
> >
> > Eitan,
> >
> > Does that ticket also include taking into account linear
> decelerations
> > as well as rotational limits? I've been using the TrajectoryPlanner
> > with reasonable acceleration limits for my differential drive robot
> > (say 0.25 m/s^2 for acc_limit_x) and, while we seem to accelerate
> > smoothly, upon reaching a goal within tolerance the system sends
> > abrupt halt commands. Does the TrajectoryPlanner expect another piece
> > of software to modulate the speeds to account for safe deceleration
> or
> > should I be seeing smooth deceleration as the robot approaches the
> > goal?
> >
> > - Eric
> >
> > On Thu, May 27, 2010 at 2:00 PM, Eitan Marder-Eppstein
> > <eitan at willowgarage.com <mailto:eitan at willowgarage.com>> wrote:
> > > Andreas,
> > >
> > > This could be due to the fact that the rotate to goal code
> > doesn't take the
> > > robot's acceleration limits into account. There's actually a
> > ticket open
> > > against it here: https://code.ros.org/trac/ros-pkg/ticket/3127
> > that got a
> > > bit lost in the pile. I'm going to change the priority on it to
> > make sure
> > > that I get to it in the next week or so since it seems to be
> > affecting you.
> > >
> > > Hope all is well,
> > >
> > > Eitan
> > >
> > >
> > > On Thu, May 27, 2010 at 12:13 AM, Andreas Vogt
> > <andreas.vogt at dfki.de <mailto:andreas.vogt at dfki.de>> wrote:
> > >>
> > >> Hi,
> > >> I am running my planner with this parameters:
> > >>
> > >> TrajectoryPlannerROS:
> > >> max_vel_x: 0.2
> > >> min_vel_x: 0.01
> > >> max_rotational_vel: 0.23
> > >> min_in_place_rotational_vel: 0.01
> > >>
> > >> acc_limit_th: 0.05
> > >> acc_limit_x: 0.05
> > >> acc_limit_y: 0.05
> > >>
> > >> holonomic_robot: false
> > >>
> > >> but sometimes it seems that the velocity (angular.z here omega)
> > jumps
> > >> without account for the acceleration. In my case from zero to
> > >> max_rotational_vel.
> > >>
> > >>
> > >> Any ideas ?
> > >>
> > >> Andreas
> > >>
> > >>
> > >>
> > >>
> > >>
> > >> [ERROR] 170.700000000: ICP: 0.000000 VEL: 0.000000 OMEGA: 0.230000
> > >> 0.000000
> > >> [ERROR] 170.754000000: ICP: 0.000000 VEL: 0.000000 OMEGA: 0.230000
> > >> 0.000000
> > >> [ERROR] 170.805000000: ICP: 0.000000 VEL: 0.000000 OMEGA: 0.173355
> > >> 0.000000
> > >> [ERROR] 170.855000000: ICP: 0.000000 VEL: 0.000000 OMEGA: 0.173355
> > >> 0.000000
> > >> [ERROR] 170.902000000: ICP: 0.000000 VEL: 0.000000 OMEGA: 0.173355
> > >> 0.000000
> > >> [ERROR] 170.952000000: ICP: 0.000000 VEL: 0.000000 OMEGA: 0.173355
> > >> 0.000000
> > >> [ERROR] 171.003000000: ICP: 0.000000 VEL: 0.000000 OMEGA: 0.140928
> > >> 0.000000
> > >> [ERROR] 171.053000000: ICP: 10.000000 VEL: 0.105000 OMEGA:
> 0.000000
> > >> 0.000000
> > >> [ERROR] 171.118000000: ICP: 10.000000 VEL: 0.105000 OMEGA:
> 0.000000
> > >> 0.000000
> > >> [ERROR] 171.152000000: ICP: 10.000000 VEL: 0.105000 OMEGA:
> 0.000000
> > >> 0.000000
> > >> [ERROR] 171.201000000: ICP: 10.000000 VEL: 0.105000 OMEGA:
> 0.000000
> > >> 0.000000
> > >> [ERROR] 171.250000000: ICP: 10.000000 VEL: 0.105000 OMEGA:
> 0.000000
> > >> 0.000000
> > >> [ERROR] 171.302000000: ICP: 10.000000 VEL: 0.105000 OMEGA:
> 0.000000
> > >> 0.000000
> > >> [ERROR] 171.353000000: ICP: 10.000000 VEL: 0.105000 OMEGA:
> 0.000000
> > >> 0.000000
> > >> [ERROR] 171.401000000: ICP: 0.000000 VEL: 0.010000 OMEGA:
> -0.230000
> > >> 0.000000
> > >> [ERROR] 171.450000000: ICP: 0.000000 VEL: 0.010000 OMEGA:
> -0.230000
> > >> 0.000000
> > >> [ERROR] 171.501000000: ICP: 0.000000 VEL: 0.010000 OMEGA:
> -0.230000
> > >> 0.000000
> > >> [ERROR] 171.550000000: ICP: 0.000000 VEL: 0.010000 OMEGA:
> -0.230000
> > >> 0.000000
> > >> [ERROR] 171.609000000: ICP: 0.000000 VEL: 0.010000 OMEGA:
> -0.230000
> > >> 0.000000
> > >>
> > >>
> > >>
> > >>
> > >> _______________________________________________
> > >> ros-users mailing list
> > >> ros-users at code.ros.org <mailto:ros-users at code.ros.org>
> > >> https://code.ros.org/mailman/listinfo/ros-users
> > >
> > >
> > > _______________________________________________
> > > ros-users mailing list
> > > ros-users at code.ros.org <mailto:ros-users at code.ros.org>
> > > https://code.ros.org/mailman/listinfo/ros-users
> > >
> > >
> > _______________________________________________
> > ros-users mailing list
> > ros-users at code.ros.org <mailto: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
> >
>
>
> --
>
> Andreas Vogt
> Logistics and Production Robotics
>
> DFKI Bremen
> Robotics Innovation Center
> Robert-Hooke-Straße 5
> 28359 Bremen, Germany
>
> Phone: +49 (0)421 218-64140
> Fax: +49 (0)421 218-64150
> E-Mail: andreas.vogt at dfki.de
>
> Weitere Informationen: http://www.dfki.de/robotik
> -----------------------------------------------------------------------
> Deutsches Forschungszentrum fuer Kuenstliche Intelligenz GmbH
> Firmensitz: Trippstadter Straße 122, D-67663 Kaiserslautern
> Geschaeftsfuehrung: Prof. Dr. Dr. h.c. mult. Wolfgang Wahlster
> (Vorsitzender) Dr. Walter Olthoff
> Vorsitzender des Aufsichtsrats: Prof. Dr. h.c. Hans A. Aukes
> Amtsgericht Kaiserslautern, HRB 2313
> Sitz der Gesellschaft: Kaiserslautern (HRB 2313)
> USt-Id.Nr.: DE 148646973
> Steuernummer: 19/673/0060/3
>
> _______________________________________________
> 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/20100528/a1a10ccc/attachment-0003.html>
More information about the ros-users
mailing list