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

imu loop back #32

Open
yangqifan913 opened this issue Nov 4, 2024 · 15 comments
Open

imu loop back #32

yangqifan913 opened this issue Nov 4, 2024 · 15 comments
Labels
documentation Improvements or additions to documentation help wanted Extra attention is needed

Comments

@yangqifan913
Copy link

频繁地报错imu loop back,clear buffer。看IMU数据经常会回滚到过去一段时间,然后又恢复正常。不进行时间同步就不会出现这个问题。
Screenshot from 2024-11-04 15-52-26

@yangqifan913
Copy link
Author

忘了说用的是mid360

@xuankuzcr
Copy link
Owner

xuankuzcr commented Nov 4, 2024

  1. 检查下是否供地,以及买的网线是否有屏蔽层。
  2. 如果实在无法修复的话,可以在imu的回调函数里面加一句,如果上一个imu msg的时间戳小于当前帧imu的话,就把回退的时间补偿回来。
  3. 也可以直接在livox_ros_driver里面修复,用下面代码替换这个函数。[但接线没问题的话是没有回退的]
uint32_t Lddc::PublishImuData(LidarDataQueue *queue, uint32_t packet_num,
                              uint8_t handle) {
  volatile uint64_t timestamp = 0;
  uint32_t published_packet = 0;

  sensor_msgs::Imu imu_data;
  imu_data.header.frame_id = "livox_frame";

  uint8_t data_source = lds_->lidars_[handle].data_src;
  StoragePacket storage_packet;
  QueuePrePop(queue, &storage_packet);
  LivoxEthPacket *raw_packet =
      reinterpret_cast<LivoxEthPacket *>(storage_packet.raw_data);
  timestamp = GetStoragePacketTimestamp(&storage_packet, data_source);
  if (timestamp >= 0) {

    if (timestamp_last_imu_ > timestamp) {
      diff_t_imu_ = timestamp_last_imu_ - timestamp;
    }

    if (diff_t_imu_ > 39809238968) {
      cnt_imu_ = ((int)((float)diff_t_imu_ / 40000000000.0));
      timestamp = timestamp + (cnt_imu_ + 1) * 40000000000;
    }
    imu_data.header.stamp =
        ros::Time(timestamp / 1000000000.0); // to ros time stamp
    timestamp_last_imu_ = timestamp;
  }

  uint8_t point_buf[2048];
  LivoxImuDataProcess(point_buf, raw_packet);

  LivoxImuPoint *imu = (LivoxImuPoint *)point_buf;
  imu_data.angular_velocity.x = imu->gyro_x;
  imu_data.angular_velocity.y = imu->gyro_y;
  imu_data.angular_velocity.z = imu->gyro_z;
  imu_data.linear_acceleration.x = imu->acc_x;
  imu_data.linear_acceleration.y = imu->acc_y;
  imu_data.linear_acceleration.z = imu->acc_z;

  QueuePopUpdate(queue);
  ++published_packet;

  ros::Publisher *p_publisher = Lddc::GetCurrentImuPublisher(handle);
  if (kOutputToRos == output_type_) {
    p_publisher->publish(imu_data);
  } else {
    if (bag_ && enable_imu_bag_) {
      bag_->write(p_publisher->getTopic(), ros::Time(timestamp / 1000000000.0),
                  imu_data);
    }
  }
  return published_packet;
}

@xuankuzcr
Copy link
Owner

别忘了定义这几个成员变量在class Lddc里。

volatile uint64_t timestamp_last_imu_ = 0;
volatile uint64_t diff_t_imu_;
volatile int cnt_imu_;

@85256638
Copy link

我也出现了同样的错误

频繁地报错imu loop back,clear buffer。看IMU数据经常会回滚到过去一段时间,然后又恢复正常。不进行时间同步就不会出现这个问题。 Screenshot from 2024-11-04 15-52-26

我也出现同样的错误了,把雷达同步线拔了就没出现错误了。。请问你这个IMU数据界面怎么展示的?

@Torchmm
Copy link

Torchmm commented Nov 25, 2024

@xuankuzcr 你好,共地是需要电源地和功能线的地线共地吗?

@85256638
Copy link

@xuankuzcr 你好,共地是需要电源地和功能线的地线共地吗?

