<p>Send me your world and launch files and I'll try to reproduce the problem.</p>
<p>    brian.</p>
<p><blockquote type="cite">On Jun 21, 2010 2:45 PM, "Suraj Swami" <<a href="mailto:suraj.g.swami@gmail.com">suraj.g.swami@gmail.com</a>> wrote:<br><br><div class="gmail_quote"><div>Hi Brain,</div><div><br>
</div><div>I am still not able to get amcl working. I changed the resolution in stage world file and in the map.yamp file .</div><div><br></div><div><div><br></div><div>

# load an environment bitmap</div><div>floorplan</div><div>( </div><div>  name "willow"</div><div>  bitmap "cave.pgm"</div><div>  size3 [22.36067 22.36067 0.5]  # Its at 500 * 500 pixel image.</div><div>


  pose [0 0 0]</div><div>)</div></div><div><br></div><div><div>image: cave.pgm</div><div>resolution: 0.002</div><div>origin: [0.0, 0.0, 0.0]</div><div>occupied_thresh: 0.65</div><div>free_thresh: 0.196</div><div>negate: 0</div>


</div><div><br></div><div>I do not get right location. Do I need to take care of anything else.</div><div><br></div><div>Thanks for the help.</div><div><br></div><div>-Suraj. </div><div> </div><blockquote class="gmail_quote" style="margin:0 0 0 .8ex;border-left:1px #ccc solid;padding-left:1ex">



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