robot_localization and gmapping with "no map received"
Hi to all,
I'm using Husky A200 with RTK GPS (/fix
), a SICK laser (/scan
), a AHRS IMU (/imu/data
) and wheel encoders.
I use robot_localization
and navsat_transform_node
to improve the position of my robot.
The topic /odometry/filtered/global
contains the robot's odometry with the GPS information.
Since I would like to build a map and use GPS waypoints for the robot's navigation, I'm trying to use slam_gmapping
with this command:
rosrun gmapping slam_gmapping scan:=scan _odom_frame:=odometry/filtered/global
The problem is that in RVIZ, I get the error: "no map received" and so I can only see the path followed by the robot, but no map.
Can you help me to fix this error, please?
I can see the /scan
laser point in RVIZ without problems.
This is my bag file (40MB) and this is the launch file I'm using for the robot_localization package:
<!-- Test launch file for two EKF instances and one navsat_transform instance -->
<launch>
<rosparam command="load" file="$(find husky_control)/config/control.yaml" />
<node name="base_controller_spawner" pkg="controller_manager" type="spawner" args="husky_joint_publisher husky_velocity_controller --shutdown-timeout 3"/>
<node pkg="rosbag" type="play" name="rosbag_play" output="screen" args="--clock /home/rocco/Desktop/gps/test4.bag -d 3"/>
<node pkg="tf2_ros" type="static_transform_publisher" name="bl_imu" args="0 0 0 0 0 0 base_link base_imu" />
<node pkg="tf2_ros" type="static_transform_publisher" name="bl_gps" args="0 0 0.4 0 0 0 base_link gps" />
<node pkg="tf2_ros" type="static_transform_publisher" name="bl_laser" args="0 0 0.4 0 0 0 base_link laser" />
<!-- Local (odom) instance -->
<node pkg="robot_localization" type="ekf_localization_node" name="ekf_localization_local" clear_params="true">
<param name="frequency" value="10"/>
<param name="sensor_timeout" value="0.1"/>
<param name="two_d_mode" value="false"/>
<param name="map_frame" value="map"/>
<param name="odom_frame" value="odom"/>
<param name="base_link_frame" value="base_link"/>
<param name="world_frame" value="odom"/>
<param name="transform_time_offset" value="0.0"/>
<param name="odom0" value="/husky_velocity_controller/odom"/>
<param name="imu0" value="/imu/data"/>
<rosparam param="odom0_config">[false, false, false,
false, false, false,
true, true, true,
false, false, true,
false, false, false]</rosparam>
<rosparam param="imu0_config">[false, false, false,
true, true, true,
false, false, false,
true, true, true,
true, true, true]</rosparam>
<param name="odom0_differential" value="false"/>
<param name="imu0_differential" value="false"/>
<param name="odom0_relative" value="false"/>
<param name="imu0_relative" value="false"/>
<param name="imu0_remove_gravitational_acceleration" value="true"/>
<param name="print_diagnostics" value="true"/>
<param name="odom0_queue_size" value="10"/>
<param name="imu0_queue_size" value="10"/>
<param name="debug" value="false"/>
<param name="debug_out_file" value="debug_ekf_localization.txt"/>
<remap from="/odometry/filtered" to="/odometry/filtered/local"/>
</node>
<!-- Global (map) instance -->
<node pkg="robot_localization" type="ekf_localization_node" name="ekf_localization_global" clear_params="true">
<param name="frequency" value="10"/>
<param name="sensor_timeout" value="0.1"/>
<param name="two_d_mode" value="false"/>
<param name="map_frame" value="map"/>
<param name="odom_frame" value="odom"/>
<param name="base_link_frame" value="base_link"/>
<param name="world_frame" value="map"/>
<param name="transform_time_offset" value="0.0"/>
<param name="odom0" value="/husky_velocity_controller/odom"/>
<param name="odom1" value="/odometry/gps"/>
<param name="imu0" value="/imu/data"/>
<rosparam param="odom0_config">[false, false, false,
false, false, false,
true ...