38 from sensor_msgs.msg
import CompressedImage, Image, CameraInfo
39 from sensor_msgs.msg
import Range
40 from cv_bridge
import CvBridge, CvBridgeError
53 ip = rospy.get_param(
"~server_ip")
54 port = rospy.get_param(
"~server_port")
57 self.
server = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
58 self.
server.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1)
59 self.
server.bind((ip, port))
60 rospy.loginfo(
"Waiting for niclabox to stream on " + ip +
" : " +
str(port))
62 distance_topic = rospy.get_param(
"~distance_topic")
65 camera_info_topic = rospy.get_param(
"~camera_info_topic")
67 self.
distance_pub = rospy.Publisher(distance_topic, Range, queue_size=5)
77 camera_info_topic, CameraInfo, queue_size=5
81 self.
range_msg.header.frame_id = rospy.get_param(
"~niclabx_distance_tf")
82 self.
range_msg.radiation_type = Range.INFRARED
101 ros_time = rospy.Time.now()
103 if len(packet) < 100:
105 distance = int.from_bytes(distance,
"big")
125 nparr = np.frombuffer(picture, np.uint8)
128 img_raw = cv2.imdecode(nparr, cv2.IMREAD_COLOR)
157 img_raw, encoding=
"bgr8"
159 except CvBridgeError
as e:
170 if __name__ ==
"__main__":
172 rospy.init_node(
"niclabox")
176 rate = rospy.Rate(50)
178 rospy.loginfo(
"Starting receiving loop")
180 while not rospy.is_shutdown():
183 server.receive_and_ros()