Git Product home page Git Product logo

pypcd's Introduction

pypcd

What?

Pure Python module to read and write point clouds stored in the PCD file format, used by the Point Cloud Library.

Why?

You want to mess around with your point cloud data without writing C++ and waiting hours for the template-heavy PCL code to compile.

You tried to get some of the Python bindings for PCL to compile and just gave up.

How does it work?

It parses the PCD header and loads the data (whether in ascii, binary or binary_compressed format) as a Numpy structured array. It creates an instance of the PointCloud class, containing the point cloud data as pc_data, and some convenience functions for I/O and metadata access. See the comments in pypcd.py for some info on the point cloud structure.

Example

import pypcd
# also can read from file handles.
pc = pypcd.PointCloud.from_path('foo.pcd')
# pc.pc_data has the data as a structured array
# pc.fields, pc.count, etc have the metadata

# center the x field
pc.pc_data['x'] -= pc.pc_data['x'].mean()

# save as binary compressed
pc.save_pcd('bar.pcd', compression='binary_compressed')

How to install

pip install pypcd

That's it! You may want to install optional dependencies such as pandas.

You can also clone this repo and use setup.py.

git clone https://github.com/dimatura/pypcd

Note that downloading data assets will require git-lfs.

Using with ROS

You can also use this library with ROS sensor_msgs, but it is not a dependency. You don't need to install this package with catkin -- using pip should be fine -- but if you want to it is possible:

Steps:

# you need to do this manually in this case
pip install python-lzf
cd your_workspace/src
git clone https://github.com/dimatura/pypcd
mv setup_ros.py setup.py
catkin build pypcd
source ../devel/setup.bash

Then you can do something like this:

import pypcd
import rospy
from sensor_msgs.msg import PointCloud2


def cb(msg):
    pc = PointCloud.from_msg(msg)
    pc.save('foo.pcd', compression='binary_compressed')
    # maybe manipulate your pointcloud
    pc.pc_data['x'] *= -1
    outmsg = pc.to_msg()
    # you'll probably need to set the header
    outmsg.header = msg.header
    pub.publish(outmsg)

# ...
sub = rospy.Subscriber('incloud', PointCloud2)
pub = rospy.Publisher('outcloud', PointCloud2, cb)
rospy.init('pypcd_node')
rospy.spin()

Is it beautiful, production-ready code?

No.

What else can it do?

There's a bunch of functionality accumulated over time, much of it hackish and untested. In no particular order,

  • Supports ascii, binary and binary_compressed data. The latter requires the lzf module.
  • Decode and encode RGB into a single float32 number. If you don't know what I'm talking about consider yourself lucky.
  • Point clouds to pandas dataframes. This in particular is quite useful, since pandas is pretty powerful and makes various operations such as merging point clouds or manipulating values easy. Conceptually, data frames are a good match to the point cloud format, since many point clouds in reality have heterogeneous data types - e.g. x, y and z are float fields but label is an int.
  • Convert to and from ROS PointCloud2 messages. Requires the ROS sensor_msgs package with Python bindings installed. This functionality uses code developed by Jon Binney under the BSD license, included as numpy_pc2.py.

What can't it do?

There's no synchronization between the metadata fields in PointCloud and the data in pc_data. If you change the shape of pc_data without updating the metadata fields you'll run into trouble.

I've only used it for unorganized point cloud data (in PCD conventions, height=1), not organized data like what you get from RGBD. However, some things may still work.

While padding and fields with count larger than 1 seem to work, this is a somewhat ad-hoc aspect of the PCD format, so be careful. If you want to be safe, you're probably better off using neither -- just name each component of your field something like FIELD_00, FIELD_01, etc.

It also can't run on Python 3, yet, but there's a PR to fix this that might get pulled in the near future.

It's slow!

Try using binary or binary_compressed; using ASCII is slow and takes up a lot of space, not to mention possibly inaccurate if you're not careful with how you format your floats.

I found a bug / I added a feature / I made your code cleaner

Thanks! You can submit a pull request. But honestly, I'm not too good at keeping up with my github :(

TODO

  • Better API for various operations.
  • Clean up, get rid of cruft.
  • Add a cli for common use cases like file type conversion.
  • Better support for structured point clouds, with tests.
  • Better testing.
  • Better docs. More examples.
  • More testing of padding
  • Improve handling of multicount fields
  • Better support for rgb nonsense
  • Export to ply?
  • Figure out if it's acceptable to use "pointcloud" as a single word.
  • Package data assets in pypi?

Credits

The code for compressed point cloud data was informed by looking at Matlab PCL.

@wkentaro for some minor changes.

I used cookiecutter to help with the packaging.

The code in numpy_pc2.py was developed by Jon Binney under the BSD license for ROS.

I want to congratulate you / insult you

My email is [email protected].

Copyright (C) 2015-2017 Daniel Maturana

pypcd's People

Contributors

dimatura avatar wkentaro avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar

pypcd's Issues

NotImplementedError: ROS sensor_msgs not found while reading rosbag

Hi, i am new to ROS2 and pointcloud.
I have Lidar data in rosbag. i want to convert it into kitti dataset format .bin files
i wanted to use pypcd to read the data but its giving following issue

pc = pypcd.PointCloud.from_msg(loc[indx])

File "/home/robot/.local/lib/python3.8/site-packages/pypcd/pypcd.py", line 779, in from_msg
raise NotImplementedError('ROS sensor_msgs not found')
NotImplementedError: ROS sensor_msgs not found

Please provide solution, thank you

The zip function in python 3 returns a object

In python 2, zip() returns a list, but a object in python 3.
python 2:

211 dtype = np.dtype(zip(fieldnames, typenames))

python 3:

211 dtype = np.dtype(list(zip(fieldnames, typenames)))

Error happens when reading pcd file

pcd = pypcd.PointCloud.from_path(pcd_path)

  File "/exercises/py35_env/lib/python3.5/site-packages/pypcd/pypcd.py", line 743, in from_path
    return point_cloud_from_path(fname)
  File "/exercises/py35_env/lib/python3.5/site-packages/pypcd/pypcd.py", line 309, in point_cloud_from_path
    pc = point_cloud_from_fileobj(f)
  File "/exercises/py35_env/lib/python3.5/site-packages/pypcd/pypcd.py", line 290, in point_cloud_from_fileobj
    dtype = _build_dtype(metadata)
  File "/exercises/py35_env/lib/python3.5/site-packages/pypcd/pypcd.py", line 215, in _build_dtype
    dtype = np.dtype(zip(fieldnames, typenames))
