cartographer-project / cartographer_ros

Provides ROS integration for Cartographer.
Apache License 2.0
1.64k stars 1.2k forks source link

Dropped empty horizontal range data Warning and map not received #1812

Closed AmineDh98 closed 6 months ago

AmineDh98 commented 6 months ago

I am trying to run cartographer on my robot moving in Gazebo simulation. I have odometry information published in odom topic and a 2D LIDAR that publishes 2D scans at a topic remapped to scan I used the cartographer_rosbag_validate to check my data and I got the below output:

I0301 08:26:18.961421 508559 rosbag_validate_main.cc:399] Time delta histogram for consecutive messages on topic "/frankenstein/laser/scan" (frame_id: "lidar_link"):
Count: 2017  Min: 0.021  Max: 0.036  Mean: 0.0250281
[0.021000, 0.022500)                            Count: 3 (0.148736%)    Total: 3 (0.148736%)
[0.022500, 0.024000)                            Count: 10 (0.495786%)   Total: 13 (0.644522%)
[0.024000, 0.025500)      ##################    Count: 1844 (91.4229%)  Total: 1857 (92.0674%)
[0.025500, 0.027000)                       #    Count: 139 (6.89142%)   Total: 1996 (98.9588%)
[0.027000, 0.028500)                            Count: 15 (0.743679%)   Total: 2011 (99.7025%)
[0.028500, 0.030000)                            Count: 4 (0.198314%)    Total: 2015 (99.9008%)
[0.030000, 0.031500)                            Count: 0 (0%)   Total: 2015 (99.9008%)
[0.031500, 0.033000)                            Count: 0 (0%)   Total: 2015 (99.9008%)
[0.033000, 0.034500)                            Count: 1 (0.0495786%)   Total: 2016 (99.9504%)
[0.034500, 0.036000]                            Count: 1 (0.0495786%)   Total: 2017 (100%)
I0301 08:26:18.962023 508559 rosbag_validate_main.cc:399] Time delta histogram for consecutive messages on topic "/odom" (frame_id: "odom"):
Count: 39882  Min: 0.001  Max: 0.013  Mean: 0.00126608
[0.001000, 0.002200)    ####################    Count: 39600 (99.2929%) Total: 39600 (99.2929%)
[0.002200, 0.003400)                            Count: 176 (0.441302%)  Total: 39776 (99.7342%)
[0.003400, 0.004600)                            Count: 58 (0.145429%)   Total: 39834 (99.8796%)
[0.004600, 0.005800)                            Count: 26 (0.0651923%)  Total: 39860 (99.9448%)
[0.005800, 0.007000)                            Count: 10 (0.025074%)   Total: 39870 (99.9699%)
[0.007000, 0.008200)                            Count: 9 (0.0225666%)   Total: 39879 (99.9925%)
[0.008200, 0.009400)                            Count: 1 (0.0025074%)   Total: 39880 (99.995%)
[0.009400, 0.010600)                            Count: 1 (0.0025074%)   Total: 39881 (99.9975%)
[0.010600, 0.011800)                            Count: 0 (0%)   Total: 39881 (99.9975%)
[0.011800, 0.013000]                            Count: 1 (0.0025074%)   Total: 39882 (100%)
I0301 08:26:18.962615 508559 rosbag_validate_main.cc:399] Time delta histogram for consecutive messages on topic "/ground_truth" (frame_id: "world"):
Count: 50133  Min: 0.001  Max: 0.011  Mean: 0.00100728
[0.001000, 0.002000)    ####################    Count: 49917 (99.5691%) Total: 49917 (99.5691%)
[0.002000, 0.003000)                            Count: 133 (0.265294%)  Total: 50050 (99.8344%)
[0.003000, 0.004000)                            Count: 46 (0.0917559%)  Total: 50096 (99.9262%)
[0.004000, 0.005000)                            Count: 17 (0.0339098%)  Total: 50113 (99.9601%)
[0.005000, 0.006000)                            Count: 9 (0.0179522%)   Total: 50122 (99.9781%)
[0.006000, 0.007000)                            Count: 6 (0.0119682%)   Total: 50128 (99.99%)
[0.007000, 0.008000)                            Count: 1 (0.00199469%)  Total: 50129 (99.992%)
[0.008000, 0.009000)                            Count: 1 (0.00199469%)  Total: 50130 (99.994%)
[0.009000, 0.010000)                            Count: 2 (0.00398939%)  Total: 50132 (99.998%)
[0.010000, 0.011000]                            Count: 1 (0.00199469%)  Total: 50133 (100%)

