Getting LiDAR data relative to base_link
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 ...