TypeError: data type not understood

reading 2MB bin file crashes system

Reading a 2MB bin file crashes 16GB RAM system.

Environment:
python2.7
Ubuntu 16.04

code:

import pypcd
bin = pypcd.PointCloud.from_path('foo.bin')
bin.save('foo.pcd', compression='binary_compressed')

Missing files in sdist

It appears that the manifest is missing at least one file necessary to build
from the sdist for version 0.1.1. You're in good company, about 5% of other
projects updated in the last year are also missing files.

+ /tmp/venv/bin/pip3 wheel --no-binary pypcd -w /tmp/ext pypcd==0.1.1
Looking in indexes: http://10.10.0.139:9191/root/pypi/+simple/
Collecting pypcd==0.1.1
  Downloading http://10.10.0.139:9191/root/pypi/%2Bf/32a/14d37ffbfd4ef/pypcd-0.1.1.tar.gz (19 kB)
    ERROR: Command errored out with exit status 1:
     command: /tmp/venv/bin/python3 -c 'import sys, setuptools, tokenize; sys.argv[0] = '"'"'/tmp/pip-wheel-_2a46niv/pypcd/setup.py'"'"'; __file__='"'"'/tmp/pip-wheel-_2a46niv/pypcd/setup.py'"'"';f=getattr(tokenize, '"'"'open'"'"', open)(__file__);code=f.read().replace('"'"'\r\n'"'"', '"'"'\n'"'"');f.close();exec(compile(code, __file__, '"'"'exec'"'"'))' egg_info --egg-base /tmp/pip-wheel-_2a46niv/pypcd/pip-egg-info
         cwd: /tmp/pip-wheel-_2a46niv/pypcd/
    Complete output (5 lines):
    Traceback (most recent call last):
      File "<string>", line 1, in <module>
      File "/tmp/pip-wheel-_2a46niv/pypcd/setup.py", line 9, in <module>
        with open('HISTORY.rst') as history_file:
    FileNotFoundError: [Errno 2] No such file or directory: 'HISTORY.rst'
    ----------------------------------------
ERROR: Command errored out with exit status 1: python setup.py egg_info Check the logs for full command output.

TypeError: object of type 'map' has no len()

