Lidar Object Detection in ROS Using PointPillars Deep Learning
In this example, you will create a ROS node to deploy a pre-trained PointPillars Deep Learning Model to detect 3D objects in point cloud images.
Feed the point cloud image into the ROS node equipped with the pre-trained PointPillars Deep Learning Model. This model employs the PointPillars network to convert sparse point clouds into 'pillars' and extract dense, robust features. It then applies a modified SSD-based 2D deep learning network to simultaneously determine 3D bounding box coordinates, object orientations, and class predictions. Upon processing, the ROS node outputs the coordinates of the 3D bounding boxes and the associated object labels, such as 'car' or 'bus'.
To understand how to train a PointPillars network for object detection in point cloud, refer to the Lidar 3-D Object Detection Using PointPillars Deep Learning (Lidar Toolbox) example.

Prerequisites
Configure MATLAB® Coder™ software to generate and build CUDA® ROS nodes from a MATLAB function by following the steps outlined in the Generate CUDA ROS and CUDA ROS 2 Nodes Using MATLAB Coder and GPU Coder example.
Configure MATLAB Coder for CUDA ROS Node Generation
Initialize ROS Core and Global Node.
rosinit
Create MATLAB Function to run Pre-trained PointPillars Model
Write a MATLAB function to subscribe to the point cloud image and apply PointPillars algorithm to detect 3D objects in it.
type('deployedPointPillarModel.m')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)");Select Localhost to deploy the object detection algorithm on a local host computer with a CUDA-enabled NVIDIA GPU.
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 deployedPointPillarModel -config cfg
Check the list of all nodes registered on the ROS network.
rosnode listCreate Publisher and Subscriber to Communicate with Deployed ROS Node Containing Pre-trained PointPillars Model
The list below contains all topics used in this network:
- "/ - pointCloudData" topic transmits point cloud data.
- "/ - nodeboxData" topic transfers the coordinates of the bounding boxes where objects are detected.
- "/ - nodeLabelsData" topic transfers the labels corresponding to each bounding box detected in the point cloud.
pcpub = rospublisher("/pointCloudData","sensor_msgs/PointCloud2",DataFormat="struct"); nodeboxSub = rossubscriber("/nodeboxData","std_msgs/Float64MultiArray",DataFormat="struct"); nodeLabelsSub = rossubscriber("/nodeLabelsData","std_msgs/String",DataFormat="struct");
Send Point Cloud Data to PointPillars Model Deployed on ROS Node
The "images.mat" file stores 2 point clouds selected from the dataset used in the Lidar 3-D Object Detection Using PointPillars Deep Learning (Lidar Toolbox) example.
% Load the point cloud from "images.mat" file load("images.mat"); PtCloud = im1_ptCloud; % or im2_ptCloud figure; ax = pcshow(PtCloud); title("PointCloud Image"); zoom(ax,1.5);

% Create a new ROS message for publishing point cloud data pcdata = rosmessage(pcpub); % Write data points in x, y and z coordinates to a ROS PointCloud2 message structure pcdata = rosWriteXYZ(pcdata,PtCloud.Location); % Write intensity data points to a ROS PointCloud2 message structure pcdata = rosWriteIntensity(pcdata,PtCloud.Intensity); % Publish a point cloud message to a ROS topic send(pcpub,pcdata); pause(5);
Receive Bounding Box Details from ROS Node
% Use the subscribers to read the response from deployed PointPillars model box = nodeboxSub.LatestMessage.Data; appStr = nodeLabelsSub.LatestMessage.Data; % Process the data received on the two rostopics. strArr = split(appStr,'_'); labels = categorical(strArr); labels = labels'; box = reshape(box,length(labels),length(box)/length(labels)); boxlabelsCar = box(labels'=='Car',:); boxlabelsTruck = box(labels'=='Truck',:);
Display Predicted Bounding Boxes
helperDisplay3DBoxesOverlaidPointCloud(PtCloud.Location,boxlabelsCar,'green',boxlabelsTruck,'magenta','Predicted Bounding Boxes');

Shut down ROS Network
rosshutdown
Helper Function
function helperDisplay3DBoxesOverlaidPointCloud(ptCld,labelsCar,carColor,labelsTruck,truckColor,titleForFigure) % Display the point cloud with different colored bounding boxes for different classes. figure; ax = pcshow(ptCld); showShape('cuboid',labelsCar,'Parent',ax,'Opacity',0.1,'Color',carColor,'LineWidth',0.5); hold on; showShape('cuboid',labelsTruck,'Parent',ax,'Opacity',0.1,'Color',truckColor,'LineWidth',0.5); title(titleForFigure); zoom(ax,1.5); end
See Also
Generate CUDA ROS and CUDA ROS 2 Nodes Using MATLAB Coder and GPU Coder