Closed litzar closed 6 years ago
For Cartographer the IMU does not necessarily be installed in the center of the robot, but it has to be collocated with the tracking frame. The reason is already given in your issue:
"The IMU frame must be colocated with the tracking frame. Transforming linear acceleration into the tracking frame will otherwise be imprecise."
The tracking_frame is 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”. See the documentation for more information about the frames.
I found the imu_link now. Thanks very much.@kdaun
<link
name="imu_link">
<visual>
<origin
xyz="0 0 0" />
<geometry>
<box
size="0.06 0.04 0.02" />
</geometry>
<material
name="orange" />
</visual>
</link>
<link
name="base_link" />
<joint
name="imu_link_joint" type="fixed">
<parent
link="base_link" />
<child
link="imu_link" />
<origin
xyz="0 0 0" />
</joint>
@litzar @kdaun Hello, I am using a 16-lines LIDAR and IMU to build 3D map by cartographer. I tun the parameters and run it with no error, the results are as follows:
There is a big gap with the real environment. I think the map is in a mess. What is the problem of this result? How can I solve it? This is the validate result of my bag:
Here are my files: demo_rsldiar_3d.launch rslidar_3d.launch mydemo_3d.rviz rslidar_2d.urdf rslidar_scan_3d.lua my data bag Could you help me?
Dear all:
Is it that the IMU chip should be installed in the center of the robot, so that the translation().norm()<1e-5? If so, why, how to understand it?
Thanks.
void SensorBridge::HandleImuMessage(const string& topic, const sensor_msgs::Imu::ConstPtr& msg) { CHECK_NE(msg->linear_acceleration_covariance[0], -1); CHECK_NE(msg->angular_velocity_covariance[0], -1); const carto::common::Time time = FromRos(msg->header.stamp); const auto sensor_to_tracking = tfbridge->LookupToTracking( time, CheckNoLeadingSlash(msg->header.frame_id)); if (sensor_to_tracking != nullptr) { CHECK(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."; trajectorybuilder->AddImuData( topic, time, sensor_to_tracking->rotation() ToEigen(msg->linear_acceleration), sensor_to_tracking->rotation() ToEigen(msg->angular_velocity)); } }