niclabox_server.py
Go to the documentation of this file.
1 # BSD 3-Clause License
2 
3 # Copyright (c) 2023, Edoardo Del Bianco, Federico Rollo
4 
5 # Redistribution and use in source and binary forms, with or without
6 # modification, are permitted provided that the following conditions are met:
7 
8 # 1. Redistributions of source code must retain the above copyright notice, this
9 # list of conditions and the following disclaimer.
10 
11 # 2. Redistributions in binary form must reproduce the above copyright notice,
12 # this list of conditions and the following disclaimer in the documentation
13 # and/or other materials provided with the distribution.
14 
15 # 3. Neither the name of the copyright holder nor the names of its
16 # contributors may be used to endorse or promote products derived from
17 # this software without specific prior written permission.
18 
19 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
22 # DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
23 # FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
24 # DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
25 # SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
26 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
27 # OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
28 # OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
29 
30 
31 # receiving distance and picture from Arduino Nicla Vision (client)
32 # and sending them on two ROS messages
33 # the picture fits into one UDP packet after compression
34 
35 import socket
36 
37 import rospy
38 from sensor_msgs.msg import CompressedImage, Image, CameraInfo
39 from sensor_msgs.msg import Range
40 from cv_bridge import CvBridge, CvBridgeError
41 import cv2
42 import numpy as np
43 
44 
45 class Server:
46 
47  # set maximum packet size
48  packet_size = 65540
49 
50  def __init__(self) -> None:
51 
52  # server address and port (the address of the machine running this code, any available port)
53  ip = rospy.get_param("~server_ip")
54  port = rospy.get_param("~server_port")
55 
56  # server socket init
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))
61 
62  distance_topic = rospy.get_param("~distance_topic")
63  self.picture_topic = rospy.get_param("~picture_topic")
64  self.image_raw_topic = rospy.get_param("~image_raw_topic")
65  camera_info_topic = rospy.get_param("~camera_info_topic")
66 
67  self.distance_pub = rospy.Publisher(distance_topic, Range, queue_size=5)
68  if self.picture_topic != "":
69  self.picture_pub = rospy.Publisher(
70  self.picture_topic, CompressedImage, queue_size=5
71  )
72  if self.image_raw_topic != "":
73  self.image_raw_pub = rospy.Publisher(
74  self.image_raw_topic, Image, queue_size=5
75  )
76  self.camera_info_pub = rospy.Publisher(
77  camera_info_topic, CameraInfo, queue_size=5
78  )
79 
80  self.range_msg = Range()
81  self.range_msg.header.frame_id = rospy.get_param("~niclabx_distance_tf")
82  self.range_msg.radiation_type = Range.INFRARED
83  self.range_msg.min_range = 0
84  self.range_msg.max_range = 4
85  self.range_msg.field_of_view = 15
86 
87  self.image_msg = CompressedImage()
88  self.image_msg.format = "jpeg"
89 
90  self.image_raw_msg = Image()
91  self.camera_info_msg = CameraInfo()
92 
93  # self.set_camera_info = rospy.Service('/niclabox/picture/set_camera_info', CameraInfo, self.handle_set_camera_info)
94 
95  # def handle_set_camera_info(self, msg):
96  # print(msg)
97 
98  def receive_and_ros(self):
99  # receive distance value
100  packet, _ = self.server.recvfrom(self.packet_size)
101  ros_time = rospy.Time.now()
102 
103  if len(packet) < 100: # a small packet is the distance
104  distance = packet
105  distance = int.from_bytes(distance, "big")
106 
107  self.range_msg.range = distance
108  self.range_msg.header.stamp = ros_time
109 
110  self.distance_pub.publish(self.range_msg)
111 
112  else: # a big packet is the picture
113 
114  picture = packet
115 
116 
117  if self.picture_topic != "":
118  self.image_msg.header.stamp = ros_time
119  self.image_msg.data = picture
120  self.picture_pub.publish(self.image_msg)
121 
122 
123  if self.image_raw_topic != "":
124  # Convert the byte array to a numpy array
125  nparr = np.frombuffer(picture, np.uint8)
126 
127  # Decode the compressed image
128  img_raw = cv2.imdecode(nparr, cv2.IMREAD_COLOR) # NOTE: BGR CONVENTION
129 
130  # To visualize the received img converted in img_raw
131  # cv2.imshow("Visualize img_raw", img_raw)
132  # cv2.waitKey(1)
133 
134  # Fill in the header
135  self.image_raw_msg.header.stamp = ros_time
136  self.image_raw_msg.header.frame_id = "nicla"
137 
138  # Fill in image height and width
139  self.image_raw_msg.height = img_raw.shape[0]
140  self.image_raw_msg.width = img_raw.shape[1]
141 
142  # Fill in encoding
143  self.image_raw_msg.encoding = (
144  "bgr8" # Assuming OpenCV returns BGR format
145  )
146 
147  # Fill in endianness and step
148  self.image_raw_msg.is_bigendian = 0 # Not big endian
149  self.image_raw_msg.step = (
150  img_raw.shape[1] * 3
151  ) # Width * number of channels
152 
153  # Convert the OpenCV image to ROS Image format using cv_bridge
154  bridge = CvBridge()
155  try:
156  self.image_raw_msg.data = bridge.cv2_to_imgmsg(
157  img_raw, encoding="bgr8"
158  ).data
159  except CvBridgeError as e:
160  print(e)
161 
162  # Publish the ROS Image message
163  self.image_raw_pub.publish(self.image_raw_msg)
164 
165 
166  self.camera_info_msg.header.stamp = ros_time
167  self.camera_info_pub.publish(self.camera_info_msg)
168 
169 
170 if __name__ == "__main__":
171 
172  rospy.init_node("niclabox")
173 
174  server = Server()
175 
176  rate = rospy.Rate(50)
177 
178  rospy.loginfo("Starting receiving loop")
179 
180  while not rospy.is_shutdown():
181 
182  try:
183  server.receive_and_ros()
184 
185  except OSError as e:
186  rospy.logerr(e)
187 
188  pass # try again
189 
190  rate.sleep()
niclabox_server.Server.__init__
None __init__(self)
Definition: niclabox_server.py:50
niclabox_server.Server.picture_pub
picture_pub
Definition: niclabox_server.py:69
niclabox_server.Server
Definition: niclabox_server.py:45
niclabox_server.Server.picture_topic
picture_topic
Definition: niclabox_server.py:63
niclabox_server.Server.image_raw_pub
image_raw_pub
Definition: niclabox_server.py:73
niclabox_server.Server.receive_and_ros
def receive_and_ros(self)
Definition: niclabox_server.py:98
niclabox_server.Server.range_msg
range_msg
Definition: niclabox_server.py:80
niclabox_server.Server.camera_info_pub
camera_info_pub
Definition: niclabox_server.py:76
nicla_receiver.str
str
Definition: nicla_receiver.py:13
niclabox_server.Server.packet_size
int packet_size
Definition: niclabox_server.py:48
niclabox_server.Server.image_msg
image_msg
Definition: niclabox_server.py:87
niclabox_server.Server.image_raw_msg
image_raw_msg
Definition: niclabox_server.py:90
niclabox_server.Server.image_raw_topic
image_raw_topic
Definition: niclabox_server.py:64
niclabox_server.Server.distance_pub
distance_pub
Definition: niclabox_server.py:67
niclabox_server.Server.server
server
Definition: niclabox_server.py:57
niclabox_server.Server.camera_info_msg
camera_info_msg
Definition: niclabox_server.py:91


nicla_vision_ros
Author(s): Davide Torielli , Damiano Gasperini , Edoardo Del Bianco , Federico Rollo
autogenerated on Sat Nov 16 2024 03:38:18