koide3 / hdl_localization

Real-time 3D localization using a (velodyne) 3D LIDAR
BSD 2-Clause "Simplified" License
775 stars 309 forks source link

Point clouds frame_id different than sensor frame_id #38

Closed ricber closed 4 years ago

ricber commented 4 years ago

Hi Koide! Are you managing the possibility that the point clouds frame_id could be different than the sensor frame_id? For example, in my case, I'm using the OS1 Ouster sensor and I have the os1_sensor frame with its two childs, namely, os1_lidar and os1_imu. As far as I see from the code, it seems that you are assuming the frame_id of the point clouds the same of the sensor. Indeed, your code computes the odometry from map to lidar_frame, instead, It should give the possibility to publish the transform from map to sensor_frame. The same holds for the IMU, it is assumed to be in the same frame of the point clouds. Is this right?

The idea would be to give the user the possibility to choose the frame_id against which to publish the odometry. Indeed, it is hardcoded in the hdl_localization_nodelet.cpp file that child_frame_id="velodyne"

/**
   * @brief publish odometry
   * @param stamp  timestamp
   * @param pose   odometry pose to be published
   */
  void publish_odometry(const ros::Time& stamp, const Eigen::Matrix4f& pose) {
    // broadcast the transform over tf
    geometry_msgs::TransformStamped odom_trans = matrix2transform(stamp, pose, "map", "velodyne");
    pose_broadcaster.sendTransform(odom_trans);

    // publish the transform
    nav_msgs::Odometry odom;
    odom.header.stamp = stamp;
    odom.header.frame_id = "map";

    odom.pose.pose.position.x = pose(0, 3);
    odom.pose.pose.position.y = pose(1, 3);
    odom.pose.pose.position.z = pose(2, 3);
    odom.pose.pose.orientation = odom_trans.transform.rotation;

    odom.child_frame_id = "velodyne";
    odom.twist.twist.linear.x = 0.0;
    odom.twist.twist.linear.y = 0.0;
    odom.twist.twist.angular.z = 0.0;

    pose_pub.publish(odom);
  }
ricber commented 4 years ago

Fixed #39

Marine98k commented 1 year ago

hi, ricber! I want to know whether you have used an internal 6-axis IMU or added an external 9-axis IMU.and how you edit the file ? thanks