@Torchmm ,我之前被这个问题困扰了很久了,一直是IMU loop back。。。 现在终于搞明白了。

我之前的情况是这样的:
整个系统里面有两块电池。第一块是笔记本自带的电池, SMT32通过USB-TTL接笔记本的USB口。 激光雷达是有另外一个12V充电宝。

现在改成:
整个系统里面有两块电池。第一块是笔记本自带的电池, SMT32通过USB-TTL接笔记本的USB口。 激光雷达是有另外一个12V充电宝。 把12V充电宝的负极用导线连接到SMT32的地线。。。。 问题解决。。。

@xuankuzcr 郑博,可能不少新手和我一样犯这个错误导致他们没有复现成功。可以把这个放到首页里面说明一下,避免他们踩同样的坑。

@xuankuzcr
Copy link
Owner

@xuankuzcr 你好,共地是需要电源地和功能线的地线共地吗?

@Torchmm ,我之前被这个问题困扰了很久了,一直是IMU loop back。。。 现在终于搞明白了。

我之前的情况是这样的: 整个系统里面有两块电池。第一块是笔记本自带的电池, SMT32通过USB-TTL接笔记本的USB口。 激光雷达是有另外一个12V充电宝。

现在改成: 整个系统里面有两块电池。第一块是笔记本自带的电池, SMT32通过USB-TTL接笔记本的USB口。 激光雷达是有另外一个12V充电宝。 把12V充电宝的负极用导线连接到SMT32的地线。。。。 问题解决。。。

@xuankuzcr 郑博,可能不少新手和我一样犯这个错误导致他们没有复现成功。可以把这个放到首页里面说明一下,避免他们踩同样的坑。

感谢~我有空把共地放到readme里面强调下

@xuankuzcr xuankuzcr added the help wanted Extra attention is needed label Dec 1, 2024
@xuankuzcr xuankuzcr reopened this Dec 1, 2024
@xuankuzcr xuankuzcr added the documentation Improvements or additions to documentation label Dec 1, 2024
@Torchmm
Copy link

Torchmm commented Dec 2, 2024

@xuankuzcr @85256638 我是一个电池,并且stm32板子和数据采集主板已经共地了,而且信号线的地也共上了,就是说,STM32的地,嵌入式主板的负极,和信号线的地线共在一起了。数据频繁回退。

@Torchmm
Copy link

Torchmm commented Dec 2, 2024

@85256638 @xuankuzcr 微信图片_20241202214324
我把一段时间的数据时间戳绘制出来,发现近似规律性的回退。

@85256638
Copy link

85256638 commented Dec 3, 2024

@xuankuzcr @85256638 我是一个电池,并且stm32板子和数据采集主板已经共地了,而且信号线的地也共上了,就是说,STM32的地,嵌入式主板的负极,和信号线的地线共在一起了。数据频繁回退。

@Torchmm 你这里的"信号线"指的是激光雷达的那个M12线? 给激光雷达供电的那个线也得和STM32供一个地。 另外你不要用livox 官方的ROS driver。 你要用作者提供的 ROS driver,他做过修改:

image

@Torchmm
Copy link

Torchmm commented Dec 3, 2024

@85256638 对,信号线指的是1HZ的PPS信号,他的地线也和电源共线了。

@85256638
Copy link

85256638 commented Dec 4, 2024

image

@Torchmm 你参考一下我的连接方式,整个系统没有使用Livox转接盒子。另外你用了作者的Livox ROS 驱动吗?

@Torchmm
Copy link

Torchmm commented Dec 4, 2024

@85256638 好的,谢谢您,我找到问题了,是模拟的GPS的时间没有按照分秒的60进制和小时的24进制发送的问题。

@xuankuzcr
Copy link
Owner

注:使用新版STM32固件,该Bug之前就修复了 (如下图红框所示)。
旧版固件中,每隔100秒会回退40秒,这是因为在99到100秒进位时,时间会跳变为1分钟,导致回退40秒的问题。因此,需要按照分秒的60进制和小时的24进制格式发送GPRMC数据。
image

@Torchmm
Copy link

Torchmm commented Dec 4, 2024

@xuankuzcr 好的,十分感谢,已经修复。

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
documentation Improvements or additions to documentation help wanted Extra attention is needed
Projects
None yet
Development

No branches or pull requests

4 participants