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
14 from nicla_vision_ros
import NiclaReceiverUDPMicroPy, NiclaReceiverTCPMicroPy
23 nicla_name = rospy.get_param(
"~nicla_name",
"nicla")
27 ip = rospy.get_param(
"~receiver_ip")
28 port = rospy.get_param(
"~receiver_port",
"8002")
29 connection_type = rospy.get_param(
"~connection_type",
"udp")
34 "~enable_camera_compressed",
False
38 "~enable_audio_stamped",
False
41 "~enable_audio_recognition_vosk",
False
44 "~audio_recognition_model_path",
""
47 "~audio_recognition_grammar",
""
50 "~audio_recognition_listen_seconds", 2
53 "~audio_recognition_wave_output_filename",
""
58 range_topic = nicla_name +
"/tof"
59 self.
range_pub = rospy.Publisher(range_topic, Range, queue_size=5)
61 self.
range_msg.header.frame_id = nicla_name +
"_tof"
62 self.
range_msg.radiation_type = Range.INFRARED
81 nicla_name +
"/camera/image_raw/compressed"
91 camera_info_topic = nicla_name +
"/camera/camera_info"
130 camera_info_topic, CameraInfo, queue_size=5
134 audio_topic = nicla_name +
"/audio"
137 audio_topic, AudioData, queue_size=10
141 audio_stamped_topic = nicla_name +
"/audio_stamped"
144 audio_stamped_topic, AudioDataStamped, queue_size=10
148 audio_info_topic = nicla_name +
"/audio_info"
156 audio_info_topic, AudioInfo, queue_size=1
160 imu_topic = nicla_name +
"/imu"
162 self.
imu_msg.header.frame_id = nicla_name +
"_imu"
167 self.
imu_pub = rospy.Publisher(imu_topic, Imu, queue_size=5)
169 if connection_type ==
"udp":
179 elif connection_type ==
"tcp":
191 rospy.logerr(
"Connection type ", connection_type,
" not known")
192 raise Exception(
"Connection type not known")
197 "Path for VOSK recognizer model is an empty string! Please provide 'audio_recognition_model_path' arg"
201 from nicla_vision_ros
import SpeechRecognizer
210 nicla_name +
"/audio_recognized", String, queue_size=10
221 self.
range_msg.header.stamp = rospy.Time.from_sec(range[0])
222 self.
range_msg.range = int.from_bytes(range[1],
"big") / 1000
239 rospy.Time.from_sec(image[0])
249 nparr = np.frombuffer(image[1], np.uint8)
252 img_raw = cv2.imdecode(
253 nparr, cv2.IMREAD_COLOR
273 img_raw, encoding=
"bgr8"
275 except CvBridgeError
as e:
316 self.
imu_msg.header.stamp = rospy.Time.from_sec(imu[0])
319 acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z = struct.unpack(
322 except Exception
as e:
323 rospy.logerr(
"imu pack has ", len(imu[1]),
" bytes")
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