Christian and Florian,

The default local planner that move_base uses, TrajectoryPlannerROS, follows a heuristic where it will only exploit a holonomic base in situations where it cannot navigate in a conventional manner. For example, the local planner will strafe when the robot finds itself too close to a wall, but won't do so in open space. The reason this heuristic was put in has to do with sensor placement on the PR2, which has all of its 3D sensors facing forward. This means it is preferable to move in a manner that keeps sensors facing in the direction of motion for safety reasons. There is potential to write a local planner that fully utilizes a holonomic base, but it would take a little bit of work and we haven't had a real need for it. We tend to use move_base to get from place to place around the office and then switch to more specialized controllers/planners for doing things like moving the base sideways along a table.

As far as "smooth motions" are concerned, what exactly do you mean? Is the robot stopping/jerking a lot? Oscillating? Overshooting its goal? Etc. A bit more information will give more of an idea about what might be causing your problem. One thing I've noticed from looking at your configuration file is that you've set your maximum velocity and acceleration limits to be pretty low and are using a very long simulation time. The robot will navigate with these settings, but I'd expect it to be pretty conservative... especially with sim_time set to 5 seconds. This means that any velocity command that would result in the robot hitting something if executed for 5 seconds won't be considered valid and, around obstacles, your robot will probably run very slowly.

Hope all is well,

Eitan

On Wed, Apr 7, 2010 at 10:42 AM, Weißhardt, Florian <Florian.Weisshardt@ipa.fraunhofer.de> wrote:

Hi together,

 

we are currently exploring the ROS navigation stack on Care-O-bot 3. Gmapping and amcl is already up and running yet we are now running in some problems with the move_base package. We are having troubles getting smooth motions and exploiting the holonomic base. E.g. the planner does not command any sidewards motions although we set the holonomic parameter in the local planner to true. Does anyone has experienced similar problems and knows which parameter to adapt? For reference we appended the configuration files for the base_local_planner.

 

TrajectoryPlannerROS:
  max_vel_x: 0.2
  min_vel_x: 0.01
  max_rotational_vel: 0.5
  min_in_place_rotational_vel: 0.1
 
  acc_limit_th: 0.5
  acc_limit_x: 0.1
  acc_limit_y: 0.1
 
  holonomic_robot: true
 
  sim_time: 5
  sim_granularity: 0.01
  xy_goal_tolerance: 0.3
  yaw_goal_tolerance: 0.1

 

We would be grateful for any help.

 

Best regards from Stuttgart

Christian and Florian

 

---
Dipl.-Ing. Florian Weißhardt

Fraunhofer IPA, Abt. 324/Robotersysteme
Nobelstrasse 12, D-70569 Stuttgart (Germany)
Phone +49(0)711-970-1046,
Fax +49(0)711-970-1008
http://www.ipa.fraunhofer.de/

 


_______________________________________________
ros-users mailing list
ros-users@code.ros.org
https://code.ros.org/mailman/listinfo/ros-users