ROS2 Python LaserScan to Transformed Pointcloud major issues
Hi All and much appreciated for the help
I am using the waffle pi on ROS2 Humble and I am having major issues transforming a pointcloud to the base frame. The laserscan is fine and generates correctly on the first pass but as soon as the robot moves the points move relative to the robot as no transform is being applied. I cannot seem to get any of the transform methods to work in ROS2 python.
The first normal method of using the laser geometry package to use the method transformLaserScanToPointCloud() is not available in the python package for ROS2 only the cpp. The projectLaser() function works just fine but stays relative to robot frame not the base frame.
The second method of using tf2sensormsgs.dotransformcloud(msg, t) after manually grabbing the transform with lookuptransform() ans using projectLaser() to convert to PointCloud2 also does not work. I included the tf2sensor_msgs.py in my package and installed PyKDL for python3 and changed the import rospy to import rclpy in an attempt to update the package.
This fails at line 171 of tf2sensormsgs.py with packinto(buff,offset,*p) struct.error: packinto expected 5 items for packing (got 3).
Help please.
How is it possible to transform a laserscan to the base frame in ROS2 with python without one of these methods?
Many Thanks
Elliot
Asked by Elliot on 2023-04-25 06:20:58 UTC
Answers
So, I believe this is the answer to your question, I am new to lidar and looked here to get answers --- and this is what i have concerning the topic.....
points too....
from sensor_msgs.msg import LaserScan
import laser_geometry.laser_geometry as lg
from laser_geometry import LaserProjection
import sensor_msgs.point_cloud2 as pcl2
###### LaserScan #################################################################
def laserscan():
msg = LaserScan()
msg.angle_min = -1.57
msg.angle_max = 1.57
msg.angle_increment = 0.1
msg.time_increment = 0.001
msg.scan_time = 0.05
msg.range_min = 0.0
msg.range_max = 10.0
msg.ranges = [1.0] * int((msg.angle_max - msg.angle_min) / msg.angle_increment)
msg.intensities = [1] * len(msg.ranges)
return msg
##### generator ####################################################################
def generator():
msg = laserscan() # return value msg from laserscan()
lp = lg.LaserProjection() # make lp out of modules
pointcloud2 = lp.projectLaser(msg) #use lp to get a pcl from scan
pointlist = pcl2.read_points_list(pointcloud2)
print (pointlist)
generator()
##################################################################################
Asked by JayT on 2023-07-27 15:21:18 UTC
Comments
Did you somehow manage to get it working? I am having the exact same problem.
Asked by SimJon1 on 2023-05-24 09:57:34 UTC