|
| 1 | +#!/usr/bin/env python |
| 2 | + |
| 3 | +# This program publishes a pointcloud2 to test rviz rendering |
| 4 | + |
| 5 | +from __future__ import print_function |
| 6 | + |
| 7 | +import rospy |
| 8 | +import numpy as np |
| 9 | +from sensor_msgs import point_cloud2 |
| 10 | +from sensor_msgs.msg import PointCloud2 |
| 11 | +from sensor_msgs.msg import PointField |
| 12 | +from std_msgs.msg import Header |
| 13 | + |
| 14 | +import math |
| 15 | +import time |
| 16 | +from geometry_msgs.msg import TransformStamped |
| 17 | +from tf2_ros.transform_broadcaster import TransformBroadcaster |
| 18 | +from tf.transformations import quaternion_from_euler |
| 19 | +from visualization_msgs.msg import Marker |
| 20 | + |
| 21 | +RATE = 30 |
| 22 | +width = 100 |
| 23 | +height = 100 |
| 24 | + |
| 25 | + |
| 26 | +def generate_point_cloud(): |
| 27 | + fields = [ |
| 28 | + PointField("x", 0, PointField.FLOAT32, 1), |
| 29 | + PointField("y", 4, PointField.FLOAT32, 1), |
| 30 | + PointField("z", 8, PointField.FLOAT32, 1), |
| 31 | + PointField("intensity", 12, PointField.FLOAT32, 1), |
| 32 | + ] |
| 33 | + |
| 34 | + header = Header() |
| 35 | + header.frame_id = "map" |
| 36 | + header.stamp = rospy.Time.now() |
| 37 | + |
| 38 | + x, y = np.meshgrid(np.linspace(-2, 2, width), np.linspace(-2, 2, height)) |
| 39 | + z = 0.5 * np.sin(2 * x) * np.sin(3 * y) |
| 40 | + points = np.array([x, y, z, z]).reshape(4, -1).T |
| 41 | + |
| 42 | + return point_cloud2.create_cloud(header, fields, points) |
| 43 | + |
| 44 | + |
| 45 | +def draw_eight(elapsed_time, full_cycle_duration=10, scale=10): |
| 46 | + # lemniscate of Gerono |
| 47 | + progress = (elapsed_time % full_cycle_duration) / full_cycle_duration |
| 48 | + t = -0.5 * math.pi + progress * (2 * math.pi) |
| 49 | + x = math.cos(t) * scale |
| 50 | + y = math.sin(t) * math.cos(t) * scale |
| 51 | + dx_dt = -math.sin(t) |
| 52 | + dy_dt = math.cos(t) * math.cos(t) - math.sin(t) * math.sin(t) |
| 53 | + yaw = math.atan2(dy_dt, dx_dt) |
| 54 | + return x, y, yaw |
| 55 | + |
| 56 | + |
| 57 | +def display_dummy_robot(stamp): |
| 58 | + marker = Marker() |
| 59 | + marker.header.frame_id = "base_link" |
| 60 | + marker.header.stamp = stamp |
| 61 | + marker.ns = "robot" |
| 62 | + marker.id = 0 |
| 63 | + marker.type = Marker.CUBE |
| 64 | + marker.action = Marker.ADD |
| 65 | + marker.pose.position.x = 0 |
| 66 | + marker.pose.position.y = 0 |
| 67 | + marker.pose.position.z = 0 |
| 68 | + marker.pose.orientation.x = 0.0 |
| 69 | + marker.pose.orientation.y = 0.0 |
| 70 | + marker.pose.orientation.z = 0.0 |
| 71 | + marker.pose.orientation.w = 1.0 |
| 72 | + marker.scale.x = 1 |
| 73 | + marker.scale.y = 1 |
| 74 | + marker.scale.z = 1 |
| 75 | + marker.color.a = 1.0 |
| 76 | + marker.color.r = 0.0 |
| 77 | + marker.color.g = 1.0 |
| 78 | + marker.color.b = 0.0 |
| 79 | + vis_pub.publish(marker) |
| 80 | + |
| 81 | + |
| 82 | +if __name__ == "__main__": |
| 83 | + rospy.init_node("point_cloud_test") |
| 84 | + |
| 85 | + tf_broadcaster = TransformBroadcaster() |
| 86 | + |
| 87 | + vis_pub = rospy.Publisher("robot/marker", Marker, queue_size=5) |
| 88 | + pc_pub = rospy.Publisher("points2", PointCloud2, queue_size=5) |
| 89 | + pc = generate_point_cloud() |
| 90 | + |
| 91 | + i = 0 |
| 92 | + rate = rospy.Rate(RATE) |
| 93 | + start = rospy.Time.now() |
| 94 | + while not rospy.is_shutdown(): |
| 95 | + now = rospy.Time.now() |
| 96 | + |
| 97 | + if i % RATE == 0: |
| 98 | + # publish just once per second |
| 99 | + pc.header.stamp = now |
| 100 | + pc_pub.publish(pc) |
| 101 | + i += 1 |
| 102 | + |
| 103 | + robot_x, robot_y, robot_yaw = draw_eight((now - start).to_sec()) |
| 104 | + q = quaternion_from_euler(0, 0, robot_yaw) |
| 105 | + |
| 106 | + tf = TransformStamped() |
| 107 | + tf.header.frame_id = "map" |
| 108 | + tf.header.stamp = now |
| 109 | + tf.child_frame_id = "base_link" |
| 110 | + tf.transform.translation.x = robot_x |
| 111 | + tf.transform.translation.y = robot_y |
| 112 | + tf.transform.rotation.x = q[0] |
| 113 | + tf.transform.rotation.y = q[1] |
| 114 | + tf.transform.rotation.z = q[2] |
| 115 | + tf.transform.rotation.w = q[3] |
| 116 | + tf_broadcaster.sendTransform(tf) |
| 117 | + |
| 118 | + display_dummy_robot(now) |
| 119 | + |
| 120 | + rate.sleep() |
0 commit comments