NiclaRosPublisherMicroPy.py
Go to the documentation of this file.
1 #!/usr/bin/env python3
2 
3 import struct
4 import rospy
5 from sensor_msgs.msg import CompressedImage, Image, CameraInfo
6 from sensor_msgs.msg import Range
7 from sensor_msgs.msg import Imu
8 from std_msgs.msg import String
9 from audio_common_msgs.msg import AudioData, AudioDataStamped, AudioInfo
10 from cv_bridge import CvBridge, CvBridgeError
11 import cv2
12 import numpy as np
13 
14 from nicla_vision_ros import NiclaReceiverUDPMicroPy, NiclaReceiverTCPMicroPy
15 
16 
18 
19  def __init__(self) -> None:
20 
21  # used for some header, be sure to use the same name here and
22  # in the urdf for proper rviz visualization
23  nicla_name = rospy.get_param("~nicla_name", "nicla")
24 
25  # server address and port (the address of the machine running
26  # this code, any available port)
27  ip = rospy.get_param("~receiver_ip")
28  port = rospy.get_param("~receiver_port", "8002")
29  connection_type = rospy.get_param("~connection_type", "udp")
30 
31  self.enable_range = rospy.get_param("~enable_range", True)
32  self.enable_camera_raw = rospy.get_param("~enable_camera_raw", True)
33  self.enable_camera_compressed = rospy.get_param(
34  "~enable_camera_compressed", False
35  )
36  self.enable_audio = rospy.get_param("~enable_audio", True)
37  self.enable_audio_stamped = rospy.get_param(
38  "~enable_audio_stamped", False
39  )
40  self.enable_audio_recognition_vosk = rospy.get_param(
41  "~enable_audio_recognition_vosk", False
42  )
43  self.audio_recognition_model_path = rospy.get_param(
44  "~audio_recognition_model_path", ""
45  )
46  self.audio_recognition_grammar = rospy.get_param(
47  "~audio_recognition_grammar", ""
48  )
49  self.audio_recognition_listen_seconds = rospy.get_param(
50  "~audio_recognition_listen_seconds", 2
51  )
53  "~audio_recognition_wave_output_filename", ""
54  )
55  self.enable_imu = rospy.get_param("~enable_imu", True)
56 
57  if self.enable_range:
58  range_topic = nicla_name + "/tof"
59  self.range_pub = rospy.Publisher(range_topic, Range, queue_size=5)
60  self.range_msg = Range()
61  self.range_msg.header.frame_id = nicla_name + "_tof"
62  self.range_msg.radiation_type = Range.INFRARED
63  self.range_msg.min_range = 0
64  self.range_msg.max_range = 3.60
65  self.range_msg.field_of_view = (
66  0.471239 # 27degrees according to VL53L1X spec
67  )
68 
69  if self.enable_camera_raw:
70  # default topic name of image transport (which is not available
71  # in python so we do not use it)
72  self.image_raw_topic = nicla_name + "/camera/image_raw"
73  self.image_raw_msg = Image()
74  self.image_raw_msg.header.frame_id = nicla_name + "_camera"
75  self.image_raw_pub = rospy.Publisher(
76  self.image_raw_topic, Image, queue_size=5
77  )
78 
81  nicla_name + "/camera/image_raw/compressed"
82  )
83  self.image_compressed_msg = CompressedImage()
84  self.image_compressed_msg.header.frame_id = nicla_name + "_camera"
85  self.image_compressed_msg.format = "jpeg"
86  self.image_compressed_pub = rospy.Publisher(
87  self.image_compressed_topic, CompressedImage, queue_size=5
88  )
89 
91  camera_info_topic = nicla_name + "/camera/camera_info"
92  self.camera_info_msg = CameraInfo()
93  self.camera_info_msg.header.frame_id = nicla_name + "_camera"
94  self.camera_info_msg.height = 240
95  self.camera_info_msg.width = 320
96  self.camera_info_msg.distortion_model = "plumb_rob"
97  self.camera_info_msg.K = [
98  416.650528,
99  0.000000,
100  166.124514,
101  0.000000,
102  419.404643,
103  104.410543,
104  0.000000,
105  0.000000,
106  1.000000,
107  ]
108  self.camera_info_msg.D = [
109  0.176808,
110  -0.590488,
111  -0.008412,
112  0.015473,
113  0.000000,
114  ]
115  self.camera_info_msg.P = [
116  421.373566,
117  0.000000,
118  168.731782,
119  0.000000,
120  0.000000,
121  426.438812,
122  102.665989,
123  0.000000,
124  0.000000,
125  0.000000,
126  1.000000,
127  0.000000,
128  ]
129  self.camera_info_pub = rospy.Publisher(
130  camera_info_topic, CameraInfo, queue_size=5
131  )
132 
133  if self.enable_audio:
134  audio_topic = nicla_name + "/audio"
135  self.audio_msg = AudioData()
136  self.audio_pub = rospy.Publisher(
137  audio_topic, AudioData, queue_size=10
138  )
139 
140  if self.enable_audio_stamped:
141  audio_stamped_topic = nicla_name + "/audio_stamped"
142  self.audio_stamped_msg = AudioDataStamped()
143  self.audio_stamped_pub = rospy.Publisher(
144  audio_stamped_topic, AudioDataStamped, queue_size=10
145  )
146 
147  if self.enable_audio or self.enable_audio_stamped:
148  audio_info_topic = nicla_name + "/audio_info"
149  self.audio_info_msg = AudioInfo()
150  self.audio_info_msg.channels = 1
151  self.audio_info_msg.sample_rate = 16000
152  self.audio_info_msg.sample_format = "S16LE"
153  self.audio_info_msg.bitrate = 0
154  self.audio_info_msg.coding_format = "raw"
155  self.audio_info_pub = rospy.Publisher(
156  audio_info_topic, AudioInfo, queue_size=1
157  )
158 
159  if self.enable_imu:
160  imu_topic = nicla_name + "/imu"
161  self.imu_msg = Imu()
162  self.imu_msg.header.frame_id = nicla_name + "_imu"
163  self.imu_msg.orientation.x = 0
164  self.imu_msg.orientation.y = 0
165  self.imu_msg.orientation.z = 0
166  self.imu_msg.orientation.w = 1
167  self.imu_pub = rospy.Publisher(imu_topic, Imu, queue_size=5)
168 
169  if connection_type == "udp":
171  ip,
172  port,
173  enable_range=self.enable_range,
174  enable_image=self.enable_camera_raw
175  or self.enable_camera_compressed,
176  enable_audio=self.enable_audio or self.enable_audio_stamped,
177  enable_imu=self.enable_imu,
178  )
179  elif connection_type == "tcp":
181  ip,
182  port,
183  enable_range=self.enable_range,
184  enable_image=self.enable_camera_raw
185  or self.enable_camera_compressed,
186  enable_audio=self.enable_audio or self.enable_audio_stamped,
187  enable_imu=self.enable_imu,
188  )
189 
190  else:
191  rospy.logerr("Connection type ", connection_type, " not known")
192  raise Exception("Connection type not known")
193 
195  if not self.audio_recognition_model_path:
196  rospy.logerr(
197  "Path for VOSK recognizer model is an empty string! Please provide 'audio_recognition_model_path' arg"
198  )
199  exit()
200 
201  from nicla_vision_ros import SpeechRecognizer
202 
208  )
209  self.speech_recognizer_pub = rospy.Publisher(
210  nicla_name + "/audio_recognized", String, queue_size=10
211  )
212 
213  self.nicla_receiver_server.serve()
214 
215  def run(self):
216 
217  if self.enable_range and (
218  (range := self.nicla_receiver_server.get_range()) is not None
219  ):
220 
221  self.range_msg.header.stamp = rospy.Time.from_sec(range[0])
222  self.range_msg.range = int.from_bytes(range[1], "big") / 1000
223  self.range_pub.publish(self.range_msg)
224 
225 
227 
228  if (image := self.nicla_receiver_server.get_image()) is not None:
229 
230 
231  self.camera_info_msg.header.stamp = rospy.Time.from_sec(
232  image[0]
233  )
234  self.camera_info_pub.publish(self.camera_info_msg)
235 
236 
237  if self.enable_camera_compressed:
238  self.image_compressed_msg.header.stamp = (
239  rospy.Time.from_sec(image[0])
240  )
241  self.image_compressed_msg.data = image[1]
242  self.image_compressed_pub.publish(
244  )
245 
246 
247  if self.enable_camera_raw:
248  # Convert the byte array to a numpy array
249  nparr = np.frombuffer(image[1], np.uint8)
250 
251  # Decode the compressed image
252  img_raw = cv2.imdecode(
253  nparr, cv2.IMREAD_COLOR
254  ) # NOTE: BGR CONVENTION
255 
256  self.image_raw_msg.header.stamp = rospy.Time.from_sec(
257  image[0]
258  )
259  self.image_raw_msg.height = img_raw.shape[0]
260  self.image_raw_msg.width = img_raw.shape[1]
261  self.image_raw_msg.encoding = (
262  "bgr8" # Assuming OpenCV returns BGR format
263  )
264  self.image_raw_msg.is_bigendian = 0 # Not big endian
265  self.image_raw_msg.step = (
266  img_raw.shape[1] * 3
267  ) # Width * number of channels
268 
269  # Convert the OpenCV image to ROS Image format using cv_bridge
270  bridge = CvBridge()
271  try:
272  self.image_raw_msg.data = bridge.cv2_to_imgmsg(
273  img_raw, encoding="bgr8"
274  ).data
275  except CvBridgeError as e:
276  print(e)
277 
278  self.image_raw_pub.publish(self.image_raw_msg)
279 
280 
281  if self.enable_audio or self.enable_audio_stamped:
282  self.audio_info_pub.publish(self.audio_info_msg)
283 
284  if (
285  self.enable_audio
286  or self.enable_audio_stamped
288  ):
289 
290  if (
291  audio_data := self.nicla_receiver_server.get_audio()
292  ) is not None:
293 
294  if self.enable_audio:
295  self.audio_msg.data = audio_data[1]
296  self.audio_pub.publish(self.audio_msg)
297 
298  if self.enable_audio_stamped:
299  self.audio_stamped_msg.header.stamp = rospy.Time.from_sec(
300  audio_data[0]
301  )
302  self.audio_stamped_msg.audio.data = audio_data[1]
303  self.audio_stamped_pub.publish(self.audio_stamped_msg)
304 
306  audio_recognized = self.speech_recognizer.process_audio(
307  audio_data[1]
308  )
309  if audio_recognized: # if not empty
310  self.speech_recognizer_pub.publish(audio_recognized)
311 
312 
313  if self.enable_imu and (
314  (imu := self.nicla_receiver_server.get_imu()) is not None
315  ):
316  self.imu_msg.header.stamp = rospy.Time.from_sec(imu[0])
317 
318  try:
319  acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z = struct.unpack(
320  ">ffffff", imu[1]
321  ) # >: big endian
322  except Exception as e:
323  rospy.logerr("imu pack has ", len(imu[1]), " bytes")
324  raise e
325 
326  self.imu_msg.angular_velocity.x = 0.017453 * gyro_x
327  self.imu_msg.angular_velocity.y = 0.017453 * gyro_y
328  self.imu_msg.angular_velocity.z = 0.017453 * gyro_z
329  self.imu_msg.linear_acceleration.x = 9.80665 * acc_x
330  self.imu_msg.linear_acceleration.y = 9.80665 * acc_y
331  self.imu_msg.linear_acceleration.z = 9.80665 * acc_z
332  self.imu_pub.publish(self.imu_msg)
333 
334  def stop(self):
335  self.nicla_receiver_server.stop_serve()
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.imu_pub
imu_pub
Definition: NiclaRosPublisherMicroPy.py:167
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy
Definition: NiclaRosPublisherMicroPy.py:17
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.enable_camera_raw
enable_camera_raw
Definition: NiclaRosPublisherMicroPy.py:32
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.audio_recognition_listen_seconds
audio_recognition_listen_seconds
Definition: NiclaRosPublisherMicroPy.py:49
nicla_vision_ros.NiclaReceiverServerMicroPy.NiclaReceiverTCPMicroPy
Definition: NiclaReceiverServerMicroPy.py:173
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.range_pub
range_pub
Definition: NiclaRosPublisherMicroPy.py:59
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.audio_msg
audio_msg
Definition: NiclaRosPublisherMicroPy.py:135
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.image_compressed_msg
image_compressed_msg
Definition: NiclaRosPublisherMicroPy.py:83
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.audio_recognition_grammar
audio_recognition_grammar
Definition: NiclaRosPublisherMicroPy.py:46
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.enable_imu
enable_imu
Definition: NiclaRosPublisherMicroPy.py:55
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.run
def run(self)
Definition: NiclaRosPublisherMicroPy.py:215
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.audio_info_pub
audio_info_pub
Definition: NiclaRosPublisherMicroPy.py:155
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.camera_info_pub
camera_info_pub
Definition: NiclaRosPublisherMicroPy.py:129
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.image_compressed_topic
image_compressed_topic
Definition: NiclaRosPublisherMicroPy.py:80
nicla_vision_ros.SpeechRecognizer.SpeechRecognizer
Definition: SpeechRecognizer.py:9
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.imu_msg
imu_msg
Definition: NiclaRosPublisherMicroPy.py:161
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.speech_recognizer
speech_recognizer
Definition: NiclaRosPublisherMicroPy.py:203
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.enable_audio
enable_audio
Definition: NiclaRosPublisherMicroPy.py:36
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.audio_pub
audio_pub
Definition: NiclaRosPublisherMicroPy.py:136
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.image_raw_msg
image_raw_msg
Definition: NiclaRosPublisherMicroPy.py:73
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.image_raw_topic
image_raw_topic
Definition: NiclaRosPublisherMicroPy.py:72
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.audio_info_msg
audio_info_msg
Definition: NiclaRosPublisherMicroPy.py:149
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.audio_recognition_model_path
audio_recognition_model_path
Definition: NiclaRosPublisherMicroPy.py:43
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.enable_camera_compressed
enable_camera_compressed
Definition: NiclaRosPublisherMicroPy.py:33
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.audio_stamped_pub
audio_stamped_pub
Definition: NiclaRosPublisherMicroPy.py:143
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.camera_info_msg
camera_info_msg
Definition: NiclaRosPublisherMicroPy.py:92
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.image_raw_pub
image_raw_pub
Definition: NiclaRosPublisherMicroPy.py:75
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.audio_stamped_msg
audio_stamped_msg
Definition: NiclaRosPublisherMicroPy.py:142
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.range_msg
range_msg
Definition: NiclaRosPublisherMicroPy.py:60
nicla_vision_ros.NiclaReceiverServerMicroPy.NiclaReceiverUDPMicroPy
Definition: NiclaReceiverServerMicroPy.py:81
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.stop
def stop(self)
Definition: NiclaRosPublisherMicroPy.py:334
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.audio_recognition_wave_output_filename
audio_recognition_wave_output_filename
Definition: NiclaRosPublisherMicroPy.py:52
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.image_compressed_pub
image_compressed_pub
Definition: NiclaRosPublisherMicroPy.py:86
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.nicla_receiver_server
nicla_receiver_server
Definition: NiclaRosPublisherMicroPy.py:170
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.speech_recognizer_pub
speech_recognizer_pub
Definition: NiclaRosPublisherMicroPy.py:209
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.enable_audio_stamped
enable_audio_stamped
Definition: NiclaRosPublisherMicroPy.py:37
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.enable_audio_recognition_vosk
enable_audio_recognition_vosk
Definition: NiclaRosPublisherMicroPy.py:40
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.enable_range
enable_range
Definition: NiclaRosPublisherMicroPy.py:31
nicla_vision_ros.NiclaRosPublisherMicroPy.NiclaRosPublisherMicroPy.__init__
None __init__(self)
Definition: NiclaRosPublisherMicroPy.py:19


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