Skip to content

ROS best practise: tf listener instead of extrinsics params? #94

@greymfm

Description

@greymfm

I noticed the extrinsics (for frames base to lidar and base to imu) are in a config file - A more ROS-compatible way would be to directly read them from the ROS transformation tree. I have tested the idea (code below) and it works - maybe I should file a pull request for it and make the idea optional?

Tested with my robot simulator (ROS1 noetic, MID360 simulation):

Image Image

In 'odom.cc' the existing extrinsics config code for 'extrinsics.baselink2lidar_T' is replaced:

  tf::TransformListener tf_listener;

  // wait for transform: base_link -> imu_frame
  ROS_INFO("DLIO: waiting for transform: base_link -> imu_frame");
  tf::StampedTransform tf_b2i;
  try {
    tf_listener.waitForTransform(this->baselink_frame, this->imu_frame, ros::Time(0), ros::Duration(5.0));
    tf_listener.lookupTransform(this->baselink_frame, this->imu_frame, ros::Time(0), tf_b2i);
  } catch (tf::TransformException &ex) {
    ROS_ERROR("Transform base_link -> imu_frame not found: %s", ex.what());
    ros::shutdown();
    return;
  }

  // base_link -> imu_frame
  this->extrinsics.baselink2imu.t = Eigen::Vector3f(
    tf_b2i.getOrigin().x(),
    tf_b2i.getOrigin().y(),
    tf_b2i.getOrigin().z()
  );

  tf::Matrix3x3 tf_rot_b2i(tf_b2i.getRotation());
  Eigen::Matrix3f R_b2i;
  for (int i = 0; i < 3; ++i)
    for (int j = 0; j < 3; ++j)
      R_b2i(i, j) = tf_rot_b2i[i][j];

  this->extrinsics.baselink2imu.R = R_b2i;
  this->extrinsics.baselink2imu_T = Eigen::Matrix4f::Identity();
  this->extrinsics.baselink2imu_T.block(0, 3, 3, 1) = this->extrinsics.baselink2imu.t;
  this->extrinsics.baselink2imu_T.block(0, 0, 3, 3) = this->extrinsics.baselink2imu.R;

  // wait for transform: base_link -> lidar_frame
  ROS_INFO("DLIO: waiting for transform: base_link -> lidar_frame");
  tf::StampedTransform tf_b2l;
  try {
    tf_listener.waitForTransform(this->baselink_frame, this->lidar_frame, ros::Time(0), ros::Duration(5.0));
    tf_listener.lookupTransform(this->baselink_frame, this->lidar_frame, ros::Time(0), tf_b2l);
  } catch (tf::TransformException &ex) {
    ROS_ERROR("Transform base_link -> lidar_frame not found: %s", ex.what());
    ros::shutdown();
    return;
  }

  // base_link -> lidar_frame
  this->extrinsics.baselink2lidar.t = Eigen::Vector3f(
    tf_b2l.getOrigin().x(),
    tf_b2l.getOrigin().y(),
    tf_b2l.getOrigin().z()
  );

  tf::Matrix3x3 tf_rot_b2l(tf_b2l.getRotation());
  Eigen::Matrix3f R_b2l;
  for (int i = 0; i < 3; ++i)
    for (int j = 0; j < 3; ++j)
      R_b2l(i, j) = tf_rot_b2l[i][j];

  this->extrinsics.baselink2lidar.R = R_b2l;
  this->extrinsics.baselink2lidar_T = Eigen::Matrix4f::Identity();
  this->extrinsics.baselink2lidar_T.block(0, 3, 3, 1) = this->extrinsics.baselink2lidar.t;
  this->extrinsics.baselink2lidar_T.block(0, 0, 3, 3) = this->extrinsics.baselink2lidar.R;

Also, I commented out the transformation publishing (transform: baselink to lidar and transform: baselink to imu) in the DLIO code as my simulation already does this.

Metadata

Metadata

Assignees

No one assigned

    Labels

    No labels
    No labels

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions