ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Getting LiDAR data relative to base_link

asked 2022-01-29 06:01:35 -0500

Roshan gravatar image

updated 2022-01-31 06:38:54 -0500

Hello, I would like to find the distance between two turtlebots using a LiDAR. Up until now I just used the default /scan and took the ranges directly and averaged it up. This got me decent results, but I saw that the distance was a little more than what it should have been. The issue was that my other measurements were relative to the base_link, while the LiDAR gives data relative to the base_scan. Once I figured that out I found the difference in distance between the base_link and base_scan and subtracted that from the LiDAR measurements, this gives the range data relative to the base_link.

Wondering if there's any way of getting the LiDAR angle measurements relative to the base_link too, or if it should be accurate enough to just leave it relative to the base_scan.

Edit:

Using the C++ example given in the answer below, I tried converting it to Python instead. This is the resulting code:

import rospy
from geometry_msgs.msg import Twist
import math
import tf2_ros
import numpy as np
import sensor_msgs.point_cloud2 as pc2
from sensor_msgs.msg import PointCloud2
from tf2_sensor_msgs.tf2_sensor_msgs import do_transform_cloud


    class move_bot:
        def __init__(self):
            self.sub2 = rospy.Subscriber("tb3_1/point_cloud",PointCloud2,self.pointcloud_callback)

        def pointcloud_callback(self,msg):
            try:
                trans_pc = tfBuffer.lookup_transform("tb3_1/base_link", msg.header.frame_id, rospy.Time(0))
            except(tf2_ros.LookupException, tf2_ros.ConnectivityException, tf2_ros.ExtrapolationException):
                rospy.logwarn(ex)
            cloud_out = do_transform_cloud(msg,trans_pc)
            print(cloud_out)



    if __name__ == '__main__':
        rospy.init_node("vision_lidar")
        rate = rospy.Rate(10) #Loop rate 
        obj = move_bot()


        #Initialize /tf transform listener
        tfBuffer = tf2_ros.Buffer()
        listener = tf2_ros.TransformListener(tfBuffer)

        #Wait for first message from callbacks. 
        rospy.wait_for_message("tb3_1/point_cloud",PointCloud2)

        #Makes sure that timer starts correctly and avoids race conditions
        prevTime = 0
        while not prevTime:
            prevTime = rospy.Time.now()

        while not rospy.is_shutdown():
            try:
                currentTime = rospy.Time.now()

                delT = currentTime-prevTime

                rate.sleep()

            except KeyboardInterrupt:
                break

This gives

header: 
  seq: 0
  stamp: 
    secs: 0
    nsecs:         0
  frame_id: "tb3_1/base_link"
height: 1
width: 7
fields: 
  - 
    name: "x"
    offset: 0
    datatype: 7
    count: 1
  - 
    name: "y"
    offset: 4
    datatype: 7
    count: 1
  - 
    name: "z"
    offset: 8
    datatype: 7
    count: 1
  - 
    name: "intensity"
    offset: 12
    datatype: 7
    count: 1
  - 
    name: "index"
    offset: 16
    datatype: 5
    count: 1
is_bigendian: False
point_step: 20
row_step: 140
data: [129, 8, 97, 63, 0, 0, 0, 0, 35, 219, 249, 61, 0, 0, 0, 0, 0, 0, 0, 0, 189, 191, 100, 63, 183, 77, 137, 60, 35, 219, 249, 61, 0, 0, 0, 0, 1, 0, 0, 0, 84, 241, 104, 63, 2, 178, 11, 61, 35, 219, 249, 61, 0, 0, 0, 0, 2, 0, 0, 0, 22, 211, 107, 63, 207, 13, 84, 189, 35, 219, 249, 61, 0, 0, 0, 0, 100, 1, 0, 0, 203, 92, 104, 63, 225, 89, 11, 189, 35, 219, 249, 61, 0, 0, 0, 0, 101, 1, 0, 0, 13, 165, 102, 63, 208, 83, 138, 188, 35, 219, 249, 61, 0, 0, 0, 0, 102, 1, 0, 0, 83, 120, 103, 63, 238, 43, 156, 54 ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2022-01-29 14:32:05 -0500

updated 2022-01-30 21:06:55 -0500

You are correct. The data you get from your sensors are in their own frame of reference. For distance / range measurements, its often a good idea to have them in the frame of reference of your robot; usually base_link. Fortunately ROS provides the tf library for this purpose. You can find more information here.

I highly recommend you go through their tutorials but the one you are looking for is a tf listener python / C++.

Once you have this transform, you can apply it to your scan. Unfortunately laserscans aren't very easy to work with and I'd suggest you convert your scan to a PointCloud2 msg and use the features PCL has to offer.

EDIT: Based on your LiDAR scan msg type, here are my suggestions:

Use the laserscan_to_pointcloud package to convert your laserscan to PointCloud2 type. You can just include this into your launch file:

<node pkg="pointcloud_to_laserscan" type="laserscan_to_pointcloud_node" name="laserscan_to_pointcloud">
    <remap from="scan_in" to="/<your scan topic>"/>
    <remap from="cloud" to="/<your cloud topic>"/>
</node>

Then, in your LiDAR callback, convert from ROS type to PCL type, lookup tf and apply it to your data. This is a simple pipeline

void CloudCallback(const sensor_msgs::PointCloud2ConstPtr &cloud_in) 
{
// copy point cloud
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
pcl::fromROSMsg(*cloud_in, *cloud);

// Transform point cloud
try {
  transform_stamped = tf_buffer.lookupTransform("base_link",
                                            cloud_in->header.frame_id,
                                            ros::Time(0),
                                            ros::Duration(1));
} catch (tf2::TransformException &ex) {
  ROS_ERROR("%s", ex.what());
  return;
}

// apply transform to point cloud
Eigen::Affine3d pc_to_base_link = tf2::transformToEigen(transform_stamped);
pcl::transformPointCloud(*cloud, *cloud,
                         pc_to_base_link);

/* 
Use cloud as you normally would 
*/

// convert back to ROS
sensor_msgs::PointCloud2 cloud_out;
pcl::toROSMsg(*cloud, cloud_out);
cloud_out.header.frame_id = cloud_in->header.frame_id;
cloud_out.header.stamp = ros::Time::now();

// publish
publisher.publish(cloud_out);

}
edit flag offensive delete link more

Comments

Hello, yes I have the transform between the base_link and base_scan, but I don't understand what to do with the LiDAR data once I have this. The LiDAR data is given in ranges and angles increments, so how do I use this together with the transform?

Roshan gravatar image Roshan  ( 2022-01-29 14:52:15 -0500 )edit

What type is your LiDAR data in? Is it a sensor_msgs: laserscan? or PointCloud? or some custom type?

Akhil Kurup gravatar image Akhil Kurup  ( 2022-01-30 15:07:40 -0500 )edit

It is sensor_msgs:LaserScan

Roshan gravatar image Roshan  ( 2022-01-30 17:57:59 -0500 )edit

Added information to the original post

Roshan gravatar image Roshan  ( 2022-01-31 04:52:43 -0500 )edit

I'd suggest using the pointcloud_to_laserscan node to convert back to sensor_msgs/LaserScan type. It should be accurate since the node is stable and mature enough. A quick and dirty check would be to show both the msgs in rviz and compare visually

Akhil Kurup gravatar image Akhil Kurup  ( 2022-01-31 11:53:27 -0500 )edit

Yeah I managed to get it working and they seem to be matching up well. Only issue I found while using it was that despite putting the min_angle at 0 and max_angle at 2pi, it only managed to detect in a 180 degree cone

Roshan gravatar image Roshan  ( 2022-01-31 12:00:49 -0500 )edit

That sounds like some issue with your LiDAR configuration possibly

Akhil Kurup gravatar image Akhil Kurup  ( 2022-01-31 12:02:33 -0500 )edit
1

Yeah, will keep testing and post a new question if I keep having issues with it. Thank you for your help!

Roshan gravatar image Roshan  ( 2022-01-31 12:19:25 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2022-01-29 06:01:35 -0500

Seen: 401 times

Last updated: Jan 31 '22