ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
Here is an example on how to publish a sensor_msgs/PointCloud in ros by using python:
#!/usr/bin/env python
import rospy
from sensor_msgs.msg import PointCloud
from geometry_msgs.msg import Point32
import std_msgs.msg
if __name__ == '__main__':
'''
Publishes example pointcloud
'''
rospy.init_node('point_polygon_scaler')
pointcloud_publisher = rospy.Publisher("/my_pointcloud_topic", PointCloud)
rospy.loginfo("pcl_publish_example")
#giving some time for the publisher to register
rospy.sleep(0.5)
#declaring pointcloud
my_awesome_pointcloud = PointCloud()
#filling pointcloud header
header = std_msgs.msg.Header()
header.stamp = rospy.Time.now()
header.frame_id = 'map'
my_awesome_pointcloud.header = header
#filling some points
my_awesome_pointcloud.points.append(Point32(1.0, 1.0, 0.0))
my_awesome_pointcloud.points.append(Point32(2.0, 2.0, 0.0))
my_awesome_pointcloud.points.append(Point32(3.0, 3.0, 0.0))
#publish
print "happily publishing pointcloud"
pointcloud_publisher.publish(my_awesome_pointcloud)
#exit. we are done!
print "bye bye..."
If you want to use sensor_msgs/Pointcloud2 then:
#!/usr/bin/env python
import rospy
import math
import sys
from sensor_msgs.msg import PointCloud2
import std_msgs.msg
import sensor_msgs.point_cloud2 as pcl2
if __name__ == '__main__':
'''
Sample code to publish a pcl2 with python
'''
rospy.init_node('pcl2_pub_example')
pcl_pub = rospy.Publisher("/my_pcl_topic", PointCloud2)
rospy.loginfo("Initializing sample pcl2 publisher node...")
#give time to roscore to make the connections
rospy.sleep(1.)
cloud_points = [[1.0, 1.0, 0.0],[1.0, 2.0, 0.0]]
#header
header = std_msgs.msg.Header()
header.stamp = rospy.Time.now()
header.frame_id = 'map'
#create pcl from points
scaled_polygon_pcl = pcl2.create_cloud_xyz32(header, cloud_points)
#publish
rospy.loginfo("happily publishing sample pointcloud.. !")
pcl_pub.publish(scaled_polygon_pcl)
enjoy !