ROS driver suite for Odin sensor modules (Manifold Tech Ltd.)
Compatibility:
● ROS 1(LTS Release: Noetic recommended)
● ROS 2(LTS Release: Humble recommended, Jazzy supported)
This driver package provides core functionality for point cloud SLAM applications and targets specific use cases. It is intended exclusively for technical professionals conducting secondary development. End users must perform scenario-specific optimization and custom development to align with operational requirements in practical deployment environments.
Current Version: v0.6.1
● Ubuntu 18.04 for ROS Melodic;
● Ubuntu 20.04 for ROS Noetic and ROS2 Foxy;
● Ubuntu 22.04 for ROS2 Humble;
● Ubuntu 24.04 for ROS2 Jazzy;
● Opencv >= 4.5.0(recommand 4.5.5/4.8.0. Make sure only one version of opencv is installed)
● yaml-cpp
● thread
● OpenSSL
● Eigen3
sudo apt update
sudo apt-get install build-essential cmake git libgtk2.0-dev pkg-config libavcodec-dev libavformat-dev libswscale-devsudo apt update
sudo apt install -y libyaml-cpp-devsudo apt update
sudo apt install -y libusb-1.0-0-devsudo apt update
sudo apt-get install libopencv-devFor ROS Melodic installation, please refer to: ROS Melodic installation instructions
For ROS Noetic installation, please refer to: ROS Noetic installation instructions
For ROS2 Foxy installation, please refer to: ROS Foxy installation instructions
For ROS2 Humble installation, please refer to: ROS Humble installation instructions
For ROS2 Jazzy installation, please refer to: ROS Jazzy installation instructions
sudo vim /etc/udev/rules.d/99-odin-usb.rulesAdd the following content to the 99-odin-usb.rules file
SUBSYSTEM=="usb", ATTR{idVendor}=="2207", ATTR{idProduct}=="0019", MODE="0666", GROUP="plugdev"Reload rules and reinsert devices
sudo udevadm control --reload
sudo udevadm triggergit clone https://github.com/manifoldsdk/odin_ros_driver.git catkin_ws/src/odin_ros_driverNote: Please clone the source code into the "[ros_workspace]/src/" folder, otherwise compilation errors will occur.
source /opt/ros/noetic/setup.bash
./script/build_ros.shsource /opt/ros/foxy/setup.bash # or /opt/ros/humble/setup.bash or /opt/ros/jazzy/setup.bash
./script/build_ros2.shsource [ros_workspace]/devel/setup.bash
roslaunch odin_ros_driver [launch file]● odin_ros_driver: package name;
● launch file: launch file;
● ros_workspace: User's ROS environment workspace;
roslaunch odin_ros_driver odin1_ros1.launchsource [ros2_workspace]/install/setup.bash
ros2 launch odin_ros_driver [launch file]● odin_ros_driver: package name;
● launch file: launch file;
● ros2_workspace: User's ROS2 environment workspace;
ROS2 Demo Launch Instructions:
ros2 launch odin_ros_driver odin1_ros2.launch.pyThe operation mode can be configured via the custom_map_mode parameter in config/control_command.yaml.
Set custom_map_mode = 0 to enable odometry mode. In this mode, the map frame and odom frame share the same pose.
Set custom_map_mode = 1 to enable slam mode. This mode provides a complete SLAM system that builds upon the Odometry Mode by adding loop closure detection and map saving capabilities.
After launching the driver, odin1 will automatically perform mapping and cache map data. When the scene capture is complete, users need to execute ./set_param.sh save_map 1 in the driver's source directory to save all map data collected since the program started. The map will be saved to the location specified by the mapping_result_dest_dir and mapping_result_file_name parameters in config/control_command.yaml. If these parameters are not specified, default values will be used.
After the initial save, you can execute the command again to save a new map. Each save operation will generate a new map file. (Please allow at least 5 seconds between consecutive save operations)
The map origin corresponds to the odom coordinate system's origin at the program's startup.
To enable relocalization, set custom_map_mode = 2 and specify the absolute path to the pre-built map using the relocalization_map_abs_path parameter in config/control_command.yaml.
Once launched, odin1 will initiate the relocalization process based on the current viewpoint and the specified map. To ensure a high success rate, it is recommended to starting within 1 meter ±10 degrees of the original position and orientation from the SLAM trajectory.
Note that relocalization performance is highly environment-dependent. In highly distinctive scenes, successful matching may occur even beyond the 1m/10° range, while other environments may require more stringent conditions. We advise testing in your target environment to determine practical tolerances.
If relocalization fails initially, the system will temporarily operate in a fallback SLAM mode (map saving is disabled in this state). During this time, you can freely move odin1. It will continue relocalization attempts in the background. Once successful, the TF between map and odom frames will be published. (Tip: Gently shaking or moving the device after initialization can help improve relocalization accuracy.)
The following topics are published in the odom frame: /odin1/cloud_slam, /odin1/odom, /odin1/highodom and /odin1/path. To obtain these in the map frame, apply the TF from odom frame to map frame.
Odin_ROS_Driver/ // ROS1/ROS2 driver package
3rdparty/ // Third-party libraries
src/
host_sdk_sample.cpp // Example source code
yaml_parser.cpp // Source code for reading yaml parameters
rawCloudRender.cpp // Source code for RenderCloud
depth_image_ros_node.cpp //depth_image_ros_node
depth_image_ros2_node.cpp //depth_image_ros2_node
pcd2depth_ros.cpp //Source code for pcd2depth_ros
pcd2depth_ros2.cpp //Source code for pcd2depth_ros2
pointcloud_depth_converter.cpp //Source code for pointcloud_depth_converter
lib/
liblydHostApi_amd.a // Static library for AMD platform
liblydHostApi_arm.a // Static library for ARM platform
include/
host_sdk_sample.h // Example header file
lidar_api_type.h // API data structure header file
lidar_api.h // API function declarations
yaml_parser.h // Parameter file reading header file
rawCloudRender.h // API about RenderCloud
data_logger.h // LOG about save_data
depth_image_ros_node.hpp // depth_image_ros_node
depth_image_ros2_node.hpp // depth_image_ros2_node
pointcloud_depth_converter.hpp // pointcloud_depth_convert
config/
control_command.yaml // Control parameter file for driver
calib.yaml // Machine calibration yaml,differ for each individual device. Retrieved from the device everytime it connects to ROS driver
launch_ROS1/
odin1_ros1.launch // ROS1 launch file
launch_ROS2/
odin1_ros2.launch.py // ROS2 launch file
script/
build_ros1.sh // Installation script for ROS1
build_ros2.sh // Installation script for ROS2
recorddata/ // holds recorded data that can import into MindCloud
log/ // holds log files
Driver_{timestamp}/ // holds all log folders for each time driver started
Conn_{timestamp}/ // holds all log files for each odin1 device connection
dev_status.csv // device status log file
README.md // Usage instructions
CMakeLists.txt // CMake build file
License // License file| Launch File Name | Description |
|---|---|
| odin1_ros1.launch | Launch file for ROS1 - Odin1 Basic Operations Demo |
| odin1_ros2.launch.py | Launch file for ROS2 - Odin1 Basic Operations Demo |
Internal parameters of the Odin ROS driver are defined in config/control_command.yaml. Below are descriptions of the commonly used parameters:
| Topic | control_command.yaml | Detailed Description |
|---|---|---|
| odin1/imu | sendimu | Imu Topic |
| odin1/image | sendrgb | RGB Camera Topic, decoded from original jpeg data from device, bgr8 format |
| odin1/image_undistort | sendrgbundistort | undistorted RGB Camera Topic, processed with calib.yaml from device |
| odin1/image/compressed | sendrgbcompressed | RGB Camera compressed Topic, original jpeg data from device |
| odin1/cloud_raw | senddtof | Raw_Cloud Topic |
| odin1/cloud_render | sendcloudrender | Render_Cloud Topic, processed with raw point cloud, rgb image, and calib.yaml from device |
| odin1/cloud_slam | sendcloudslam | Slam_PointCloud Topic |
| odin1/odometry | sendodom | Odom Topic |
| odin1/odometry_high | sendodom | high frequency Odom Topic |
| odin1/path | showpath | Odom Path Topic |
| tf | sendodom | tf tree Topic |
| odin1/depth_img_competetion | senddepth | Dense depth image Topic. Demo, high computing power required. One-to-one with odin1/image_undistort. To utilize the data please directly subscribe to this topic instead of echoing it. Original value is already depth data, no need for further convert. |
| odin1/depth_img_competetion_cloud | senddepth | Dense Depth_Cloud Topic. Demo, high computing power required |
- The raw point cloud (cloud_raw) has the following fields:
float32 x // X axis, in meters
float32 y // Y axis, in meters
float32 z // Z axis, in meters
uint8 intensity // Reflectivity, range 0–255
uint16 confidence // Point confidence, range 0–65535
float32 offset_time // Time offset relative to the base timestamp unit: s
To work with this custom format in PCL, first define the point type:
/*** LS ***/
namespace ls_ros {
struct EIGEN_ALIGN16 Point {
float x;
float y;
float z;
uint8_t intensity;
uint16_t confidence;
float offset_time;
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};
} // namespace ls_ros
POINT_CLOUD_REGISTER_POINT_STRUCT(ls_ros::Point,
(float, x, x)
(float, y, y)
(float, z, z)
(uint8_t, intensity, intensity)
(uint16_t, confidence, confidence)
(float offset_time , offset_time)
)Then, you can easily convert a ROS sensor_msgs::PointCloud2 message into a PCL point cloud:
pcl::PointCloud<ls_ros::Point> ls_cloud;
pcl::fromROSMsg(*msg, ls_cloud);
- The slam point cloud (cloud_slam) and directly rendered point cloud (cloud_render) has the following fields:
float32 x // X axis, in meters
float32 y // Y axis, in meters
float32 z // Z axis, in meters
float32 rgb // RGB value
| control_command.yaml | Detailed Description |
|---|---|
| strict_usb3.0_check | Strict USB3.0 check, if off, allow connection even if usb connection is below usb 3.0 |
| recorddata | Record data in specific format that can be imported into MindCloud(TM) for post-processing. Please be aware that this will consume a lot of storage space. Testing shows 9.5G for 10mins of data. |
| devstatuslog | Device status logging, currently save device status (soc temperature, cpu usage, ram usage, dtof sensor temp .etc) and data tx & rx rate to devstatus.csv under log folder. A new file will be created every time the driver is started. |
| showcamerapose | Display Camera Pose and Field of View. |
| custom_map_mode | Operation Modes: Mode 0 - Odometry mode: The map frame and odom frame share the same pose. Mode 1 - Mapping (with loop closure) mode: This mode supports map saving. Mode 2 - Relocalization mode: Requires specifying the absolute path to the map file. After successful relocalization, it will output the TF relationship between the map and odom frames. |
| custom_init_pos | Initialization Position (currently unused). |
| relocalization_map_abs_path | Absolute Path to Map File: Used for relocalization mode. |
| mapping_result_dest_dir and mapping_result_file_name | Path and Name for Saving Maps in Mapping Mode: If not specified, default values will be used. |
Error Message
No device connected after 60 seconds
Solution
-
Please power on Odin module again # Disconnect and reconnect odin power
-
Reinitialize Odin SDK # Execute SDK after device reboot
Error Message
ld: cannot find -llydHostApi or symbol lookup errors
Resolution
- Clean previous build artifacts
ROS1
rm -rf devel/ build/ ROS2
rm -rf devel/ install/ log/ - Re-run script installation
Error Message
Unable to open X display or No protocol specified
Resolution
xhost + #This command enables graphical passthrough to Docker containersError Message
<ERROR><api.cpp:lidar_get_version:672>: get device version fail.
get version failed.Resolution
Device firmware version is too low, please update to latest version.
Error Message
Rviz does not respond, and after a while the terminal prints Device disconnected, waiting for reconnection...
Resolution
Please power on Odin module again
Error Message
Missed ok response from device,probably wrong interaction procedure.
Resolution
Please adopt the solution mentioned in 5.1
Error Message
ERROR:Missing camera node 'cam_0'
Resolution
Please plug and unplug the USB again
Error Message
Device ready and streams activated
Device detaching...
Wating for device reconnection...
Device disconnected, waiting for reconnection...Reason
Mostly common on ros2 environment and connected to complex network environment, such as office wifi & ethernet. ROS2 default to broadcast, and complex network environment will cause ros2 publish to block, leading to device disconnection.
Resolution
If cross-device communication is not required, please restrict ros2 to localhost only with:
export ROS_LOCALHOST_ONLY=1If cross-device communication is required, please simplify the network environment as much as possible. Mini local network with only required devices is recommended.
Error Message
Device ready and streams activated
[host_sdk_sample-2] process has died ......Test
Disable odin1/image with sendrgb = 0 in control_command.yaml and try again. If the driver now works, it is likely that the issue is related to multiple version of opencv is installed on the system.
Resolution
Purge the unused version of opencv and maintain a single complete version, then rebuild the driver and try again.
To help diagnose the issue, please provide the following details to our FAE engineer:
- Current firmware version
[device_version_capture]: ros_driver_version: [Version Number]-
Photos of power adapter and converter cable in use.
-
Does the issue happen occasionally or consistently?
-
Provide images of the problem scenario.
-
Did the troubleshooting methods in Section V resolve the issue?
-
Expected timeline for issue resolution.