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

Revision history [back]

You can set cartographer to publish odometry, or else you can generate odometry using some other algorithms. But you cannot do it at the same time.

reference: https://google-cartographer-ros.readthedocs.io/en/latest/configuration.html

So if you want to only use cartographer, so you do not want to use a supplementary odometry, set use_odometry to false, and published frame should be base_footprint or base_link. Because a mapping procedure normally publish tf from map to odom, which indicates the drift error, plus a raw odometry we will have the pose of base_link w.r.t. map.

Then you can configure whether you want cartographer provide the odom frame. set provide_odom_frame to false the mapping process will give you base_link to map directly, however as a convention, better set provide the odom frame and the odom frame will be published. So you can have the odom info from cartographer.

  map_frame = "map",
  tracking_frame = "IMU_link",

  use_odometry = false,
  published_frame = "base_footprint",

  provide_odom_frame = true,
  odom_frame = "odom",

As you have already disabled odometry, you could set imu to true

  TRAJECTORY_BUILDER_2D.use_imu_data = true

Another case is that you can use some other method to generate odom instead of cartographer. For example if you use velodyne you can try https://github.com/laboshinl/loam_velodyne, or rplidar you can try https://github.com/MAPIRlab/rf2o_laser_odometry

if you have wheel encoder, it is similar configuration. if you set provide odom frame to true, cartographer node wont die but the odom frame will oscillating because tf to odom is broadcasted by two nodes. and odom_frame is not used.

Even if you set imu to true, it will not adjust the perception according to imu readings.

  map_frame = "map",
  tracking_frame = "base_footprint",

  use_odometry = true,
  published_frame = "odom",

  provide_odom_frame = false,
  odom_frame = "odom",

(Some conclusion is not fully tested but I think it will be.)

If you are interested in the full code, I am busy updating an racecar project recently. you could check this out: https://github.com/tianbot/tianbot_racecar

You can set cartographer to publish odometry, or else you can generate odometry using some other algorithms. But you cannot do it both at the same time.

You may need to know that odometry which provided by wheel encoder is odom->base_link, map->odom is the drift error and provided by mapping process.

reference: https://google-cartographer-ros.readthedocs.io/en/latest/configuration.html

So if you If you only want to only use cartographer, so you cartographer with your lidar and IMU, and do not want to use a supplementary odometry, set use_odometry to false, and published frame should be base_footprint or base_link. Because a mapping procedure normally publish tf from map to odom, which indicates the drift error, error. The drift error plus a raw odometry we will have the pose of base_link w.r.t. map.

Then you can configure whether you want cartographer provide the odom frame. set provide_odom_frame to false the mapping process will give you base_link to map directly, however as a convention, better set provide the odom frame to true and the odom frame will be published. So Then you can have the odom info from cartographer.

  map_frame = "map",
  tracking_frame = "IMU_link",

  use_odometry = false,
  published_frame = "base_footprint",

  provide_odom_frame = true,
  odom_frame = "odom",

As you have already disabled odometry, you could set imu to truetrue, this gives better SLAM result.

  TRAJECTORY_BUILDER_2D.use_imu_data = true

Another case is that you can use some other method to generate odom instead of cartographer. For example if you use velodyne you can try https://github.com/laboshinl/loam_velodyne, or rplidar you can try https://github.com/MAPIRlab/rf2o_laser_odometry

if you have wheel encoder, it is similar configuration. if you set provide odom frame to true, cartographer node wont die but the odom frame will oscillating because tf to odom is broadcasted by two nodes. and In this case, odom_frame is not used.has no use.

Even if you set imu to true, it will not adjust the perception according to imu readings. Sensor readings are attached to base_link which is provided by odom->base_link which is provided by odometry.

  map_frame = "map",
  tracking_frame = "base_footprint",

  use_odometry = true,
  published_frame = "odom",

  provide_odom_frame = false,
  odom_frame = "odom",

(Some conclusion is not fully tested but I think it will be.)

If you are interested in the full code, I am busy updating an racecar project recently. you could check this out: https://github.com/tianbot/tianbot_racecar

You can set cartographer to publish odometry, or else you can generate odometry using some other algorithms. But you cannot do both at the same time.

You may need to know that odometry which provided by wheel encoder is odom->base_link, map->odom is the drift error and provided by mapping process.

reference: https://google-cartographer-ros.readthedocs.io/en/latest/configuration.html

If you only want to use cartographer with your lidar and IMU, and do not want to use a supplementary odometry, set use_odometry to false, and published frame should be base_footprint or base_link. Because a mapping procedure normally publish tf from map to odom, which indicates the drift error. The drift error plus a raw odometry we will have the pose of base_link w.r.t. map.

Then you can configure whether you want cartographer provide the odom frame. set provide_odom_frame to false the mapping process will give you base_link to map directly, however as a convention, better set provide the odom frame to true and the odom frame will be published. Then you can have the odom info from cartographer.

  map_frame = "map",
  tracking_frame = "IMU_link",

  use_odometry = false,
  published_frame = "base_footprint",

  provide_odom_frame = true,
  odom_frame = "odom",

As you have already disabled odometry, you could set imu to true, this gives better SLAM result.

  TRAJECTORY_BUILDER_2D.use_imu_data = true

Another case is that you can use some other method to generate odom instead of cartographer. For example if you use velodyne you can try https://github.com/laboshinl/loam_velodyne, or rplidar you can try https://github.com/MAPIRlab/rf2o_laser_odometry

if you have wheel encoder, it is similar configuration. if you set provide odom frame to true, cartographer node wont die but the odom frame will oscillating because tf to odom is broadcasted by two nodes. In this case, odom_frame has no use.

Even if you set imu to true, it will not adjust the perception according to imu readings. Sensor readings are attached to base_link which is provided by odom->base_link which is provided by odometry.

  map_frame = "map",
  tracking_frame = "base_footprint",

  use_odometry = true,
  published_frame = "odom",

  provide_odom_frame = false,
  odom_frame = "odom",

(Some conclusion is not fully tested but I think it will be.)

If you are interested in the full code, I am busy updating an racecar project recently. you could check this out: https://github.com/tianbot/tianbot_racecar

https://github.com/tianbot/tianracer