Skip to content

Livox 3D lidar support#188

Open
AndBondStyle wants to merge 10 commits into
masterfrom
livox-lidar
Open

Livox 3D lidar support#188
AndBondStyle wants to merge 10 commits into
masterfrom
livox-lidar

Conversation

@AndBondStyle
Copy link
Copy Markdown
Member

@AndBondStyle AndBondStyle commented Nov 2, 2024

  1. Add livox-sdk2 to container.
  2. Prepare lidar net config for container
  3. Add livox ros node to our repo (with some clean up)

Comment thread Dockerfile Outdated

FROM --platform=linux/amd64 ubuntu:20.04 AS truck-base-amd64
# Do not use "20.04" tag because it can be re-published and reset docker cache
FROM --platform=linux/amd64 ubuntu:focal-20240530 AS truck-base-amd64
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

У меня появились почему-то проблемы на стыке python/ros2, я это связывая с тем, что мы образ обновили. Хочу перепроверить, пересобрав еще раз со старым контейнером...

root@0fb133acef20:/truck/packages# ros2 topic list
/opt/ros/iron/bin/ros2:6: DeprecationWarning: pkg_resources is deprecated as an API. See https://setuptools.pypa.io/en/latest/pkg_resources.html
  from pkg_resources import load_entry_point
Traceback (most recent call last):
  File "/opt/ros/iron/bin/ros2", line 11, in <module>
    load_entry_point('ros2cli==0.25.7', 'console_scripts', 'ros2')()
  File "/opt/ros/iron/lib/python3.8/site-packages/ros2cli/cli.py", line 91, in main
    rc = extension.main(parser=parser, args=args)
  File "/opt/ros/iron/lib/python3.8/site-packages/ros2topic/command/topic.py", line 41, in main
    return extension.main(args=args)
  File "/opt/ros/iron/lib/python3.8/site-packages/ros2topic/verb/list.py", line 55, in main
    with NodeStrategy(args) as node:
  File "/opt/ros/iron/lib/python3.8/site-packages/ros2cli/node/strategy.py", line 35, in __init__
    spawn_daemon(args)
  File "/opt/ros/iron/lib/python3.8/site-packages/ros2cli/node/daemon.py", line 148, in spawn_daemon
    fdlimit = int(line.removeprefix(string_to_find).strip())
AttributeError: 'str' object has no attribute 'removeprefix'

Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Судя по всему эта проблема давно с нами, в humble это починили, но мы живем на Iron, а эта версия предполагает начилие Python3.9, где данный метод уже имеется. Возможно, будет проще переехать на новый софт.

Comment thread docker-compose.yaml Outdated
truck:
container_name: "${CONTAINER_NAME:-truck-${USER}}"
image: "registry.robotics-lab.ru/truck:0.11.1"
image: "registry.robotics-lab.ru/truck:0.12.0-dev" # FIXME
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Давайте не забудем убрать...

Comment thread macvlan.yaml Outdated
Comment thread packages/livox_driver/CMakeLists.txt Outdated
Comment thread packages/livox_driver/CMakeLists.txt Outdated
Comment thread packages/livox_driver/CMakeLists.txt Outdated
Comment thread packages/livox_driver/CMakeLists.txt Outdated
Comment thread packages/livox_driver/launch/msg_MID360_launch.py Outdated
Comment thread packages/livox_driver/launch/msg_MID360_launch.py Outdated
Comment thread packages/livox_driver/config/MID360_config.json Outdated
Comment on lines +1 to +9
# Livox costom pointcloud format.

uint32 offset_time # offset time relative to the base time
float32 x # X axis, unit:m
float32 y # Y axis, unit:m
float32 z # Z axis, unit:m
uint8 reflectivity # reflectivity, 0~255
uint8 tag # livox tag
uint8 line # laser number in lidar
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Можно будет потом вовсе все это выкинуть, как упростим ноду еще сильнее.

Copy link
Copy Markdown
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Сейчас пишется в стандартные sensor_msgs/PointCloud2 вот с такими полями:

float32 x               # X axis, unit:m
float32 y               # Y axis, unit:m
float32 z               # Z axis, unit:m
float32 intensity       # the value is reflectivity, 0.0~255.0
uint8   tag             # livox tag
uint8   line            # laser number in lidar
float64 timestamp       # Timestamp of point

Меня напрягает:

  • intensity: почему не uint8 а float32
  • tag, line - не уверен что вообще нужны
  • timestamp - кажется точно не нужен и много места занимает

Comment thread packages/livox_driver/src/include/ros_headers.h Outdated
Comment thread packages/model/config/model.yaml Outdated
child_frame_id: "lidar_link"
translation: { x: 0.0, y: 0.0, z: 0.0 }
rotation: { x: 0.0, y: 0.0, z: 0.0, w: 1.0 }
rotation: { x: 0, y: 0.0, z: 1.0, w: 0.0 }
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

x: 0.0

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

3 participants