This ROS package enables the conversion of RGB images to depth images using Depth Anything V2 and subsequently transforms the depth image into LaserScan data.
- SLAM: Uses an RGB camera for 2D mapping, so no additional LiDAR sensor is required.
- VSLAM: Uses an RGB camera for visual SLAM, so a depth camera is not necessary.
- ..
Subscribed Topics:
-
RGB Image (
sensor_msgs/Image
):- Topic: (
/usb_cam/image_raw
)
- Topic: (
-
Camera Info (
sensor_msgs/CameraInfo
):- Topic: (
/usb_cam/camera_info
)
- Topic: (
Published Topics:
-
Depth Image (
sensor_msgs/Image
):- Topic: (
/depth/image_raw
)
- Topic: (
-
Depth Camera Info (
sensor_msgs/CameraInfo
):- Topic: (
/depth/camera_info
)
- Topic: (
Subscribed Topics:
-
Depth Image (
sensor_msgs/Image
):- Topic:
/depth/image_raw
- Topic:
-
Camera Info (
sensor_msgs/CameraInfo
):- Topic:
/depth/camera_info
- Topic:
Published Topics:
- Laser Scan (
sensor_msgs/LaserScan
):- Topic:
scan
- Topic:
This package is built for ROS Noetic, but it might build for ROS Melodic too. Additionally, the package depends on following packages and python libraries:
- torch
- torchvision
- opencv-python
sudo apt update
sudo apt install ros-noetic-usb-cam
sudo apt install ros-noetic-depthimage-to-laserscan
pip install opencv-python torch torchvision
cd ~/catkin_ws/src
git clone https://github.com/3bdul1ah/rgbimage_to_laserscan
cd .. && catkin_make
source devel/setup.bash
After completing the installation steps, make sure you calibrate your camera using the instructions here. You can then run the example:
roslaunch depth_anything_v2_ros webcam_laser.launch