These are sample solutions for the Python scripts from the sending and receiving our first ROS nodes homework exercise.
point_location_sender.py
#!/usr/bin/env python3
""" This script publishes ROS messages containing the 3D coordinates of a single point """
import rospy
from geometry_msgs.msg import Point, PointStamped
from std_msgs.msg import Header
rospy.init_node('send_point_location')
my_header = Header(stamp=rospy.Time.now(), frame_id="odom")
my_point = Point(1.0, 2.0, 0.0)
my_point_stamped = PointStamped(header=my_header, point=my_point)
publisher = rospy.Publisher('/my_point', PointStamped, queue_size=10)
r = rospy.Rate(2)
while not rospy.is_shutdown():
my_point_stamped.header.stamp = rospy.Time.now()
publisher.publish(my_point_stamped)
r.sleep()
point_location_receiver.py
#!/usr/bin/env python3
""" This script receives ROS messages containing the 3D coordinates of a single point and prints them out """
import rospy
from geometry_msgs.msg import PointStamped
rospy.init_node('receive_point_location')
def process_point(data):
print("[{:.2f}, {:.2f}, {:.2f}]".format(data.point.x, data.point.y, data.point.z))
rospy.Subscriber("/my_point", PointStamped, process_point)
rospy.spin()
point_location_sender.py
(object-oriented)
#!/usr/bin/env python3
import rospy
from geometry_msgs.msg import Point, PointStamped
from std_msgs.msg import Header
class SendPointLocation(object):
""" This node publishes ROS messages containing the 3D coordinates of a single point """
def __init__(self):
rospy.init_node('send_point_location')
self.point_location_pub = rospy.Publisher('/my_point', PointStamped, queue_size=10)
def run(self):
my_header = Header(stamp=rospy.Time.now(), frame_id="odom")
my_point = Point(1.0, 2.0, 0.0)
my_point_stamped = PointStamped(header=my_header, point=my_point)
r = rospy.Rate(2)
while not rospy.is_shutdown():
my_point_stamped.header.stamp = rospy.Time.now()
self.point_location_pub.publish(my_point_stamped)
r.sleep()
if __name__ == '__main__':
node = SendPointLocation()
node.run()
point_location_receiver.py
(object-oriented)
#!/usr/bin/env python3
import rospy
from geometry_msgs.msg import PointStamped
class ReceivePointLocation(object):
""" This node receives ROS messages containing the 3D coordinates of a single point and prints them out """
def __init__(self):
rospy.init_node('receive_point_location')
rospy.Subscriber("/my_point", PointStamped, self.process_point)
def process_point(self, data):
print("[{:.2f}, {:.2f}, {:.2f}]".format(data.point.x, data.point.y, data.point.z))
def run(self):
rospy.spin()
if __name__ == '__main__':
node = ReceivePointLocation()
node.run()