hi Suraj, You probably have the resolution set incorrectly, but understandably so, in map.yaml. In the stage .world file, 'resolution' determines the resolution of the underlying grid that's used for simulation. The resolution of a bitmap that you load (for example, to be used as a background map), is determined by the combination of the bitmap's size in pixels, and the size that you specify for the bitmap. In this case, you're using cave.pgm, which I assume was created from Stage's cave.png, which is 500x500 pixels. Given the size you're setting, 54.0x58.7, the map resolution is about 0.11 m/pixel. That's the value you want to put in map.yaml. Now, why would a square bitmap be given a different size in X and Y? Depending on the version of Stage you're using, the map boundaries might be determined by the farthest-out black pixels, as opposed to the actual image boundaries. The slightly different values you're using might be an attempt to account for the non-square scaling that can result. There's a ticket for that: https://code.ros.org/trac/ros-pkg/ticket/4133 . brian. On Thu, Jun 10, 2010 at 11:42 PM, Suraj Swami wrote: > Hi, > I am trying to get understand how to use the AMCL package. I am using > simulator stage. And have written a  small node to make the robot move in > the map. But I am not getting right amcl_pose values. > I am not sure if my map_server and stage are well synchronized to have the > map data, resolution and origin. > FILE: map.yaml > image: cave.pgm > resolution: 0.02 > origin: [0.0, 0.0, 0.0] > occupied_thresh: 0.65 > free_thresh: 0.196 > negate: 0 > > FILE: MCL.world > define block model > ( >   size3 [0.5 0.5 0.5] >   gui_nose 0 > ) > define topurg laser > ( >   range_min 0.0 >   range_max 30.0 >   fov 360 >   samples 720 >   # generic model properties >   color "black" >   size [ 0.05 0.05 0.1 ] > ) > define erratic position > ( >   #size3 [0.415 0.392 0.25] >   size3 [0.35 0.35 0.25] >   origin3 [-0.05 0 0 0] >   gui_nose 1 >   drive "diff" >   topurg(pose [0.050 0.000 0.000]) > ) > define floorplan model > ( >   # sombre, sensible, artistic >   color "gray30" >   # most maps will need a bounding box >   boundary 0 >   gui_nose 0 >   gui_grid 0 >   gui_movemask 0 >   gui_outline 0 >   gripper_return 0 >   fiducial_return 0 >   laser_return 1 > ) > # set the resolution of the underlying raytrace model in meters > resolution 0.02 > interval_sim 1  # simulation timestep in milliseconds > interval_real 1  # real-time interval between simulation updates in > milliseconds > window > ( >   size [ 675.0 745.0 ] >   center [678.990 293.960] >   rotate [ 0.000 0 ] >   scale 28.806 > ) > # load an environment bitmap > floorplan > ( >   name "willow" >   bitmap "cave.pgm" >   size3 [54.0 58.7 0.5] >   pose [0 0 0] > ) > > > # throw in a robot > erratic( pose [0 0 0.000] name "era" color "blue") > block( pose [-13.924 25.020 0.000] color "red") > > > Is there a problem to synchronize the two files or is there any other > parameters that I need to take care of ? > Thank you. > Regards, > Suraj Swami > > > > > _______________________________________________ > ros-users mailing list > ros-users@code.ros.org > https://code.ros.org/mailman/listinfo/ros-users > >