Hi everyone,
we are trying to run a stage simulation for our robot. So far we have already tested a simulation of our lab map (generated with gmapping
and a sick laser) which worked fine. Here you can find the files [PGM] [YAML] for the generated map.
Our problem comes when we map the entire floor of the building, again with gmapping
and a sick laser. The generated map seems to be correct, at least we did not noticed any significative differences with de format of the smaller one. However, in this case, the map_server
dies when trying load the map without raising any error. The files for the bigger map are [PGM] [YAML].
Watching the logs it seems that the map_server
tries to load the map with no success and dies without notifying any errors.
Since we are using the same config and procedure to generate both maps, we suspect that the problem might come when loading the map.
We would appreciate any ideas or hints that might help us to solve this issue.
The launch_file we are using is the following:
<arg name="map" default="$(find maps)/roboticslab_complete.yaml"/>
<arg name="navmap" default="$(find maps)/roboticslab_complete.yaml"/>
<arg name="locations" default="$(find maps)/roboticslab_complete.yaml"/>
<arg name="world" default="$(find config)/roboticslab_complete.world"/>
<param name="map" type="string" value="$(arg map)"/>
<param name="navmap" type="string" value="$(arg navmap)"/>
<param name="locations" type="string" value="$(arg locations)"/>
<!-- Robot parameters -->
<param name="shape" type="string" value="$(find config)/mbot_shape-1px_5mm-c67_47.yaml"/>
<rosparam file="$(find config)/mbot.yaml"/>
<!-- Stage simulator -->
<node name="stage" pkg="stage_ros" type="stageros" args="$(arg world)">
<remap from="base_scan" to="scan"/>
</node>
<!-- LIDAR position -->
<node pkg="tf" type="static_transform_publisher" name="laser_broadcaster"
args="0 0 0 0 0 0 /base_laser_link /laser_frame 100"
required="true" />
<!-- Run the map server -->
<node name="map_server" pkg="map_server" type="map_server" args=" $(arg map)" required="true" output="screen">
<param name="frame_id" value="/map" />
</node>
<!--- AMCL -->
<include file="$(find launch)/mbot/amcl.launch"/>
<!-- Navigation -->
<node name="navigation" pkg="scout_navigation" type="navigator">
<param name="~guidance_method" type="string" value="fmm"/>
<param name="~platform_mode" type="string" value="omni"/>
</node>
<!-- Web console -->
<node name="webconsole" pkg="webconsole" type="server">
<param name="~home" type="string" value="home_mbot.html"/>
</node>
The world file we are using for both maps is the following:
include "uc3m_mbot_stage.world.inc"
define lidar ranger
(
sensor(
range [ 0.0 5.6 ]
fov 240
samples 680
)
# generic model properties
color "black"
size [ 0.05 0.05 0.1 ]
)
define lidar2 ranger
(
sensor(
range [ 0.0 5.9 ]
fov 360
samples 1020
)
# generic model properties
color "black"
size [ 0.05 0.05 0.1 ]
)
define mbot position
(
size [0.650 0.445 0.522]
origin [0 0 0 0]
gui_nose 1
drive "omni"
#lidar(pose [ 0.300 0.000 0.137 0.000 ])
lidar2(pose [ 0.000 0.000 0.137 0.000 ])
# UNSUPPORTED lidar(pose2 [ -0.230 0.000 0.137 180 ])
localization "odom"
)
define floorplan model
(
# sombre, sensible, artistic
color "gray30"
# most maps will need a bounding box
boundary 1
gui_nose 0
gui_grid 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 100 # simulation timestep in milliseconds
window
(
size [ 400 500 ]
rotate [ 0.000 0 ]
scale 30
)
# throw in a robot
mbot
(
name "mbot10"
pose [ -0.90 1.07 0.000 0 ]
color "blue"
)
## load an environment bitmap
floorplan
(
name "roboticslab_complete"
bitmap "../maps/roboticslab_complete.pgm"
size [200 200 1.000]
pose [ -0.90 1.07 0.000 0 ]
)
And here you can see the log of the map_server
dying when we try to load the bigger map:
... logging to /home/monarch/.ros/log/79d03972-f56a-11e4-90bb-10c37b936e61/roslaunch-mpc01-22912.log
monarch@mpc01:[~/monarch/co..._ws/launch/mbot]$ roslaunch uc3m_stage_simulation.launch
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.
started roslaunch server http://192.168.1.5:46538/
SUMMARY
========
PARAMETERS
* /amcl/kld_err
* /amcl/kld_z
* /amcl/laser_lambda_short
* /amcl/laser_likelihood_max_dist
* /amcl/laser_max_beams
* /amcl/laser_model_type
* /amcl/laser_sigma_hit
* /amcl/laser_z_hit
* /amcl/laser_z_max
* /amcl/laser_z_rand
* /amcl/laser_z_short
* /amcl/max_particles
* /amcl/min_particles
* /amcl/odom_alpha1
* /amcl/odom_alpha2
* /amcl/odom_alpha3
* /amcl/odom_alpha4
* /amcl/odom_alpha5
* /amcl/odom_frame_id
* /amcl/odom_model_type
* /amcl/recovery_alpha_fast
* /amcl/recovery_alpha_slow
* /amcl/resample_interval
* /amcl/transform_tolerance
* /amcl/update_min_a
* /amcl/update_min_d
* /locations
* /map
* /map_server/frame_id
* /navigation/guidance_method
* /navigation/laser_frame
* /navigation/max_dist
* /navigation/min_dist
* /navigation/obs_mult
* /navigation/platform_mode
* /navigation/vref
* /navmap
* /rosdistro
* /rosversion
* /shape
* /webconsole/home
NODES
/
amcl (amcl/amcl)
laser_broadcaster (tf/static_transform_publisher)
map_server (map_server/map_server)
navigation (scout_navigation/navigator)
stage (stage_ros/stageros)
webconsole (webconsole/server)
ROS_MASTER_URI=http://mpc01:11311
core service [/rosout] found
process[stage-1]: started with pid [22930]
process[laser_broadcaster-2]: started with pid [22946]
process[map_server-3]: started with pid [22959]
[ INFO] [1431340918.912792474]: Loading map from image "/home/monarch/monarch/code/trunk/rosbuild_ws/maps/roboticslab_complete.pgm"
process[amcl-4]: started with pid [22977]
================================================================================REQUIRED process [map_server-3] has died!
process has died [pid 22959, exit code 255, cmd /opt/ros/hydro/lib/map_server/map_server /home/monarch/monarch/code/trunk/rosbuild_ws/maps/roboticslab_complete_clean.yaml __name:=map_server __log:=/home/monarch/.ros/log/79d03972-f56a-11e4-90bb-10c37b936e61/map_server-3.log].
log file: /home/monarch/.ros/log/79d03972-f56a-11e4-90bb-10c37b936e61/map_server-3*.log
Initiating shutdown!
================================================================================
cannot add process [navigation-5] after process monitor has been shut down
[amcl-4] killing on exit
[map_server-3] killing on exit
[laser_broadcaster-2] killing on exit
[stage-1] killing on exit
And the map_server-3-stdout.log
file only tells us that is loading the map but nothing else:
monarch:mbot/ $ cat /home/monarch/.ros/log/79d03972-f56a-11e4-90bb-10c37b936e61/map_server-3-stdout.log [12:43:09]
[ INFO] [1431082392.889096566]: Loading map from image "/home/monarch/monarch/code/trunk/rosbuild_ws/maps/../maps/roboticslab_complete.pgm"
Originally posted by Victor Gonzalez-Pacheco on ROS Answers with karma: 396 on 2015-05-11
Post score: 2