Introduction
The “Radxa Orion O6” mini ITX motherboard, jointly created by Radxa, CIX, and Arm China, is one of the most anticipated development boards currently. This product is equipped with the CIX P1 (CD8180) 12-core Armv9 processor, paired with a 30TOPS computing power NPU and high-performance GPU, combined with a maximum of 64GB LPDDR RAM, making it very suitable for AI development workstations, edge computing nodes, and high-performance personal computing applications.
I will try to deploy the depth-anything-v2 model on ‘Radxa Orion O6’ using ROS2.
Hardware Requirements
1.“Radxa Orion O6” AI PC Development Board
2. USB camera
Software Requirements
1.Ubuntu 24.04
2. ROS2
Steps to deploy the depth-anything-v2 model in ROS2
Create USB camera function package and image publishing node.
1.create a function package
mkdir -p ros_ws/src
cd ros_ws/src
ros2 pkg create image_publish --build-type ament_python --dependencies rclpy cv_bridge
2.write the code for the image publishing node.
import rclpy
from rclpy.node import Node
from sensor_msgs.msg import Image
from cv_bridge import CvBridge
import cv2
class CameraPublisher(Node):
def __init__(self):
super().__init__('camera_publisher')
self.publisher_ = self.create_publisher(Image, 'camera/image_raw', 10)
self.cap = cv2.VideoCapture(0)
self.bridge = CvBridge()
self.timer = self.create_timer(0.1, self.timer_callback)
def timer_callback(self):
ret, frame = self.cap.read()
if ret:
msg = self.bridge.cv2_to_imgmsg(frame, "bgr8")
self.publisher_.publish(msg)
def main():
rclpy.init()
node = CameraPublisher()
rclpy.spin(node)
node.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
3.compile and execute
colcon build
source install/setup.bash
ros2 run image_publish image
4.view topic
ros2 topic list
The camera/image_raw topic indicates that the USB camera data has been successfully packaged into ROS2 data format and published.
Create a deep estimation function package and inference result publishing node
1.create a function package
cd ros_ws/src
ros2 pkg create depth_estimate --build-type ament_python --dependencies rclpy cv_bridge opencv-python numpy
2.write inference node code
copy the precompiled .cix and NOE_Engine.py from the CIX modelhub to the ros_ws/src/depth_estimate/depth_estimate folder.
import rclpy
from rclpy.node import Node
from sensor_msgs.msg import Image
from cv_bridge import CvBridge
import cv2
import numpy as np
from .NOE_Engine import EngineInfer
def preprocess_image(image, mean : list = [0.485, 0.456, 0.406], std : list = [0.229, 0.224, 0.225], target_size : tuple = (520, 520), flag : bool = True, rgb : bool = True) -> np.ndarray:
mean = np.array(mean).astype(np.float32)
std = np.array(std).astype(np.float32)
# image = cv2.imread(image_path)
if rgb:
image = image[:, :, ::-1] # BGR2RGB
image_resized = cv2.resize(image, target_size)
if flag:
image_normalized = image_resized.astype(np.float32) / 255.0
else:
image_normalized = image_resized.astype(np.float32)
image_standardized = (image_normalized - mean) / std
image_transposed = image_standardized.transpose(2, 0, 1)
input_tensor = np.expand_dims(image_transposed, axis=0)
return input_tensor
class CameraProcessor(Node):
def __init__(self):
super().__init__('image_processor')
self.subscription = self.create_subscription(
Image,
'camera/image_raw',
self.listener_callback,
10)
self.bridge = CvBridge()
self.publisher_ = self.create_publisher(Image, 'processer/image_prcocess', 10)
self.model = EngineInfer("/home/cix/ros_ws/src/depth_estimate/depth_estimate/depth_anything_v2.cix")
def listener_callback(self, msg):
input_image = self.bridge.imgmsg_to_cv2(msg, desired_encoding='bgr8')
image = input_image
h, w = image.shape[:2]
input = preprocess_image(input_image,[0.485, 0.456, 0.406],[0.229, 0.224, 0.225],(518,518))
depth = self.model.forward([input])[0]
depth = np.reshape(depth, (1, 518, 518))
depth = (depth - depth.min()) / (depth.max() - depth.min()) * 255.0
depth = depth.transpose(1, 2, 0).astype("uint8")
depth = cv2.resize(depth, (w, h), interpolation=cv2.INTER_CUBIC)
depth_color = cv2.applyColorMap(depth, cv2.COLORMAP_INFERNO)
ros_image = self.bridge.cv2_to_imgmsg(depth_color, encoding="bgr8")
ros_image.header.stamp = self.get_clock().now().to_msg()
ros_image.header.frame_id = "camera_frame"
self.publisher_.publish(ros_image)
def main(args=None):
rclpy.init(args=args)
camera_processor = CameraProcessor()
rclpy.spin(camera_processor)
camera_processor.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
3.compile and execute
colcon build
source install/setup.bash
ros2 run depth_estimate depth
view topic
ros2 topic list
you can see the topic of the original data and depth estimation.
4.rviz visualization results
just subscribe to the relevant topic data in rviz.
ros2 run rviz2 rviz2
Conclusion
Overall, the ‘Radxa Orion O6’ can fully utilize CPU and NPU computation to perform AI model inference in the ROS2 environment, and display it through ROS2’s visualization plugins.