[ros-users] Navigation Stack: the robot rotates most of the time after receiving a goal

Eitan Marder-Eppstein eitan at willowgarage.com
Tue Sep 14 08:09:17 UTC 2010


XiaoJun,

>From looking at the video of rviz that you posted. It looks like your robot
is not well localized... though it depends on what the fixed and target
frames actually were for the video that you made. Do you remember what they
were? Are you able to run AMCL (http://www.ros.org/wiki/amcl) with just a
joystick with reasonable results? That would probably be a good first step
in getting navigation up and running well. Also, what parameters are you
using to bring up and run amcl?

Hope this helps,

Eitan

On Tue, Sep 14, 2010 at 12:50 AM, XiaoJun Wu <wu.xiaojun at gmail.com> wrote:

> Hi, all
>
> I have been testing the navigation stack on our own robot but suffers such
> a problem:
>
> The testing environment is a small lab area, with a map captured using
> gmapping. After launching robot_config.launch and move_base.launch, in rviz,
> a 2D Nav Goal then is given to the robot. The robot will start moving, but
> most of the time it keeps rotating itself unresonably. Ultimately the robot
> can achieve the goal, although much longer time is consumed than expected.
>
> Two video clips recording this strange behavior, one shoots the actual
> robot and the other captures the rviz screen, are uploaded to youtube for
> easy review.
> http://www.youtube.com/watch?v=PRWvs9oXBl8
> http://www.youtube.com/watch?v=XBD3lCyuILs
>
> I also tried the teleop_joystick function from robotino_teleop package with
> a logitech joystick. It works pretty well for both translational and
> rotational movement. From this fact, I think that the low-level robot
> control is of no problem, and most possibly the problem is from the
> high-level motion planner.
>
> I referred to the following post, which looks a bit similar to what I have
> met,
>
> http://ros-users.122217.n3.nabble.com/Navigation-stack-robot-starts-rotating-upon-recieving-goal-td819551.html#a819551
> But in rviz, I didn't find obstacle that prevent the planner to find a
> path, and I can't find the "move_base_node" which claims to hold the
> unknow-space topic.
>
> Any help or hints would be greatly appreciated!
>
> The robot used here is a self-developed 4-wheel omnidirectional platform;
> and I am using Boxturtule ROS, under Ubuntu 10.04.
> Also listed here are the yaml files I used for navigation:
>
> base_local_planner_params.yaml
> ------------------------------
> TrajectoryPlannerROS:
>   max_vel_x: 0.3
>   min_vel_x: 0.1
>   max_rotational_vel: 1.0
>   min_in_place_rotational_vel: 0.5
>   acc_lim_th: 2.0
>   acc_lim_x: 1.5
>   acc_lim_y: 1.5
>   backup_vel: -0.1
>   holonomic_robot: true
>   y_vels: [-0.3, -0.1, 0.1, 0.3]
>   dwa: true
>   path_distance_bias: 0.5
>   occdist_scale: 0.1
>   heading_lookahead: 0.5
>   heading_scoring: false #true
>   yaw_goal_tolerance: 0.2
>   xy_goal_tolerance: 0.1
>   sim_time: 1.0
>   sim_granularity: 0.025
>   oscillation_reset_dist: 1 #0.05
>   controller_frequency: 10
>
> costmap_common_params.yaml
> -------------------------
>   obstacle_range: 2.5
>   raytrace_range: 3.0
>   robot_radius: 0.25
>   inflation_radius: 0.3
>   inscribed_radius: 0.25
>   circumscribed_radius: 0.3
>   observation_sources: laser_scan_sensor
>   laser_scan_sensor: {sensor_frame: laser, data_type: LaserScan, topic:
> scan, marking: true, clearing: true}
>
> global_costmap_params.yaml
> --------------------------
> global_costmap:
>   global_frame: /map
>   robot_base_frame: /base_link
>   update_frequency: 2.0
>   publish_frequency: 1.0
>   static_map: true
>   rolling_window: false
>   width: 3.0
>   height: 3.0
>   resolution: 0.05
>   transform_tolerance: 0.5
>   map_type: costmap
>
> local_costmap_params.yaml
> -------------------------
> local_costmap:
>   global_frame: /map
>   robot_base_frame: /base_link
>   update_frequency: 10.0
>   publish_frequency: 1.0
>   static_map: false
>   rolling_window: true
>   width: 2.0
>   height: 2.0
>   resolution: 0.05
>   transform_tolerance: 0.5
>   map_type: costmap
>
>
> _______________________________________________
> 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/20100914/08626065/attachment-0003.html>


More information about the ros-users mailing list