Then I run my simulation to test the cartographer in real time and I used the below configuration:

options = { map_builder = MAP_BUILDER, trajectory_builder = TRAJECTORY_BUILDER, map_frame = "world", tracking_frame = "robot_frame", published_frame = "robot_frame", odom_frame = "odom", provide_odom_frame = true, publish_frame_projected_to_2d = true, use_pose_extrapolator = true, use_odometry = true, use_nav_sat = false, use_landmarks = false, num_laser_scans = 1, num_multi_echo_laser_scans = 0, num_subdivisions_per_laser_scan = 1, num_point_clouds = 0, } MAP_BUILDER.use_trajectory_builder_2d = true TRAJECTORY_BUILDER_2D.num_accumulated_range_data = 100 TRAJECTORY_BUILDER_2D.use_imu_data = false TRAJECTORY_BUILDER_2D.max_range = 40 TRAJECTORY_BUILDER_2D.min_range = 0.5

As a result, Rviz did not find the map (it gives warning that no map received) and I keep getting another warning saying:

[ WARN] [1709278310.809044891, 857.644000000]: W0301 08:31:50.000000 510125 local_trajectory_builder_2d.cc:218] Dropped empty horizontal range data.

Please find the rosbag file in this link: https://drive.google.com/file/d/1x8yZNXGfRxjehW-lVLKRYF6BHDgxgceT/view?usp=sharing

You can also have a look at the tf tree below: frames

Could you please identify the problem of not getting the map and SLAM not working ?

Note: -I am using ROS Noetic and Ubuntu 20.04 -The robot does not have an IMU

Please let me know if you need any more information! Thanks!

maker-ATOM commented 6 months ago

From the tf tree your world => odom is broadcasted by /world_to_odom_broadcaster which actually should be cartographer_node more over odom => robot_frame is also not broadcasted by /cartographer_node.

Check why these other nodes are broadcasting and if possible shutdown them.

AmineDh98 commented 6 months ago

Thank you for your answer.

regarding world => odom

Please find below my launch file that contains the /world_to_odom_broadcaster

<launch>
  <include file="$(find gazebo_ros)/launch/empty_world.launch">
    <arg name="world_name" value="$(find frankenstein_gazebo)/worlds/TAVIL.world"/>
    <arg name="paused" value="false"/>
    <arg name="use_sim_time" value="true"/>
    <arg name="gui" value="true"/>
    <arg name="recording" value="false"/>
    <arg name="debug" value="false"/>
    <arg name="verbose" value="true" />
  </include>
  <node pkg="tf2_ros" type="static_transform_publisher" name="world_to_odom_broadcaster"
      args="0 0 0 0 0 0 1 world odom" />

  <param name="robot_description" command="$(find xacro)/xacro $(find frankenstein_description)/urdf/frankenstein.xacro"/>

   <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />

  <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher">
    </node>
  <node pkg="rviz" type="rviz" name="rviz" args="-d $(find frankenstein_description)/rviz/frankenstein.rviz">
    </node>

  <node pkg="frankenstein_simulation" type="odometry_node" name="robot_model" />
  <node pkg="frankenstein_simulation" type="visualizer_node" name="path_visualizer" />

  <node name="cartographer_node" pkg="cartographer_ros"
      type="cartographer_node" args="
          -configuration_directory $(find cartographer_ros)/configuration_files
          -configuration_basename frankenstein.lua"
      output="screen">
    <remap from="scan" to="/frankenstein/laser/scan" />
  </node>

  <node name="cartographer_occupancy_grid_node" pkg="cartographer_ros"
      type="cartographer_occupancy_grid_node" args="-resolution 0.05" />
  <node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model" output="screen"
          args="-param robot_description -urdf -model frankenstein " />

