Hitesh,<br><br>Planning normally fails for one of two reasons:<br><br>1) There is an obstacle, or a perceived obstacle, that causes planning to fail. Look at the move_base_node/global_costmap/obstacles and move_base_node/global_costmap/inflated_obstacles topics in rviz to help debug this. Do you see any obstacles show up at all? Do you see the path blocked by the inflated obstacles? Also, visualize the goal that you're sending to move_base... check out the move_base_node/current_goal topic. You can find more information on using rviz with the navigation stack here: <a href="http://www.ros.org/wiki/navigation/Tutorials/Using%20rviz%20with%20the%20Navigation%20Stack">http://www.ros.org/wiki/navigation/Tutorials/Using%20rviz%20with%20the%20Navigation%20Stack</a><br>
<br>2) There is unknown space that prevents planning from succeeding. Look at the move_base_node/global_costmap/unknown_space topic in rviz. Do you see unknown space blocking the robot's path?<br><br>Also, a couple of suggestions from looking at your configuration:<br>
<br>1) You should probably set "raytrace_range" to be greater than "obstacle_range," otherwise you may have obstacles that do not clear out of the costmap as you'd expect.<br><br>2) If you're going to use a global_costmap that works in the odom frame, you'll probably want to set the "rolling_window" parameter to true. Otherwise, the robot will reach the edge of the map and not be able to continue.<br>
<br>Hope this helps,<br><br>Eitan<br><br><div class="gmail_quote">On Sat, May 15, 2010 at 5:35 AM, hitesh dhiman <span dir="ltr"><<a href="mailto:hitesh.dhiman.1988@gmail.com">hitesh.dhiman.1988@gmail.com</a>></span> wrote:<br>
<blockquote class="gmail_quote" style="border-left: 1px solid rgb(204, 204, 204); margin: 0pt 0pt 0pt 0.8ex; padding-left: 1ex;">Hi all,<br>I've been trying to troubleshoot the robot and running navigation stack on it. Earlier atleast the path was being planed and published, but we decided to migrate to a different laptop with a graphics card.<br>

Now, our files are  the same, the tf's are also same, I've attached the file. ROS installation on the new laptop was done through svn, and that's the only change. <br>The odometry is transformed as follows:<br>

odom_broadcaster.sendTransform((odom.pose.pose.position.x, odom.pose.pose.position.y , odom.pose.pose.position.z),tf.transformations.quaternion_from_euler(0,0,float(odo_returned[2]*0.001534)),rospy.Time.now(),"base_link","odom") <br>

<br>odo_returned[2] here is an element of a python list, and contains the odometry data with yaw values, that have a conversion factor of .001534.<br><br>The laser is being transformed as follows:<br>broadcaster.sendTransform(tf::StampedTransform(tf::Transform(tf::Quaternion(0, 0, 0, 1), tf::Vector3(0.0, 0.0, 0.2)),ros::Time::now(),"/base_link", "/laser"));<br>

<br>The values for move_base parameters are also shown below:<br><span style="background-color: rgb(255, 255, 255); color: rgb(102, 0, 204);">base_local_planner_params.yaml:</span><br>TrajectoryPlannerROS:<br>  transform_tolerance: 0.3<br>

  sim_time: 1.7<br>  sim_granularity: 0.05<br># dwa: true<br>  vx_samples: 3<br>  vtheta_samples: 20<br>  max_vel_x: 1<br>  min_vel_x: 0.2<br>  max_rotational_vel: 1.0<br>  min_in_place_rotational_vel: 0.4<br>  xy_goal_tolerance: 0.2<br>

  yaw_goal_tolerance: 0.05<br>  goal_distance_bias: 0.8<br>  path_distance_bias: 0.6<br>  occdist_scale: 0.5<br># occdist_scale: 0.05<br>  heading_lookahead: 0.325<br>  oscillation_reset_dist: 0.05<br>  acc_limit_th: 3.2<br>

  acc_limit_x: 2.5<br>  acc_limit_y: 2.5<br>  holonomic_robot: false<br><br><span style="color: rgb(51, 51, 153);">costmap_common_params.yaml:</span><br>obstacle_range: 2.5<br>raytrace_range: 1.0<br>footprint: [[-0.2, -0.2], [0.2, -0.2], [0.2, 0.2], [-0.2, 0.2]]<br>

#robot_radius: 0.4<br>inflation_radius: 0.2<br><br>observation_sources: laser_scan_sensor <br><br>laser_scan_sensor: {sensor_frame: laser, data_type: LaserScan, topic: /scan , marking: true, clearing: true}<br><br><span style="color: rgb(51, 51, 153);">global_costmap_params.yaml:</span><br>

global_costmap:<br>  global_frame: /odom<br>  robot_base_frame: /base_link<br>  update_frequency: 5.0<br>  publish_frequency: 2.0<br>  static_map: false<br><br><span style="color: rgb(51, 51, 153);">local_costmap_params.yaml:</span><br>

local_costmap:<br>  global_frame: /odom<br>  robot_base_frame: /base_link<br>  update_frequency: 5.0<br>  publish_frequency: 2.0<br>  static_map: false<br>  rolling_window: true<br>  width: 6.0<br>  height: 6.0<br>  resolution: 0.05<br>

<br clear="all">I'm using simple_navigation_goals, and giving a goal of x=2 m and w = 1 in /odom frame.<br><br>On passing the goal, the robot starts rotating about the centre, and gives the following in the status:<br>

Failed to find a valid plan. Even after executing recovery behaviors.<br>No messages for any global or local plan are being published. We also tried to start with running the robot straight, and then giving it a goal to see if anything works. But the velocity commands were still being pulished as (x =0, theta = 57), which means it still wants to rotate.<br>

The action server reports that the The base failed to move forward 2 meter for some reason.<br><br>The test is being done in a corridor, approx 8-10 feet wide with no obstacles, so there is no reason why the plan should fail.<br>

<br>Any help or hints would be greatly appreciated. I've out all the possible problems i thought could exist, but no luck so far.<br><font color="#888888">-- <br>Regards,<br>Hitesh Dhiman<br>Electrical Engineering<br>
National University of Singapore<br>

</font><br>_______________________________________________<br>
ros-users mailing list<br>
<a href="mailto:ros-users@code.ros.org">ros-users@code.ros.org</a><br>
<a href="https://code.ros.org/mailman/listinfo/ros-users" target="_blank">https://code.ros.org/mailman/listinfo/ros-users</a><br>
<br></blockquote></div><br>