PointCloud2 read_points unpack_from problem

asked 2018-04-30 12:43:21 -0500

SancheZ gravatar image

Hey, I'm working on a object recognition framework that uses deep learning methods. Given the locations of the objects in the image (bounding box), I use the PointCloud publised by a Kinect 2, to locate those.

Currently, I'm working with ROS Kinetic and I'm developing in python.

Sometimes, trying to obtain the xyz points of the bounding box, using the read_points method I receive the following error:

File "/home/some1/catkin_ws/src/sem_mapper_isr/sem_mapper_markers/nodes/object_mapper.py", line 205, in get_object_3D_points points = np.array(list(pc2.read_points(self.curr_pc,field_names = ("x", "y", "z"), skip_nans=True, uvs=bb_pts))) File "/opt/ros/kinetic/lib/python2.7/dist-packages/sensor_msgs/point_cloud2.py", line 83, in read_points p = unpack_from(data, (row_step * v) + (point_step * u)) error: unpack_from requires a buffer of at least 12 bytes

This error doesn't happen everytime I try to obtain the xyz points. Sometimes, there is no problem. The code is extensive, I will try to show their important parts for this case.

Imports:

import rospy
from sensor_msgs.msg import PointCloud2, PointField
import sensor_msgs.point_cloud2 as pc2

PointCloud Callback definition:

self.pc_xyz_sub = rospy.Subscriber(sub_pointcloud_topic, PointCloud2, self.pointcloud_callback, queue_size=2)

PointCloud Callback:

def pointcloud_callback(self, pointcloud_msg):
    self.pc_message_locker.acquire()
    self.curr_pc = pointcloud_msg
    self.pc_message_locker.release()

Where I try to obtain the xyz points:

def get_object_3D_points(self,width_min,width_max,height_min,height_max,view_path):
    bb_pts=((i,j) for i in xrange(width_min,width_max+1) for j in xrange(height_min, height_max+1))#pixels of the image to verify in the pointcloud
    self.pc_message_locker.acquire() #lock the pc message -> dont change/access current pc message at same time
    points = np.array(list(pc2.read_points(self.curr_pc,field_names = ("x", "y", "z"), skip_nans=True, uvs=bb_pts)))
    self.pc_message_locker.release()

I'm subscribing to the camera/depth_registered/points published by openni using Kinect.

I searched for that problem with the unpack and found nothing until now, do you have any idea what can be happening? Thanks for your patience, SancheZ

edit retag flag offensive close merge delete

Comments

did u find a solution for this??

MohamedEhab gravatar image MohamedEhab  ( 2019-04-18 14:04:22 -0500 )edit

I have the same issue.

Redhwan gravatar image Redhwan  ( 2022-10-12 03:42:21 -0500 )edit