Generate CUDA ROS and CUDA ROS 2 Nodes Using MATLAB Coder and GPU Coder
Configure MATLAB® Coder™ software to generate and build CUDA® ROS and CUDA® ROS 2 nodes from a MATLAB function. You can deploy the CUDA nodes to local or remote GPU target devices.
In this example, you deploy MobileNet-v2 object detection algorithm on a local host computer with a supported NVIDIA graphics card.
Begin by creating a ROS publisher to publish the ROS image and run prediction on it using MobileNet-v2 object detection algorithm. You then generate a local host node to deploy the object detection algorithm on a local host computer with a CUDA-enabled NVIDIA GPU. Finally, you create a ROS subscriber to plot the top five prediction scores.
Prerequisites
1. Install and set up these MathWorks® products and support packages: MATLAB® Coder™ (required), Embedded Coder® (recommended), GPU Coder™, and GPU Coder Interface for Deep Learning (required for Deep Learning).
Note: GPU Coder™ is supported only on Windows and Linux.
2. You can also install MATLAB® Coder™ Support Package for NVIDIA® Jetson™ and NVIDIA DRIVE™ Platforms (required for an NVIDIA hardware connection).
3. Your target device can be a local host computer with a CUDA-enabled NVIDIA GPU, or a remote device such as an NVIDIA Jetson board.
4. To use GPU Coder for CUDA code generation, you must install NVIDIA graphics driver, CUDA toolkit, cuDNN library, and TensorRT library. For more information on local host deployment and host simulation, see Installing Prerequisite Products (GPU Coder).
5. To set up the environment variables, see Setting Up the Prerequisite Products (GPU Coder). Before you run the node, set the CODER_DATA_PATH
environment variable to the path containing the bin files.
6. To ensure you have the required third-party software, see ROS Toolbox System Requirements.
Verify GPU Environment for GPU Code Generation
To verify that your development computer has the drivers, tools, libraries, and configuration required for GPU code generation, see Setting Up the Prerequisite Products (GPU Coder).
Create a coder.gpuEnvConfig
(GPU Coder) object and set its property values. Then, verify your GPU code generation environment using the coder.checkGpuInstall
(GPU Coder) function.
gpuEnvObj = coder.gpuEnvConfig;
gpuEnvObj.BasicCodegen = 1;
gpuEnvObj.BasicCodeexec = 1;
gpuEnvObj.DeepLibTarget = "tensorrt";
gpuEnvObj.DeepCodeexec = 1;
gpuEnvObj.DeepCodegen = 1;
results = coder.checkGpuInstall(gpuEnvObj)
The output is representative. Results might differ from user to user.
Compatible GPU : PASSED CUDA Environment : PASSED Runtime : PASSED cuFFT : PASSED cuSOLVER : PASSED cuBLAS : PASSED cuDNN Environment : PASSED TensorRT Environment : PASSED Basic Code Generation : PASSED Basic Code Execution : PASSED Deep Learning (TensorRT) Code Generation: PASSED Deep Learning (TensorRT) Code Execution: PASSED results = struct with fields: gpu: 1 cuda: 1 cudnn: 1 tensorrt: 1 basiccodegen: 1 basiccodeexec: 1 deepcodegen: 1 deepcodeexec: 1 tensorrtdatatype: 1 profiling: 0
Configure MATLAB Coder for CUDA ROS Node Generation
Initialize ROS Core and Global Node.
rosinit
Launching ROS Core... .Done in 1.1242 seconds. Initializing ROS master on http://172.18.226.60:11311. Initializing global node /matlab_global_node_73382 with NodeURI http://hyd-jkonakal:49931/ and MasterURI http://localhost:11311.
Create MATLAB Function for Deep Learning
Write a MATLAB function to subscribe to the image and apply MobileNet-v2 algorithm to analyze the probability of pepper.
type('mobilenet_ros1node_predictor.m')
function mobilenet_ros1node_predictor % Copyright 2022 The MathWorks, Inc. %#codegen % Create an image subscriber imgSub = rossubscriber("/image_topic","sensor_msgs/Image","DataFormat","struct"); % Create a scores results publisher scoresPub = rospublisher('/score_results','std_msgs/Float32MultiArray',... 'DataFormat','struct'); scoresMsg = rosmessage("std_msgs/Float32MultiArray", "DataFormat","struct"); % Create an index results publisher indexPub = rospublisher('/index_results','std_msgs/Float32MultiArray',... 'DataFormat','struct'); indexMsg = rosmessage("std_msgs/Float32MultiArray", "DataFormat","struct"); upperImageSize = [224,224,3]; in = zeros(upperImageSize,'uint8'); r = rosrate(30); reset(r); while (1) receivedImage = imgSub.LatestMessage; while ~isempty(receivedImage) && ~isempty(receivedImage.Data) imageData = rosReadImage(receivedImage,"Encoding","rgb8"); % Crop the received image if it exceeds the upper size imgSize = size(imageData); index = min(imgSize,upperImageSize); in(1:index(1),1:index(2),1:index(3)) = imageData(1:index(1),1:index(2),1:index(3)); % pass image to mobilenetv2_predict network predict_scores = mobilenetv2_predict(in); [scores,indexes] = sort(predict_scores, 'descend'); scoresMsg.Data = zeros(1000,1,'single'); indexMsg.Data = zeros(1000,1,'single'); if ~isempty(scores) scoresMsg.Data = single(scores'); indexMsg.Data = single(indexes'); end send(scoresPub,scoresMsg); send(indexPub,indexMsg); end waitfor(r); end end
Generate Local Host Node
Configure MATLAB Code Generation config
object settings and generate local host node.
cfg = coder.config("exe");
Select the ROS version.
cfg.Hardware = coder.hardware("Robot Operating System (ROS)");
cfg.CppPreserveClasses = false;
Select Localhost to deploy the object detection algorithm on a local host computer with a CUDA-enabled NVIDIA GPU.
NOTE: Select Remote Hardware to deploy the object detection algorithm on a remote target device such as NVIDIA Jetson board.
cfg.Hardware.DeployTo = "Localhost"; cfg.Hardware.BuildAction = "Build and run"; cfg.HardwareImplementation.ProdHWDeviceType = "Intel->x86-64 (Windows64)"; cfg.HardwareImplementation.ProdLongLongMode = true; % Use 'long long' for Int64 or Uint64 data types
Create the GpuCodeConfig
object and enable it.
cfg.GpuConfig = coder.GpuCodeConfig; cfg.GpuConfig.Enabled = true;
Create a DeepLearningConfig
object and select the appropriate DNN library.
cfg.DeepLearningConfig = coder.DeepLearningConfig('cudnn'); codegen mobilenet_ros1node_predictor -config cfg
Warning: Generation of C++ classes for MATLAB classes is not supported by GPU Coder. Disabling this option for GPU code generation.
--- Running ROS node. Warning: Function 'mobilenet_ros1node_predictor' does not terminate due to an infinite loop. Warning in ==> mobilenet_ros1node_predictor Line: 50 Column: 1 Code generation successful (with warnings): View report
When codegen
is successful, it creates a ROS node /mobilenet_ros1node_predictor
on your local machine. You can verify the successful creation of the node by using rosnode list
.
rosnode list
/matlab_global_node_73382 /mobilenet_ros1node_predictor
Create a publisher to read the ROS image and publish it to the /image_topic
.
publishpepperimage
Visualize Probability Data
Subscribe to the topic and plot the top five prediction scores.
visualizepredictiondata
You can generate and build ROS 2 CUDA node using the following steps, to deploy them to local host computer.
Configure MATLAB Coder for CUDA ROS 2 Node Generation
To generate a CUDA ROS 2 node, create a MATLAB function for deep learning corresponding to ROS 2.
type('mobilenet_ros2node_predictor.m')
function mobilenet_ros2node_predictor % Copyright 2022-23 The MathWorks, Inc. %#codegen % Create a ROS 2 node node = ros2node('ros2_cuda_node'); % Create an image subscriber imgSub = ros2subscriber(node,'/image_topic','sensor_msgs/Image'); % Create a scores results publisher scoresPub = ros2publisher(node,'/score_results','std_msgs/Float32MultiArray'); scoresMsg = ros2message("std_msgs/Float32MultiArray"); % Create an index results publisher indexPub = ros2publisher(node,'/index_results','std_msgs/Float32MultiArray'); indexMsg = ros2message("std_msgs/Float32MultiArray"); upperImageSize = [224,224,3]; in = zeros(upperImageSize,'uint8'); r = ros2rate(node,30); reset(r); while (1) receivedImage = imgSub.LatestMessage; while ~isempty(receivedImage) && ~isempty(receivedImage.data) imageData = rosReadImage(receivedImage,'Encoding','rgb8'); % Crop the received image if it exceeds the upper size imgSize = size(imageData); index = min(imgSize,upperImageSize); in(1:index(1),1:index(2),1:index(3)) = imageData(1:index(1),1:index(2),1:index(3)); % pass image to mobilenetv2_predict network predict_scores = mobilenetv2_predict(in); [scores,indexes] = sort(predict_scores, 'descend'); scoresMsg.data = zeros(1000,1,'single'); indexMsg.data = zeros(1000,1,'single'); if ~isempty(scores) scoresMsg.data = single(scores'); indexMsg.data = single(indexes'); end send(scoresPub,scoresMsg); send(indexPub,indexMsg); end waitfor(r); end end
Now configure the config
object settings for executable code.
cfg = coder.config("exe");
Select the ROS version as ROS 2.
cfg.Hardware = coder.hardware("Robot Operating System 2 (ROS 2)");
cfg.CppPreserveClasses = false;
Select Localhost to deploy the object detection algorithm on a local host computer with a CUDA-enabled NVIDIA GPU.
NOTE: Select Remote Hardware to deploy the object detection algorithm on a remote target device such as NVIDIA Jetson board.
cfg.Hardware.DeployTo = "Localhost"; cfg.Hardware.BuildAction = "Build and run"; cfg.HardwareImplementation.ProdHWDeviceType = "Intel->x86-64 (Windows64)"; cfg.HardwareImplementation.ProdLongLongMode = true; % Use 'long long' for Int64 or Uint64 data types
Create the GpuCodeConfig
object and enable it.
cfg.GpuConfig = coder.GpuCodeConfig; cfg.GpuConfig.Enabled = true;
Create a DeepLearningConfig
object and select the appropriate DNN library.
cfg.DeepLearningConfig = coder.DeepLearningConfig('cudnn'); codegen mobilenet_ros2node_predictor -config cfg
When codegen
is successful, it creates a ROS 2 node /mobilenet_ros2node_predictor
on your local machine. You can verify the successful creation of the node by using ros2 node list
.
ros2 node list
Create a publisher to read the image and publish it to the /image_topic
.
publishpepperimage_ros2
Visualize Probability Data
Subscribe to the topic and plot the top five prediction scores.
visualizepredictiondata_ros2
Limitations
The build folder path cannot contain any spaces.