File "/usr/local/lib/python3.5/dist-packages/pypcd/pypcd.py", line 736, in from_path
return point_cloud_from_path(fname)
File "/usr/local/lib/python3.5/dist-packages/pypcd/pypcd.py", line 303, in point_cloud_from_path
pc = point_cloud_from_fileobj(f)
File "/usr/local/lib/python3.5/dist-packages/pypcd/pypcd.py", line 296, in point_cloud_from_fileobj
return PointCloud(metadata, pc_data)
File "/usr/local/lib/python3.5/dist-packages/pypcd/pypcd.py", line 671, in init
self.check_sanity()
File "/usr/local/lib/python3.5/dist-packages/pypcd/pypcd.py", line 683, in check_sanity
assert(_metadata_is_consistent(md))
File "/usr/local/lib/python3.5/dist-packages/pypcd/pypcd.py", line 177, in _metadata_is_consistent
if not check(metadata):
File "/usr/local/lib/python3.5/dist-packages/pypcd/pypcd.py", line 162, in
checks.append((lambda m: len((m['type'])) == len((m['count'])) ==
TypeError: object of type 'map' has no len()

In python 3, map has no len()

162 checks.append((lambda m: len(m['type']) == len(m['count']) ==
163 len(m['fields']),

Add a list() to resolve the problems?

162 checks.append((lambda m: len(list(m['type'])) == len(list(m['count'])) ==
163 len(list(m['fields'])),

Unable to install via pip or whl

Error message:
Collecting pypcd
Using cached https://files.pythonhosted.org/packages/44/2c/81a97605f112c3ecd01ae5d378f5c35f4eef843c71a031627788c650bc00/pypcd-0.1.1-py2.py3-none-any.whl
Collecting python-lzf (from pypcd)
Using cached https://files.pythonhosted.org/packages/e3/33/b8f67bbe695ccc39f868ae55378993a7bde1357a0567803a80467c8ce1a4/python-lzf-0.2.4.tar.gz
Requirement already satisfied: numpy in c:\programdata\anaconda3\envs\envtoolchain\lib\site-packages (from pypcd) (1.18.4)
Building wheels for collected packages: python-lzf
Building wheel for python-lzf (setup.py) ... error
ERROR: Complete output from command 'C:\ProgramData\Anaconda3\envs\envToolchain\python.exe' -u -c 'import setuptools, tokenize;file='"'"'C:\Users\Z0007157\AppData\Local\Temp\pip-install-lqerxxna\python-lzf\setup.py'"'"';f=getattr(tokenize, '"'"'open'"'"'
, open)(file);code=f.read().replace('"'"'\r\n'"'"', '"'"'\n'"'"');f.close();exec(compile(code, file, '"'"'exec'"'"'))' bdist_wheel -d 'C:\Users\Z0007157\AppData\Local\Temp\pip-wheel-7g46w_95' --python-tag cp37:
ERROR: running bdist_wheel
running build
running build_ext
building 'lzf' extension
creating build
creating build\temp.win-amd64-3.7
creating build\temp.win-amd64-3.7\Release
cl.exe /c /nologo /Ox /W3 /GL /DNDEBUG /MT -I. -IC:\ProgramData\Anaconda3\envs\envToolchain\include -IC:\ProgramData\Anaconda3\envs\envToolchain\include "-IC:\Program Files (x86)\Windows Kits\NETFXSDK\4.6.1\include\um" /Tclzf_module.c /Fobuild\temp.win-amd64-3.7\Rel
ease\lzf_module.obj -Wall
error: command 'cl.exe' failed: No such file or directory

ERROR: Failed building wheel for python-lzf
Running setup.py clean for python-lzf
Failed to build python-lzf
Installing collected packages: python-lzf, pypcd
Running setup.py install for python-lzf ... error
ERROR: Complete output from command 'C:\ProgramData\Anaconda3\envs\envToolchain\python.exe' -u -c 'import setuptools, tokenize;file='"'"'C:\Users\Z0007157\AppData\Local\Temp\pip-install-lqerxxna\python-lzf\setup.py'"'"';f=getattr(tokenize, '"'"'open'"'
"', open)(file);code=f.read().replace('"'"'\r\n'"'"', '"'"'\n'"'"');f.close();exec(compile(code, file, '"'"'exec'"'"'))' install --record 'C:\Users\Z0007157\AppData\Local\Temp\pip-record-ocav5mr9\install-record.txt' --single-version-externally-managed --compil
e:
ERROR: running install
running build
running build_ext
building 'lzf' extension
creating build
creating build\temp.win-amd64-3.7
creating build\temp.win-amd64-3.7\Release
cl.exe /c /nologo /Ox /W3 /GL /DNDEBUG /MT -I. -IC:\ProgramData\Anaconda3\envs\envToolchain\include -IC:\ProgramData\Anaconda3\envs\envToolchain\include "-IC:\Program Files (x86)\Windows Kits\NETFXSDK\4.6.1\include\um" /Tclzf_module.c /Fobuild\temp.win-amd64-3.7\R
elease\lzf_module.obj -Wall
error: command 'cl.exe' failed: No such file or directory
----------------------------------------
ERROR: Command "'C:\ProgramData\Anaconda3\envs\envToolchain\python.exe' -u -c 'import setuptools, tokenize;file='"'"'C:\Users\Z0007157\AppData\Local\Temp\pip-install-lqerxxna\python-lzf\setup.py'"'"';f=getattr(tokenize, '"'"'open'"'"', open)(file);code
=f.read().replace('"'"'\r\n'"'"', '"'"'\n'"'"');f.close();exec(compile(code, file, '"'"'exec'"'"'))' install --record 'C:\Users\Z0007157\AppData\Local\Temp\pip-record-ocav5mr9\install-record.txt' --single-version-externally-managed --compile" failed with error cod
e 1 in C:\Users\Z0007157\AppData\Local\Temp\pip-install-lqerxxna\python-lzf\

I'm sure I have this file, but no such file or directory

Thank you for your project and contribution
(Where2comm) w@ubuntu:~/wherecomm/Where2comm$ python opencood/tools/train.py --hypes_yaml /home/w/wherecomm/Where2comm/opencood/hypes_yaml/dair_where2comm_max_multiscale_resnet.yaml > training_log.txt
/home/w/anaconda3/envs/Where2comm/lib/python3.8/site-packages/torch/utils/data/dataloader.py:478: UserWarning: This DataLoader will create 8 worker processes in total. Our suggested max number of worker in current system is 2, which is smaller than what this DataLoader is going to create. Please be aware that excessive worker creation might get DataLoader running slow or even freeze, lower the worker number to avoid potential slowness/freeze if necessary.
warnings.warn(_create_warning_msg(
/home/w/anaconda3/envs/Where2comm/lib/python3.8/site-packages/mmcv/init.py:20: UserWarning: On January 1, 2023, MMCV will release v2.0.0, in which it will remove components related to the training process and add a data transformation module. In addition, it will rename the package names mmcv to mmcv-lite and mmcv-full to mmcv. See https://github.com/open-mmlab/mmcv/blob/master/docs/en/compatibility.md for more details.
warnings.warn(
Traceback (most recent call last):
File "opencood/tools/train.py", line 192, in
main()
File "opencood/tools/train.py", line 96, in main
for i, batch_data in enumerate(train_loader):
File "/home/w/anaconda3/envs/Where2comm/lib/python3.8/site-packages/torch/utils/data/dataloader.py", line 521, in next
data = self._next_data()
File "/home/w/anaconda3/envs/Where2comm/lib/python3.8/site-packages/torch/utils/data/dataloader.py", line 1203, in _next_data
return self._process_data(data)
File "/home/w/anaconda3/envs/Where2comm/lib/python3.8/site-packages/torch/utils/data/dataloader.py", line 1229, in _process_data
data.reraise()
File "/home/w/anaconda3/envs/Where2comm/lib/python3.8/site-packages/torch/_utils.py", line 434, in reraise
raise exception
FileNotFoundError: Caught FileNotFoundError in DataLoader worker process 0.
Original Traceback (most recent call last):
File "/home/w/anaconda3/envs/Where2comm/lib/python3.8/site-packages/torch/utils/data/_utils/worker.py", line 287, in _worker_loop
data = fetcher.fetch(index)
File "/home/w/anaconda3/envs/Where2comm/lib/python3.8/site-packages/torch/utils/data/_utils/fetch.py", line 49, in fetch
data = [self.dataset[idx] for idx in possibly_batched_index]
File "/home/w/anaconda3/envs/Where2comm/lib/python3.8/site-packages/torch/utils/data/_utils/fetch.py", line 49, in
data = [self.dataset[idx] for idx in possibly_batched_index]
File "/home/w/wherecomm/Where2comm/opencood/data_utils/datasets/intermediate_fusion_dataset_dair.py", line 317, in getitem
base_data_dict = self.retrieve_base_data(idx)
File "/home/w/wherecomm/Where2comm/opencood/data_utils/datasets/intermediate_fusion_dataset_dair.py", line 147, in retrieve_base_data
data[1]['lidar_np'], _ = pcd_utils.read_pcd(os.path.join(self.root_dir,frame_info["infrastructure_pointcloud_path"]))
File "/home/w/wherecomm/Where2comm/opencood/utils/pcd_utils.py", line 227, in read_pcd
with open(pcd_path, "rb") as f:
FileNotFoundError: [Errno 2] No such file or directory: '/home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/016525.pcd'
And I output pcd read.log, which shows that each time a portion of the file can be read normally, but it stops at a random location
2023-05-22 06:02:11,373 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/015024.pcd
2023-05-22 06:02:11,374 - INFO - Other key information: ...
2023-05-22 06:02:11,388 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/003774.pcd
2023-05-22 06:02:11,390 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/009323.pcd
2023-05-22 06:02:11,391 - INFO - Other key information: ...
2023-05-22 06:02:11,393 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/007600.pcd
2023-05-22 06:02:11,394 - INFO - Other key information: ...
2023-05-22 06:02:11,383 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/013056.pcd
2023-05-22 06:02:11,394 - INFO - Other key information: ...
2023-05-22 06:02:11,395 - INFO - Other key information: ...
2023-05-22 06:02:11,414 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/010300.pcd
2023-05-22 06:02:11,420 - INFO - Other key information: ...
2023-05-22 06:02:11,417 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/012471.pcd
2023-05-22 06:02:11,429 - INFO - Other key information: ...
2023-05-22 06:02:11,505 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/015111.pcd
2023-05-22 06:02:11,512 - INFO - Other key information: ...
2023-05-22 06:02:11,645 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/016530.pcd
2023-05-22 06:02:11,645 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/016530.pcd
2023-05-22 06:02:11,645 - INFO - Other key information: ...
2023-05-22 06:02:11,645 - INFO - Other key information: ...
2023-05-22 06:02:11,692 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/017888.pcd
2023-05-22 06:02:11,692 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/017888.pcd
2023-05-22 06:02:11,692 - INFO - Other key information: ...
2023-05-22 06:02:11,692 - INFO - Other key information: ...
2023-05-22 06:02:11,711 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/000786.pcd
2023-05-22 06:02:11,711 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/000786.pcd
2023-05-22 06:02:11,711 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/000786.pcd
2023-05-22 06:02:11,711 - INFO - Other key information: ...
2023-05-22 06:02:11,711 - INFO - Other key information: ...
2023-05-22 06:02:11,711 - INFO - Other key information: ...
2023-05-22 06:02:11,713 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/018505.pcd
2023-05-22 06:02:11,713 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/018505.pcd
2023-05-22 06:02:11,713 - INFO - Other key information: ...
2023-05-22 06:02:11,713 - INFO - Other key information: ...
2023-05-22 06:02:11,719 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/000142.pcd
2023-05-22 06:02:11,719 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/000142.pcd
2023-05-22 06:02:11,719 - INFO - Other key information: ...
2023-05-22 06:02:11,719 - INFO - Other key information: ...
2023-05-22 06:02:11,725 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/010807.pcd
2023-05-22 06:02:11,725 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/010807.pcd
2023-05-22 06:02:11,725 - INFO - Other key information: ...
2023-05-22 06:02:11,725 - INFO - Other key information: ...
2023-05-22 06:02:11,745 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/012562.pcd
2023-05-22 06:02:11,745 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/012562.pcd
2023-05-22 06:02:11,745 - INFO - Other key information: ...
2023-05-22 06:02:11,745 - INFO - Other key information: ...
2023-05-22 06:02:11,755 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/007527.pcd
2023-05-22 06:02:11,755 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/007527.pcd
2023-05-22 06:02:11,755 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/007527.pcd
2023-05-22 06:02:11,755 - INFO - Other key information: ...
2023-05-22 06:02:11,755 - INFO - Other key information: ...
2023-05-22 06:02:11,755 - INFO - Other key information: ...
2023-05-22 06:02:11,775 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/014259.pcd
2023-05-22 06:02:11,775 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/014259.pcd
2023-05-22 06:02:11,775 - INFO - Other key information: ...
2023-05-22 06:02:11,775 - INFO - Other key information: ...
2023-05-22 06:02:11,780 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/000037.pcd
2023-05-22 06:02:11,780 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/000037.pcd
2023-05-22 06:02:11,780 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/000037.pcd
2023-05-22 06:02:11,780 - INFO - Other key information: ...
2023-05-22 06:02:11,780 - INFO - Other key information: ...
2023-05-22 06:02:11,780 - INFO - Other key information: ...
2023-05-22 06:02:11,807 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/004529.pcd
2023-05-22 06:02:11,807 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/004529.pcd
2023-05-22 06:02:11,807 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/004529.pcd
2023-05-22 06:02:11,807 - INFO - Other key information: ...
2023-05-22 06:02:11,807 - INFO - Other key information: ...
2023-05-22 06:02:11,807 - INFO - Other key information: ...
2023-05-22 06:02:11,808 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/015050.pcd
2023-05-22 06:02:11,808 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/015050.pcd
2023-05-22 06:02:11,808 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/015050.pcd
2023-05-22 06:02:11,808 - INFO - Other key information: ...
2023-05-22 06:02:11,808 - INFO - Other key information: ...
2023-05-22 06:02:11,808 - INFO - Other key information: ...
2023-05-22 06:02:11,835 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/013659.pcd
2023-05-22 06:02:11,835 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/013659.pcd
2023-05-22 06:02:11,835 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/013659.pcd
2023-05-22 06:02:11,835 - INFO - Other key information: ...
2023-05-22 06:02:11,835 - INFO - Other key information: ...
2023-05-22 06:02:11,835 - INFO - Other key information: ...
2023-05-22 06:02:11,859 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/016457.pcd
2023-05-22 06:02:11,859 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/016457.pcd
2023-05-22 06:02:11,859 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/016457.pcd
2023-05-22 06:02:11,859 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/016457.pcd
2023-05-22 06:02:11,859 - INFO - Other key information: ...
2023-05-22 06:02:11,859 - INFO - Other key information: ...
2023-05-22 06:02:11,859 - INFO - Other key information: ...
2023-05-22 06:02:11,859 - INFO - Other key information: ...
2023-05-22 06:02:11,880 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/014680.pcd
2023-05-22 06:02:11,880 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/014680.pcd
2023-05-22 06:02:11,880 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/014680.pcd
2023-05-22 06:02:11,880 - INFO - Other key information: ...
2023-05-22 06:02:11,880 - INFO - Other key information: ...
2023-05-22 06:02:11,880 - INFO - Other key information: ...
2023-05-22 06:14:03,848 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/006270.pcd
2023-05-22 06:14:03,848 - INFO - Other key information: ...
2023-05-22 06:14:03,849 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/010304.pcd
2023-05-22 06:14:03,849 - INFO - Other key information: ...
2023-05-22 06:14:03,864 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/020193.pcd
2023-05-22 06:14:03,864 - INFO - Other key information: ...
2023-05-22 06:14:03,866 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/018509.pcd
2023-05-22 06:14:03,866 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/018509.pcd
2023-05-22 06:14:03,866 - INFO - Other key information: ...
2023-05-22 06:14:03,866 - INFO - Other key information: ...
2023-05-22 06:14:03,877 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/000627.pcd
2023-05-22 06:14:03,877 - INFO - Other key information: ...
2023-05-22 06:19:55,706 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/009125.pcd
2023-05-22 06:19:55,707 - INFO - Other key information: ...
2023-05-22 06:19:55,712 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/010534.pcd
2023-05-22 06:19:55,713 - INFO - Other key information: ...
2023-05-22 06:19:55,716 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/015172.pcd
2023-05-22 06:19:55,716 - INFO - Other key information: ...
2023-05-22 06:19:55,719 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/013629.pcd
2023-05-22 06:19:55,719 - INFO - Other key information: ...
2023-05-22 06:19:55,730 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/010779.pcd
2023-05-22 06:19:55,730 - INFO - Other key information: ...
2023-05-22 06:19:55,731 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/011428.pcd
2023-05-22 06:19:55,732 - INFO - Other key information: ...
2023-05-22 06:19:55,739 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/015899.pcd
2023-05-22 06:19:55,739 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/015899.pcd
2023-05-22 06:19:55,739 - INFO - Other key information: ...
2023-05-22 06:19:55,739 - INFO - Other key information: ...
2023-05-22 06:19:55,748 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/016189.pcd
2023-05-22 06:19:55,748 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/016189.pcd
2023-05-22 06:19:55,748 - INFO - Other key information: ...
2023-05-22 06:19:55,748 - INFO - Other key information: ...
2023-05-22 06:19:55,755 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/009051.pcd
2023-05-22 06:19:55,755 - INFO - Other key information: ...
2023-05-22 06:19:55,761 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/000349.pcd
2023-05-22 06:19:55,761 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/000349.pcd
2023-05-22 06:19:55,761 - INFO - Other key information: ...
2023-05-22 06:19:55,761 - INFO - Other key information: ...
2023-05-22 06:19:55,764 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/013712.pcd
2023-05-22 06:19:55,764 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/013712.pcd
2023-05-22 06:19:55,764 - INFO - Other key information: ...
2023-05-22 06:19:55,764 - INFO - Other key information: ...
2023-05-22 06:19:55,765 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/018215.pcd
2023-05-22 06:19:55,765 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/018215.pcd
2023-05-22 06:19:55,765 - INFO - Other key information: ...
2023-05-22 06:19:55,765 - INFO - Other key information: ...
2023-05-22 06:19:55,767 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/013984.pcd
2023-05-22 06:19:55,767 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/013984.pcd
2023-05-22 06:19:55,768 - INFO - Other key information: ...
2023-05-22 06:19:55,768 - INFO - Other key information: ...
2023-05-22 06:19:55,768 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/000537.pcd
2023-05-22 06:19:55,768 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/000537.pcd
2023-05-22 06:19:55,768 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/000537.pcd
2023-05-22 06:19:55,768 - INFO - Other key information: ...
2023-05-22 06:19:55,768 - INFO - Other key information: ...
2023-05-22 06:19:55,768 - INFO - Other key information: ...
2023-05-22 06:19:55,771 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/007789.pcd
2023-05-22 06:19:55,771 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/007789.pcd
2023-05-22 06:19:55,771 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/007789.pcd
2023-05-22 06:19:55,771 - INFO - Other key information: ...
2023-05-22 06:19:55,771 - INFO - Other key information: ...
2023-05-22 06:19:55,771 - INFO - Other key information: ...
2023-05-22 06:19:55,772 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/013123.pcd
2023-05-22 06:19:55,772 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/013123.pcd
2023-05-22 06:19:55,772 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/013123.pcd
2023-05-22 06:19:55,772 - INFO - Other key information: ...
2023-05-22 06:19:55,772 - INFO - Other key information: ...
2023-05-22 06:19:55,772 - INFO - Other key information: ...
2023-05-22 06:36:18,855 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/013182.pcd
2023-05-22 06:36:18,889 - INFO - Other key information: ...
2023-05-22 06:36:18,862 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/010426.pcd
2023-05-22 06:36:18,894 - INFO - Other key information: ...
2023-05-22 06:36:18,906 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/011659.pcd
2023-05-22 06:36:18,907 - INFO - Other key information: ...
2023-05-22 06:36:18,912 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/010622.pcd
2023-05-22 06:36:18,914 - INFO - Other key information: ...
2023-05-22 06:36:18,909 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/012460.pcd
2023-05-22 06:36:18,930 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/020196.pcd
2023-05-22 06:36:18,931 - INFO - Other key information: ...
2023-05-22 06:36:18,928 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/006179.pcd
2023-05-22 06:36:18,932 - INFO - Other key information: ...
2023-05-22 06:36:18,935 - INFO - Other key information: ...
2023-05-22 06:36:18,927 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/003541.pcd
2023-05-22 06:36:18,942 - INFO - Other key information: ...
2023-05-22 06:36:18,972 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/010385.pcd
2023-05-22 06:36:18,972 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/010385.pcd
2023-05-22 06:36:18,972 - INFO - Other key information: ...
2023-05-22 06:36:18,972 - INFO - Other key information: ...
2023-05-22 06:36:18,973 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/009384.pcd
2023-05-22 06:36:18,973 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/009384.pcd
2023-05-22 06:36:18,973 - INFO - Other key information: ...
2023-05-22 06:36:18,973 - INFO - Other key information: ...
2023-05-22 06:36:19,000 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/013068.pcd
2023-05-22 06:36:19,000 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/013068.pcd
2023-05-22 06:36:19,000 - INFO - Other key information: ...
2023-05-22 06:36:19,000 - INFO - Other key information: ...
2023-05-22 06:36:19,001 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/000104.pcd
2023-05-22 06:36:19,001 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/000104.pcd
2023-05-22 06:36:19,001 - INFO - Other key information: ...
2023-05-22 06:36:19,001 - INFO - Other key information: ...
2023-05-22 06:36:19,002 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/008798.pcd
2023-05-22 06:36:19,002 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/008798.pcd
2023-05-22 06:36:19,002 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/008798.pcd
2023-05-22 06:36:19,002 - INFO - Other key information: ...
2023-05-22 06:36:19,002 - INFO - Other key information: ...
2023-05-22 06:36:19,002 - INFO - Other key information: ...
2023-05-22 06:36:19,006 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/013189.pcd
2023-05-22 06:36:19,006 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/013189.pcd
2023-05-22 06:36:19,006 - INFO - Other key information: ...
2023-05-22 06:36:19,006 - INFO - Other key information: ...
2023-05-22 06:36:19,007 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/000326.pcd
2023-05-22 06:36:19,007 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/000326.pcd
2023-05-22 06:36:19,007 - INFO - Other key information: ...
2023-05-22 06:36:19,007 - INFO - Other key information: ...
2023-05-22 06:36:19,016 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/013190.pcd
2023-05-22 06:36:19,016 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/013190.pcd
2023-05-22 06:36:19,016 - INFO - Other key information: ...
2023-05-22 06:36:19,016 - INFO - Other key information: ...
2023-05-22 06:36:19,030 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/014740.pcd
2023-05-22 06:36:19,030 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/014740.pcd
2023-05-22 06:36:19,030 - INFO - Other key information: ...
2023-05-22 06:36:19,030 - INFO - Other key information: ...
2023-05-22 06:38:48,109 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/004688.pcd
2023-05-22 06:38:48,109 - INFO - Other key information: ...
2023-05-22 06:38:48,113 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/008933.pcd
2023-05-22 06:38:48,114 - INFO - Other key information: ...
2023-05-22 06:38:48,114 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/009332.pcd
2023-05-22 06:38:48,114 - INFO - Other key information: ...
2023-05-22 06:38:48,115 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/003736.pcd
2023-05-22 06:38:48,115 - INFO - Other key information: ...
2023-05-22 06:38:48,117 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/010244.pcd
2023-05-22 06:38:48,117 - INFO - Other key information: ...
2023-05-22 06:38:48,119 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/000148.pcd
2023-05-22 06:38:48,119 - INFO - Other key information: ...
2023-05-22 06:38:48,138 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/011600.pcd
2023-05-22 06:38:48,139 - INFO - Other key information: ...
2023-05-22 06:38:48,145 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/013613.pcd
2023-05-22 06:38:48,145 - INFO - Other key information: ...
2023-05-22 06:38:48,156 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/006829.pcd
2023-05-22 06:38:48,156 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/006829.pcd
2023-05-22 06:38:48,156 - INFO - Other key information: ...
2023-05-22 06:38:48,156 - INFO - Other key information: ...
2023-05-22 06:38:48,163 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/017897.pcd
2023-05-22 06:38:48,163 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/017897.pcd
2023-05-22 06:38:48,163 - INFO - Other key information: ...
2023-05-22 06:38:48,163 - INFO - Other key information: ...
2023-05-22 06:38:48,164 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/018449.pcd
2023-05-22 06:38:48,164 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/018449.pcd
2023-05-22 06:38:48,164 - INFO - Other key information: ...
2023-05-22 06:38:48,164 - INFO - Other key information: ...
2023-05-22 06:38:48,166 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/000609.pcd
2023-05-22 06:38:48,166 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/000609.pcd
2023-05-22 06:38:48,166 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/000609.pcd
2023-05-22 06:38:48,166 - INFO - Other key information: ...
2023-05-22 06:38:48,166 - INFO - Other key information: ...
2023-05-22 06:38:48,166 - INFO - Other key information: ...
2023-05-22 06:38:48,167 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/019953.pcd
2023-05-22 06:38:48,167 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/019953.pcd
2023-05-22 06:38:48,167 - INFO - Other key information: ...
2023-05-22 06:38:48,167 - INFO - Other key information: ...
2023-05-22 06:38:48,170 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/014425.pcd
2023-05-22 06:38:48,170 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/014425.pcd
2023-05-22 06:38:48,170 - INFO - Other key information: ...
2023-05-22 06:38:48,170 - INFO - Other key information: ...
2023-05-22 18:37:01,618 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/006584.pcd
2023-05-22 18:37:01,618 - INFO - Other key information: ...
2023-05-22 18:37:01,609 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/007572.pcd
2023-05-22 18:37:01,621 - INFO - Other key information: ...
2023-05-22 18:37:01,612 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/007595.pcd
2023-05-22 18:37:01,621 - INFO - Other key information: ...
2023-05-22 18:37:01,616 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/007772.pcd
2023-05-22 18:37:01,622 - INFO - Other key information: ...
2023-05-22 18:37:01,622 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/006751.pcd
2023-05-22 18:37:01,623 - INFO - Other key information: ...
2023-05-22 18:37:01,622 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/010436.pcd
2023-05-22 18:37:01,623 - INFO - Other key information: ...
2023-05-22 18:37:01,616 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/002461.pcd
2023-05-22 18:37:01,624 - INFO - Other key information: ...
2023-05-22 18:37:01,626 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/020239.pcd
2023-05-22 18:37:01,626 - INFO - Other key information: ...
2023-05-22 18:37:01,711 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/015639.pcd
2023-05-22 18:37:01,711 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/015639.pcd
2023-05-22 18:37:01,711 - INFO - Other key information: ...
2023-05-22 18:37:01,711 - INFO - Other key information: ...
2023-05-22 18:37:01,713 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/004079.pcd
2023-05-22 18:37:01,713 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/004079.pcd
2023-05-22 18:37:01,713 - INFO - Other key information: ...
2023-05-22 18:37:01,713 - INFO - Other key information: ...
2023-05-22 18:37:01,715 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/015801.pcd
2023-05-22 18:37:01,715 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/015801.pcd
2023-05-22 18:37:01,715 - INFO - Other key information: ...
2023-05-22 18:37:01,715 - INFO - Other key information: ...
2023-05-22 18:37:01,717 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/008889.pcd
2023-05-22 18:37:01,717 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/008889.pcd
2023-05-22 18:37:01,717 - INFO - Other key information: ...
2023-05-22 18:37:01,717 - INFO - Other key information: ...
2023-05-22 18:37:01,717 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/008619.pcd
2023-05-22 18:37:01,717 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/008619.pcd
2023-05-22 18:37:01,717 - INFO - Other key information: ...
2023-05-22 18:37:01,717 - INFO - Other key information: ...
2023-05-22 18:37:01,720 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/016502.pcd
2023-05-22 18:37:01,720 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/016502.pcd
2023-05-22 18:37:01,720 - INFO - Other key information: ...
2023-05-22 18:37:01,720 - INFO - Other key information: ...
2023-05-22 18:37:01,722 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/016525.pcd
2023-05-22 18:37:01,722 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/016525.pcd
2023-05-22 18:37:01,723 - INFO - Other key information: ...
2023-05-22 18:37:01,723 - INFO - Other key information: ...
2023-05-22 18:37:01,726 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/020104.pcd
2023-05-22 18:37:01,726 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/020104.pcd
2023-05-22 18:37:01,726 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/020104.pcd
2023-05-22 18:37:01,726 - INFO - Other key information: ...
2023-05-22 18:37:01,726 - INFO - Other key information: ...
2023-05-22 18:37:01,726 - INFO - Other key information: ...
2023-05-22 18:37:01,730 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/018372.pcd
2023-05-22 18:37:01,730 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/infrastructure-side/velodyne/018372.pcd
2023-05-22 18:37:01,730 - INFO - Other key information: ...
2023-05-22 18:37:01,730 - INFO - Other key information: ...
2023-05-22 18:37:01,735 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/003415.pcd
2023-05-22 18:37:01,735 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/003415.pcd
2023-05-22 18:37:01,735 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/003415.pcd
2023-05-22 18:37:01,735 - INFO - Other key information: ...
2023-05-22 18:37:01,735 - INFO - Other key information: ...
2023-05-22 18:37:01,735 - INFO - Other key information: ...
2023-05-22 18:37:01,735 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/010236.pcd
2023-05-22 18:37:01,735 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/010236.pcd
2023-05-22 18:37:01,735 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/010236.pcd
2023-05-22 18:37:01,735 - INFO - Other key information: ...
2023-05-22 18:37:01,735 - INFO - Other key information: ...
2023-05-22 18:37:01,735 - INFO - Other key information: ...
2023-05-22 18:37:01,746 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/019997.pcd
2023-05-22 18:37:01,746 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/019997.pcd
2023-05-22 18:37:01,746 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/019997.pcd
2023-05-22 18:37:01,746 - INFO - Other key information: ...
2023-05-22 18:37:01,746 - INFO - Other key information: ...
2023-05-22 18:37:01,746 - INFO - Other key information: ...
2023-05-22 18:37:01,747 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/012480.pcd
2023-05-22 18:37:01,747 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/012480.pcd
2023-05-22 18:37:01,747 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/012480.pcd
2023-05-22 18:37:01,747 - INFO - Other key information: ...
2023-05-22 18:37:01,747 - INFO - Other key information: ...
2023-05-22 18:37:01,747 - INFO - Other key information: ...
2023-05-22 18:37:01,749 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/015411.pcd
2023-05-22 18:37:01,749 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/015411.pcd
2023-05-22 18:37:01,749 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/015411.pcd
2023-05-22 18:37:01,749 - INFO - Other key information: ...
2023-05-22 18:37:01,749 - INFO - Other key information: ...
2023-05-22 18:37:01,749 - INFO - Other key information: ...
2023-05-22 18:37:01,755 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/014113.pcd
2023-05-22 18:37:01,755 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/014113.pcd
2023-05-22 18:37:01,755 - INFO - pcd_path: /home/w/wherecomm/Where2comm/dataset/cooperative-vehicle-infrastructure/vehicle-side/velodyne/014113.pcd
2023-05-22 18:37:01,755 - INFO - Other key information: ...
2023-05-22 18:37:01,755 - INFO - Other key information: ...
2023-05-22 18:37:01,755 - INFO - Other key information: ...
If you could provide any suggestions, I would greatly appreciate it

Error when loading binary_compressed pcd file

Thanks for the great library! When I reload the binary_compressed PCD file, which is saved by pypcd from ros message, there is an error happening at https://github.com/dimatura/pypcd/blob/master/pypcd/pypcd.py#L683

I checked the code, and found out that when decoding the data at https://github.com/dimatura/pypcd/blob/master/pypcd/pypcd.py#L264 pc_data is created as a numpy array with shape (width, ). After decoding, len(pc_data) is also width instead number of points (width x height).

I am not sure whether this problem is caused by different python version. Actually, I tested on both python2.7 and python3.7 (with #9) and noticed the same error.

Any suggestions here?

NotImplementedError: ROS sensor_msgs not found

i am am getting this error. What am i doing wrong ?

[ERROR] [1701354711.882691, 1693481923.663362]: bad callback: <function callback_py at 0x7f4753d5a9d0> Traceback (most recent call last): File "/opt/ros/noetic/lib/python3/dist-packages/rospy/topics.py", line 750, in _invoke_callback cb(msg) File "/workspaces/noetic_dev/src/ros_numpy/src/ros_numpy/runfile.py", line 61, in callback_py pc = pypcd.PointCloud.from_msg(data) File "/usr/local/lib/python3.8/dist-packages/pypcd/pypcd.py", line 780, in from_msg raise NotImplementedError('ROS sensor_msgs not found') NotImplementedError: ROS sensor_msgs not found

Failes to read binar or binary compressed pcd files

I'm using python 2.7 and want to read binary or binary compressed pcd files.
The pcd files seems to be ok, because other tools like pcl_viewer visualize them correctly.

ASCII ==> OK
{'version': '0.7', 'fields': ['x', 'y', 'z', 'intensity', 't', 'reflectivity', 'ring', 'ambient', 'range'], 'size': [4, 4, 4, 4, 4, 2, 1, 2, 4], 'type': ['F', 'F', 'F', 'F', 'U', 'U', 'U', 'U', 'U'], 'count': [1, 1, 1, 1, 1, 1, 1, 1, 1], 'width': 2048, 'height': 128, 'viewpoint': [0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0], 'points': 262144, 'data': 'ascii'}
[(-0.000000000000, 0.000000000000, 0.000000000000, 4.000000000000, 0, 0, 0, 229, 0)
(-0.313022673130, 0.022687347606, 0.153115406632, 52.000000000000, 43776, 117, 0, 154, 336)
(-0.306455463171, 0.023132724687, 0.150558993220, 60.000000000000, 95232, 119, 0, 165, 329)
(-0.306383043528, 0.024072807282, 0.150558993220, 70.000000000000, 149760, 122, 0, 159, 329)
(-0.000000000000, 0.000000000000, 0.000000000000, 3.000000000000, 197632, 0, 0, 217, 0)
(-0.000000000000, 0.000000000000, 0.000000000000, 4.000000000000, 239872, 0, 0, 211, 0)
(-0.301513284445, 0.026466993615, 0.148732990026, 53.000000000000, 289024, 117, 0, 152, 324)
(-0.000000000000, 0.000000000000, 0.000000000000, 4.000000000000, 345856, 0, 0, 211, 0)
(-0.290227115154, 0.027229102328, 0.144350573421, 62.000000000000, 392960, 120, 0, 160, 312)
(-0.288289755583, 0.027932453901, 0.143620163202, 48.000000000000, 435456, 115, 0, 164, 310)]

Binary ==> invalid values
{'version': '0.7', 'fields': ['x', 'y', 'z', 'intensity', 't', 'reflectivity', 'ring', 'ambient', 'range'], 'size': [4, 4, 4, 4, 4, 2, 1, 2, 4], 'type': ['F', 'F', 'F', 'F', 'U', 'U', 'U', 'U', 'U'], 'count': [1, 1, 1, 1, 1, 1, 1, 1, 1], 'width': 2048, 'height': 128, 'viewpoint': [0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0], 'points': 262144, 'data': 'binary'}
[(-0.322375327349, 0.022405456752, 0.156767427921, 1.000000000000, 1116340224, 0, 0, 31232, 3070230528)
( 9007199254740992.000000000000, 0.000000000000, 0.000000000000, 0.000000000000, 2181038080, 40663, 190, 7677, 2870295736)
( 0.000000000000, 0.000000000000, -0.031313404441, 0.000000000000, 10616832, 0, 77, 1, 0)
( 0.000000000000, 0.000000000000, -0.000000000000, -23.072139739990, 483019068, 62, 0, 16256, 1115947008)
( 0.000000000000, 0.000000000000, 0.000000000000, 0.000000000000, 0, 0, 0, 0, 0)
( 0.000000000000, 0.000000000000, 0.000000000000, 0.000000000000, 4194304, 595, 0, 0, 12451840)
( 0.000000000000, 0.000000000000, 0.000000000000, 0.000000000000, 1092157440, 48798, 235, 52953, 457922620)
(-0.000000000000, 33554684.000000000000, 0.000000000000, 0.000000000000, 39168, 19456, 1, 0, 0)
( 0.000000000000, 0.000000000000, -0.319211810827, 0.027101533487, 1042245743, 0, 128, 63, 4363264)
( 2658757058587385950290469587571965952.000000000000, -0.000000000000, 140737488355328.000000000000, 0.000000000000, 0, 0, 0, 0, 0)]

Binary Compressed ==> crash
File "/datasets/utils/src/pypcd/pypcd/pypcd.py", line 755, in from_path
return point_cloud_from_path(fname)
File "/datasets/utils/src/pypcd/pypcd/pypcd.py", line 312, in point_cloud_from_path
pc = point_cloud_from_fileobj(f)
File "/datasets/utils/src/pypcd/pypcd/pypcd.py", line 305, in point_cloud_from_fileobj
return PointCloud(metadata, pc_data)
File "/datasets/utils/src/pypcd/pypcd/pypcd.py", line 690, in init
self.check_sanity()
File "/datasets/utils/src/pypcd/pypcd/pypcd.py", line 703, in check_sanity
assert(self.pc_data.size == self.points)
AssertionError

Any ideas what's going wrong?

Multiple errors while trying to convert binary pcd file

Hi,
I'm using Pypcd version 0.1.1 and python 3.8.10
I'm getting multiple errors while trying to parse binary pcd file (Nuscenes).
the one I'm stuck on right now is in line 282:
if ln.startswith('DATA'):
TypeError: startswith first arg must be bytes or a tuple of bytes, not str

The code should understand if this is binary or ascii. Is there a solution or a different version that works?
btw, just changing to (b'DATA') will create an error in a different place.

Thanks

Organized cloud can be loaded from ASCII but not from binary

I am getting assertion error here:

/usr/local/lib/python3.6/dist-packages/pypcd-0.1.1-py3.6.egg/pypcd/pypcd.py in check_sanity(self)
    621         md = self.get_metadata()
    622         assert(_metadata_is_consistent(md))
--> 623         assert(len(self.pc_data) == self.points)
    624         assert(self.width*self.height == self.points)
    625         assert(len(self.fields) == len(self.count))

AssertionError: 

when loading an organized cloud from binary, but loads fine the very same cloud saved as ASCII. I can later provide a sample input files, but those I have at the moment are too big (45M for binary).

Unable to read binary format pcds

@dimatura , Thanks for putting together an amazing support for reading point cloud data in python. PCD is a widely used extension in the CV community. I was trying to leverage pypcd support to read a binary pcd but was unsuccessful in all my attempts. Can you please guide me on how to fix this issue to be able to read the pcd info ( binary/ascii ) successfully.

Attaching for reference of the error i had been receiving:

ValueError: field '__0000' occurs more than once

FYI: I was just using

 pc = pypcd.PointCloud.from_path("abc.pcd")

where abc.pcd was a binary format pcd.

TypeError: startswith first arg must be bytes or a tuple of bytes, not str

I'm using python3.7.3
and change cStringIO to 'StringIO'.
In my code, I used pypcd.PointCloud.from_path(image_path + str(cnt) +".pcd") and
error that show 'TypeError: startswith first arg must be bytes or a tuple of bytes, not str' ocurred in if ln.startswith('DATA'):(282, pypcd.py).
I guess that this happened because ln is already binary but I don't know how to start to fix it.
please, help me...

Conversion to .bin format

Hi,

I was wondering if we can convert the .pcd file format to .bin using this library. is there a module that enables just that?

Thank you.

Regards

Python 3 support

It would be great if this module worked with Python 3. Currently it does not properly import.

I briefly looked into it and it looks like the python-lzf module (not Python 3 compatible) could be the culprit. However, Python 3 appears to have this functionality built-in.

KeyError: ('I', 1)

File "/home/ubuntu/pypcd/pypcd/pypcd.py", line 675, in from_path
return point_cloud_from_path(fname)
File "/home/ubuntu/pypcd/pypcd/pypcd.py", line 293, in point_cloud_from_path
pc = point_cloud_from_fileobj(f)
File "/home/ubuntu/pypcd/pypcd/pypcd.py", line 275, in point_cloud_from_fileobj
dtype = _build_dtype(metadata)
File "/home/ubuntu/pypcd/pypcd/pypcd.py", line 197, in _build_dtype
np_type = pcd_type_to_numpy_type[(t, s)]
KeyError: ('I', 1)

Convert binary PCD to ascii PCD with RGB column

Hi,

I am using pypcd to convert from binary PCD file to ascii PCD file without installing PCL in my system. My original binary PCD file has x, y, z and rgb data and I use the following code to read it and save it with ascii format:

pc = pypcd.PointCloud.from_path('binary_input.pcd')
pc.save_pcd('ascii_output.pcd', compression='ascii')

All works fine except for the rgb column. The output ascii file has all RGB values set to 0.0.

But if I use this snippet of code I can print the RGB values:

rgb_columns = pypcd.decode_rgb_from_pcl(cloud.pc_data['rgb'])

Thanks.

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.