</launch>

When I comment out the /world_to_odom_broadcaster rviz gives error saying that Unknown frame world and tf_tree returns the tree below: broadcast_commented

Which means that the cartographer_node is not broadcasting this transformation.

Regarding odom => robot_frame

The transformation is broadcasted in the odometry node (where the odomentry is calculated given the joint states). Please see the snippet code below:

void publishOdometry(double x, double y, double alpha, double v, double omega, ros::Time current_time) {

        nav_msgs::Odometry odom_msg;
        odom_msg.header.stamp = current_time;
        odom_msg.header.frame_id = "odom";
        odom_msg.child_frame_id = "robot_frame";

        odom_msg.pose.pose.position.x = x;
        odom_msg.pose.pose.position.y = y;
        tf2::Quaternion q;
        q.setRPY(0, 0, alpha);
        odom_msg.pose.pose.orientation = tf2::toMsg(q);

        odom_msg.twist.twist.linear.x = vx;
        odom_msg.twist.twist.linear.y = vy;
        odom_msg.twist.twist.angular.z = omega;
        odom_msg.pose.covariance = {Pk[0][0], Pk[0][1], 0, 0, 0, Pk[0][2],
                            Pk[1][0], Pk[1][1], 0, 0, 0, Pk[1][2],
                            0, 0, 0, 0, 0, 0,
                            0, 0, 0, 0, 0, 0,
                            0, 0, 0, 0, 0, 0,
                            Pk[2][0], Pk[2][1], 0, 0, 0, Pk[2][2]};
        odom_pub.publish(odom_msg);

        transformStamped.header.stamp = current_time;
        transformStamped.header.frame_id = "odom";
        transformStamped.child_frame_id = "robot_frame";
        transformStamped.transform.translation.x = x;
        transformStamped.transform.translation.y = y;
        transformStamped.transform.translation.z = 0.0;
        transformStamped.transform.rotation = tf2::toMsg(q);

        br.sendTransform(transformStamped);

When I comment out the broadcasting part of the code, the tree becomes as below:

cpp_commented

the cartographer_node is not broadcasting this transformation as well even though when I commented both of them.

When do you think the problem is ? Thanks

AmineDh98 commented 6 months ago

I identified the problem. Because the LIDAR is not at position z=0, and it is not at the same vertical level with the robot_frame . It is not detecting scan. When I changed tracking_frame = "lidar_link" , and after commenting out the 2 transformations above, I started to see this tree: frames The only problem now is how to configure the cartographer so that it knows the LIDAR pose ?

maker-ATOM commented 6 months ago

What exactly do you mean by

It is not detecting scan.

It is not necessary for LIDAR to align with robot_frame in the z-axis.

Are able to visualise /scan data in rviz?

AmineDh98 commented 6 months ago

Yes I can visualize /scan in Rviz Could you please explain what is tracking_frame exactly ? Because when follow the tutorials and write: tracking_frame = "robot_frame" it doesnt broadcast the transformations and keeps showing this warning Dropped empty horizontal range data Only if I set the tracking_frame = "lidar_link" it performs the broadcasting and shows the map.

maker-ATOM commented 6 months ago

According to the documentation,

tracking_frame
   The ROS frame ID of the frame that is tracked by the SLAM algorithm. If an IMU is used, it
   should be at its position, although it might be rotated. A common choice is “imu_link”.

But setting it to base_link works in my case.

AmineDh98 commented 6 months ago

An update !

I figured out how to make it work with tracking_frame = "robot_frame" by setting the z range of the 2Dtrajectory builder as below:

TRAJECTORY_BUILDER_2D.min_z =3.
TRAJECTORY_BUILDER_2D.max_z =4.

The range should include the pose of the LIDAR w.r.t the robot_frame. This was missing before (I had to be more careful when reading the documentation). Thanks for your help !