Skip to content

Commit

Permalink
Fix TF and improve configuration.
Browse files Browse the repository at this point in the history
  • Loading branch information
rafal-gorecki committed Sep 2, 2024
1 parent 32012b5 commit 770edbe
Show file tree
Hide file tree
Showing 3 changed files with 140 additions and 60 deletions.
5 changes: 5 additions & 0 deletions Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -17,3 +17,8 @@ RUN apt-get update && apt-get install -y \
apt-get clean && \
rm -rf src build && \
rm -rf /var/lib/apt/lists/*

COPY demo/config /config
COPY demo/velodyne.launch.py /velodyne.launch.py

STOPSIGNAL SIGINT
44 changes: 35 additions & 9 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,28 +1,29 @@
# velodyne-docker

Dockerized Velodyne LiDAR package.

## Velodyne configuration

Connect to Velodyne using an ethernet cable.

To access the sensor's Web Interface, you must know the sensor's Ip. You can find it for example using `nmap`:
To access the sensor's Web Interface, you must know the sensor's IP. You can find it for example using `nmap`:

Find your ethernet Ip:
Find your ethernet IP:

```
```bash
ifconfig
```

Use your ethernet Ip to find devices in the same network. You need to replace the last number of Ip with 0/24 for example if your Ip is 10.15.20.1 then:
Use your ethernet IP to find devices in the same network. You need to replace the last number of IP with 0/24 for example if your IP is 10.15.20.1 then:

```
```bash
nmap -sn 10.15.20.0/24
```

This will list all devices in the same network including Velodyne.

Then you need to specify the host to which Velodyne will be able to send data. In the browser enter the sensor Ip to access Web Interface.
Go to **Host (Destination)** and change Ip Address to your device.
Then you need to specify the host to which Velodyne will be able to send data. In the browser enter the sensor IP to access Web Interface.
Go to **Host (Destination)** and change IP Address to your device.
Click the **set** button on the right, then go to the bottom and click the **Save configuration** button.

For more information about Velodyne configuration refer to official User Manuals.
Expand All @@ -33,17 +34,42 @@ If you find an IP of Velodyne change [configuration file](./demo/config/panther_

Clone this repo:

```
```bash
git clone -b ros2 https://github.com/husarion/velodyne-docker
```

Sensor's parameters can be changed, by editing or providing your own config files and mounting them into the container. Default config files are located in [config](./demo/config/) directory.

Run docker compose:

```
```bash
cd velodyne-docker/demo
docker compose up
```

You should be able to see sensor data on the `/panther/velodyne/velodyne_points` topic with standard `sensor_msgs/msg/PointCloud2` message type.

## Parameters

The image includes a custom `velodyne.launch.py` file, which is based on the official Velodyne package but includes additional configurations for easier integration with Husarion robots. This launch file contains the following parameters:

| **Parameter** | **Description** | **Default Value** |
| ----------------------- | --------------- | ----------------- |
| `device_namespace` | Namespace for the device, utilized in TF frames and preceding device topics. This aids in differentiating between multiple devices on the same robot. | `"velodyne"` |
| `driver_params_file` | Path to the parameter file for the velodyne_driver_node node. | `"/config/panther_velodyne_driver.yaml"` |
| `robot_namespace` | Namespace to all launched nodes and use namespace as tf_prefix. This aids in differentiating between multiple robots with the same devices. | `env("ROBOT_NAMESPACE")` (`""` if not specified) |
| `transform_params_file` | Path to the parameter file for the velodyne_transform_node node. | `"/config/panther_velodyne_pointcloud.yaml"` |
| `x` | Initial robot position in the global 'x' axis. | `0.185` |
| `y` | Initial robot position in the global 'y' axis. | `0.0` |
| `z` | Initial robot position in the global 'z' axis. | `0.209` |
| `roll` | Initial robot 'roll' orientation. | `0.0` |
| `pitch` | Initial robot 'pitch' orientation. | `0.0` |
| `yaw` | Initial robot 'yaw' orientation. | `0.0` |

Using both `device_namespace` and `robot_namespace` makes:

- Topic: `{robot_namespace}/{device_namespace}/{default_topic}`
- URDF Link: `{robot_namespace}/{device_namespace}`

> [!IMPORTANT]
> The default configuration files are set up for the VLP16 LIDAR model. If you are using a different model, it is recommended to adjust the configuration files accordingly. For guidance, refer to the [Velodyne ROS2 driver repository](https://github.com/ros-drivers/velodyne/tree/ros2).
151 changes: 100 additions & 51 deletions demo/velodyne.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -32,14 +32,18 @@

"""Launch the velodyne driver, pointcloud, and laserscan nodes with default configuration."""

import os

import ament_index_python.packages
import launch
import launch_ros.actions

from launch.actions import DeclareLaunchArgument
from launch.substitutions import EnvironmentVariable, LaunchConfiguration
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, EmitEvent, RegisterEventHandler
from launch.event_handlers import OnProcessExit
from launch.events import Shutdown
from launch.substitutions import (
EnvironmentVariable,
LaunchConfiguration,
PathJoinSubstitution,
PythonExpression,
)
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
from nav2_common.launch import ReplaceString


Expand All @@ -48,7 +52,14 @@ def generate_launch_description():
declare_device_namespace_arg = DeclareLaunchArgument(
"device_namespace",
default_value="velodyne",
description="Namespace for the device, utilized in TF frames and preceding device topics. This aids in differentiating between multiple cameras on the same robot.",
description="Namespace for the device, utilized in TF frames and preceding device topics. This aids in differentiating between multiple devices on the same robot.",
)

driver_params_file = LaunchConfiguration("driver_params_file")
declare_driver_params_file_arg = DeclareLaunchArgument(
"driver_params_file",
default_value="/config/panther_velodyne_driver.yaml",
description="Path to the parameter file for the velodyne_driver_node node.",
)

robot_namespace = LaunchConfiguration("robot_namespace")
Expand All @@ -58,97 +69,135 @@ def generate_launch_description():
description="Namespace to all launched nodes and use namespace as tf_prefix. This aids in differentiating between multiple robots with the same devices.",
)

driver_params_file = LaunchConfiguration("driver_params_file")
driver_params_file_arg = DeclareLaunchArgument(
"driver_params_file",
description="Path to the parameter file for the velodyne_driver_node node.",
)

transform_params_file = LaunchConfiguration("transform_params_file")
transform_params_file_arg = DeclareLaunchArgument(
declare_transform_params_file_arg = DeclareLaunchArgument(
"transform_params_file",
default_value="/config/panther_velodyne_pointcloud.yaml",
description="Path to the parameter file for the velodyne_transform_node node.",
)

driver_params_file = ReplaceString(
source_file=driver_params_file,
replacements={"<robot_namespace>": robot_namespace, "//": "/"},
x = LaunchConfiguration("x")
declare_x_arg = DeclareLaunchArgument(
"x", default_value="0.185", description="Initial robot position in the global 'x' axis."
)

y = LaunchConfiguration("y")
declare_y_arg = DeclareLaunchArgument(
"y", default_value="0.0", description="Initial robot position in the global 'y' axis."
)

z = LaunchConfiguration("z")
declare_z_arg = DeclareLaunchArgument(
"z", default_value="0.209", description="Initial robot position in the global 'z' axis."
)

roll = LaunchConfiguration("roll")
declare_roll_arg = DeclareLaunchArgument(
"roll", default_value="0.0", description="Initial robot 'roll' orientation."
)

pitch = LaunchConfiguration("pitch")
declare_pitch_arg = DeclareLaunchArgument(
"pitch", default_value="0.0", description="Initial robot 'pitch' orientation."
)

yaw = LaunchConfiguration("yaw")
declare_yaw_arg = DeclareLaunchArgument(
"yaw", default_value="0.0", description="Initial robot 'yaw' orientation."
)

driver_params_file = ReplaceString(
source_file=driver_params_file,
replacements={"<device_namespace>": device_namespace},
replacements={
"<device_namespace>": device_namespace,
"<robot_namespace>": robot_namespace,
"//": "/",
},
)

velodyne_driver_node = launch_ros.actions.Node(
device_ns = PythonExpression(
["'", device_namespace, "' + '/' if '", device_namespace, "' else ''"]
)
robot_ns = PythonExpression(
["'", robot_namespace, "' + '/' if '", robot_namespace, "' else ''"]
)

velodyne_driver_node = Node(
package="velodyne_driver",
executable="velodyne_driver_node",
output="both",
parameters=[driver_params_file],
namespace=robot_namespace,
remappings=[
("velodyne_packets", [device_namespace, "/velodyne_packets"]),
("velodyne_packets", [device_ns, "velodyne_packets"]),
],
)

velodyne_transform_node = launch_ros.actions.Node(
velodyne_transform_node = Node(
package="velodyne_pointcloud",
executable="velodyne_transform_node",
output="both",
parameters=[transform_params_file],
namespace=robot_namespace,
remappings=[
("velodyne_packets", [device_namespace, "/velodyne_packets"]),
("velodyne_points", [device_namespace, "/velodyne_points"]),
("velodyne_packets", [device_ns, "velodyne_packets"]),
("velodyne_points", [device_ns, "velodyne_points"]),
],
)

laserscan_share_dir = ament_index_python.packages.get_package_share_directory(
"velodyne_laserscan"
)
laserscan_params_file = os.path.join(
laserscan_share_dir, "config", "default-velodyne_laserscan_node-params.yaml"
laserscan_params_file = PathJoinSubstitution(
[
FindPackageShare("velodyne_laserscan"),
"config",
"default-velodyne_laserscan_node-params.yaml",
]
)
velodyne_laserscan_node = launch_ros.actions.Node(

velodyne_laserscan_node = Node(
package="velodyne_laserscan",
executable="velodyne_laserscan_node",
output="both",
parameters=[laserscan_params_file],
namespace=robot_namespace,
remappings=[
("velodyne_points", [device_namespace, "/velodyne_points"]),
("scan", [device_namespace, "/scan"]),
("velodyne_points", [device_ns, "velodyne_points"]),
("scan", [device_ns, "scan"]),
],
)

static_transform_publisher = launch_ros.actions.Node(
static_transform_publisher = Node(
package="tf2_ros",
executable="static_transform_publisher",
namespace=robot_namespace,
arguments=[
"0.185",
"0.0",
"0.2093",
"0.0",
"0.0",
"0.0",
[robot_namespace, "base_link"],
[robot_namespace, device_namespace],
x,
y,
z,
roll,
pitch,
yaw,
[robot_ns, "base_link"],
[robot_ns, device_namespace],
],
)

return launch.LaunchDescription(
return LaunchDescription(
[
driver_params_file_arg,
transform_params_file_arg,
declare_driver_params_file_arg,
declare_device_namespace_arg,
declare_robot_namespace_arg,
declare_transform_params_file_arg,
declare_x_arg,
declare_y_arg,
declare_z_arg,
declare_roll_arg,
declare_pitch_arg,
declare_yaw_arg,
velodyne_driver_node,
velodyne_transform_node,
velodyne_laserscan_node,
static_transform_publisher,
launch.actions.RegisterEventHandler(
event_handler=launch.event_handlers.OnProcessExit(
RegisterEventHandler(
event_handler=OnProcessExit(
target_action=velodyne_driver_node,
on_exit=[launch.actions.EmitEvent(event=launch.events.Shutdown())],
on_exit=[EmitEvent(event=Shutdown())],
)
),
]
Expand Down

0 comments on commit 770edbe

Please sign in to comment.