ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

robot_localization and gmapping with "no map received"

asked 2017-06-11 15:12:11 -0500

Marcus Barnet gravatar image

updated 2017-06-11 15:18:24 -0500

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 ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2017-06-11 17:56:28 -0500

ufr3c_tjc gravatar image

_odom_frame:=... should not be the topic for the odometry. It is the frame within which to localize. Since your global version of robot_localization has the world frame parameter set to map, set the _odom_frame:=map and you'll have a better chance.

However, you may experience issues using GPS to localize within a map since it is discontinuous. Even RTK, which I know has centimeter-level accuracy, will give issues when it loses a signal due to roofs/tree cover/satellite availability etc. A better approach is to use the odom instance of robot_localization, and use tf to transform your coordinates from a UTM frame to your odom frame.

edit flag offensive delete link more

Comments

Thank you, I set _odom_frame:=map and now I can see the map. I tried to use rostopic pub /move_base_simple/goal geometry_msgs/PoseStped '{header: {stamp: now, frame_id: "map"}, pose: {position: {x: 15, y: -13, z: 0.0}, orientation: {w: 1.0}}}' to make the robot move in RVIZ, but nothing happens.

Marcus Barnet gravatar image Marcus Barnet  ( 2017-06-12 13:44:56 -0500 )edit

Am I using the move_base in the wrong way? How can I make the robot moves inside the map? i'm giving it the coordinates in odom frames.

Marcus Barnet gravatar image Marcus Barnet  ( 2017-06-12 13:45:58 -0500 )edit
1

Are you running this on the actual robot, or in a Gazebo simulation? You'll need to do one of those to see it actually move. Rviz only visualizes what is occurring. You need feedback from the simulation in Gazebo or from the real robot encoders to see it move.

ufr3c_tjc gravatar image ufr3c_tjc  ( 2017-06-12 18:01:58 -0500 )edit

I'm running this after loading the robot model in Gazebo. If I run commands like rostopic pub /husky/cmd_vel geometry_msgs/Twist -r 100 '[0.5,0,0]' '[0,0,0]', the robot moves, but if I run move_base, nothing happens. Do I need any additional package to make the move_base work?

Marcus Barnet gravatar image Marcus Barnet  ( 2017-06-29 09:37:57 -0500 )edit

Are you able to run move_base on my bag file without problems?

Marcus Barnet gravatar image Marcus Barnet  ( 2017-06-29 09:38:44 -0500 )edit

Question Tools

Stats

Asked: 2017-06-11 15:12:11 -0500

Seen: 4,590 times

Last updated: Jun 11 '17