Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

I can't use IMU in cartographer #278

Closed
sunmk2006 opened this issue Mar 15, 2017 · 5 comments
Closed

I can't use IMU in cartographer #278

sunmk2006 opened this issue Mar 15, 2017 · 5 comments

Comments

@sunmk2006
Copy link

only Lidar can be used to built map,but when i joined the IMU, there is an error:
[ INFO] [1489563685.321344447]: I0315 15:41:25.000000 16889 map_builder_bridge.cc:37] Added trajectory with ID '0'.
[ WARN] [1489563685.525837849]: W0315 15:41:25.000000 16889 tf_bridge.cc:51] Lookup would require extrapolation at time 1489563685.525495000, but only time 1489563685.530481674 is in the buffer, when looking up transform from frame [imu] to frame [base_link]
[ WARN] [1489563685.528745250]: W0315 15:41:25.000000 16889 tf_bridge.cc:51] Lookup would require extrapolation at time 1489563685.477205200, but only time 1489563685.529379831 is in the buffer, when looking up transform from frame [laser] to frame [base_link]
F0315 15:41:25.544420 16889 sensor_bridge.cc:67] Check failed: sensor_to_tracking->translation().norm() < 1e-5 The IMU frame must be colocated with the tracking frame. Transforming linear acceleration into the tracking frame will otherwise be imprecise.
[FATAL] [1489563685.544553362]: F0315 15:41:25.000000 16889 sensor_bridge.cc:67] Check failed: sensor_to_tracking->translation().norm() < 1e-5 The IMU frame must be colocated with the tracking frame. Transforming linear acceleration into the tracking frame will otherwise be imprecise.
*** Check failure stack trace: ***
@ 0x7fc7ff7a1daa (unknown)
@ 0x7fc7ff7a1ce4 (unknown)
@ 0x7fc7ff7a16e6 (unknown)
@ 0x7fc7ff7a4687 (unknown)
@ 0x505921 cartographer_ros::SensorBridge::HandleImuMessage()
@ 0x4eb7ac ZN5boost6detail8function26void_function_obj_invoker1IZN16cartographer_ros12_GLOBAL__N_13RunEvEUlRKNS_10shared_ptrIKN11sensor_msgs4Imu_ISaIvEEEEEE2_vSD_E6invokeERNS1_15function_bufferESD
@ 0x4f0a3b boost::detail::function::void_function_obj_invoker1<>::invoke()
@ 0x4f69e8 ros::SubscriptionCallbackHelperT<>::call()
@ 0x7fc7fc68e6b5 (unknown)
@ 0x7fc7fc648107 (unknown)
@ 0x7fc7fc648c33 (unknown)
@ 0x7fc7fc6911e5 (unknown)
@ 0x7fc7fc678e0b (unknown)
@ 0x4ec78b cartographer_ros::(anonymous namespace)::Run()
@ 0x4e9bbd main
@ 0x7fc7fb44bf45 (unknown)
@ 0x4eb267 (unknown)
@ (nil) (unknown)
[cartographer_node-1] process has died [pid 16889, exit code -6, cmd /home/wiki/google_ws/install_isolated/lib/cartographer_ros/cartographer_node -configuration_directory /home/wiki/google_ws/install_isolated/share/cartographer_ros/configuration_files -configuration_basename my_backpack_2d.lua __name:=cartographer_node __log:=/home/wiki/.ros/log/eb12c7c4-0951-11e7-ab03-f44d30664634/cartographer_node-1.log].
log file: /home/wiki/.ros/log/eb12c7c4-0951-11e7-ab03-f44d30664634/cartographer_node-1*.log

@damonkohler
Copy link
Contributor

Here's your issue:

F0315 15:41:25.544420 16889 sensor_bridge.cc:67] Check failed: sensor_to_tracking->translation().norm() < 1e-5 The IMU frame must be colocated with the tracking frame. Transforming linear acceleration into the tracking frame will otherwise be imprecise.

Change your tracking frame to be the IMU and that should fix it.

@KushnirDmytro
Copy link

NB: If you are using Gazebo, there are a crucial issue:
Locate where your slam package is (for me it is done via 'rospack turtlebot3_slam)
edit 'config/turtlebot3_lds_2d.lua' in that location:
on line #23 you will find an "Easter egg" from developers:
tracking_frame = "imu_link", -- imu_link, If you are using gazebo, use 'base_footprint' (libgazebo_ros_imu's bug)
using that tip: replace "imu_link" with "base_footprint". Without this fix, there will be constant failure mentioning that the IMU frame has to be collocated with your 'tracking frame'.

@crankler
Copy link

NB: If you are using Gazebo, there are a crucial issue:
Locate where your slam package is (for me it is done via 'rospack turtlebot3_slam)
edit 'config/turtlebot3_lds_2d.lua' in that location:
on line #23 you will find an "Easter egg" from developers:
tracking_frame = "imu_link", -- imu_link, If you are using gazebo, use 'base_footprint' (libgazebo_ros_imu's bug)
using that tip: replace "imu_link" with "base_footprint". Without this fix, there will be constant failure mentioning that the IMU frame has to be collocated with your 'tracking frame'.

but when I replace "imu_link" with "base_footprint" and roslaunch , there show error W0527 10:09:53.000000 26453 tf_bridge.cc:52] "base_footprint" passed to lookupTransform argument target_frame does not exist.
so how can I do in the next ?

@EdwardAbrosimov
Copy link

In addition: if you use turtlebot3_slam in Gazebo, you must use param
<arg name="configuration_basename" default="turtlebot3_lds_2d_gazebo.lua"/>
instead of <arg name="configuration_basename" default="turtlebot3_lds_2d.lua"/> in turtlebot3_slam.launch. It fix this error.

@nyangshawbin
Copy link

Hi, I am facing the same issue. I am using Cartographer on a rosbag offline, recorded from Gazebo on a Husky robot. Cartographer only works when I set 'tracking frame' into base_link, does this mean that I am not using IMU?

I have tried to modify the original husky urdf so that its colocated with the tracking frame. I set the imu_link to share the same origin as the base_link, but am still facing the same error. Would really appreciate if anyone can help me point out if im doing anything wrong, thank you in advance!

Below are some files to better understand my setup:
Husky.lua
Modified Husky URDF

@3473f 3473f mentioned this issue Oct 25, 2020
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

6 participants