# Copyright 2016 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
# Copyright 2022 robot-creation-diary.com
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
# 整数とテキストを送信するチュートリアルの内容から、ステレオカメラデータを取得し
# 変換・送信するように変更してある。
import rclpy
from rclpy.node import Node
from cpp_pubsub.msg import VideoMsg
#from cpp_pubsub.msg import VideoMsg
from hmdcontroller.CustomMjpeg import CustomMjpeg
import cv2
import time
import pyaudio
import numpy as np
# ステレオサウンドの設定
CHANNELS = 2
SAMPLE_RATE = 44100
SAMPLE_WIDTH = 2
CHUNK_SIZE = 8192 # バッファーサイズ(2の累乗)SAMPLE_RATE/fps より大きくすること
class MinimalPublisher(Node):
def __init__(self):
super().__init__('minimal_publisher')
print("init start")
self.publisher = self.create_publisher(VideoMsg, 'topic', 10)
# self.publisher_r = self.create_publisher(VideoMsg, 'video_r_topic', 10)
timer_period = 0.016 # seconds
# self.timer = self.create_timer(timer_period, self.timer_callback)
print("init 0")
self.st = time.time()
# カメラ関連
# 0はカメラを指定する番号。状況に応じて変更のこと
self.video_capture_l = CustomMjpeg(1,1280,720,30,640,360)
# 1はカメラを指定する番号。状況に応じて変更のこと
self.video_capture_r = CustomMjpeg(0,1280,720,30,640,360)
# self.video_capture_r.set(cv2.CAP_PROP_FRAME_WIDTH, 320) # 解像度指定
# self.video_capture_r.set(cv2.CAP_PROP_FRAME_HEIGHT, 240) # 解像度指定
p = pyaudio.PyAudio()
# 入力ストリームを開く
self.audio_input_stream = p.open(format=p.get_format_from_width(SAMPLE_WIDTH),
channels=CHANNELS,
rate=SAMPLE_RATE,
input=True,
frames_per_buffer=CHUNK_SIZE)
self.timer = self.create_timer(timer_period, self.timer_callback)
def __del__(self):
#self.video_capture_l.release()
#self.video_capture_r.release()
pass
def timer_callback(self):
# カメラ関連
frame_data_l = None
frame_data_r = None
while True:
#両方のバッファがなくなるまでループを回す
buf_frame_data_l = self.video_capture_l.get_jpeg_data()
buf_frame_data_r = self.video_capture_r.get_jpeg_data()
if None is not buf_frame_data_l:
frame_data_l = buf_frame_data_l
if None is not buf_frame_data_l:
frame_data_r = buf_frame_data_r
if None is buf_frame_data_l and\
None is buf_frame_data_r:
break
break
# ret, encoded_data_l = cv2.imencode(".jpg", frame_data_l,
# (cv2.IMWRITE_JPEG_QUALITY, 50))
# ret, encoded_data_r = cv2.imencode(".jpg", frame_data_r,
# (cv2.IMWRITE_JPEG_QUALITY, 50))
# バイナリデータを読み取る
# input_data = self.audio_input_stream.read(CHUNK_SIZE)
input_data = [0,0,0]
# バイト配列に変換する
#audio_bytes = np.frombuffer(input_data, dtype=np.int16)
if None is not frame_data_l and None is not frame_data_r:
# データ送信関連
msg = VideoMsg()
# msg_r = VideoMsg()
# # 送信用データの代入単純に=で代入しようとすると型が違うと怒られる
msg.img_data_l.frombytes(frame_data_l)
msg.img_data_r.frombytes(frame_data_r)
#
#msg.audio_data.frombytes(input_data)
self.publisher.publish(msg)
# self.publisher_r.publish(msg_r)
# # コンソールに何も表示されないと不安なのでデータの内容を表示
# self.get_logger().info('Publishing: %d %d'
# % (msg_l.img_data_l[0], msg_r.img_data_r[0]))
print("FPS", 1/(time.time() - self.st ), input_data[0],input_data[1])
self.st = time.time()
pass
else:
if None is not frame_data_l:
print("l", len(frame_data_l))
if None is not frame_data_r:
print("r", len(frame_data_r))
pass
# print("error")
def main(args=None):
rclpy.init(args=args)
minimal_publisher = MinimalPublisher()
rclpy.spin(minimal_publisher)
# Destroy the node explicitly
# (optional - otherwise it will be done automatically
# when the garbage collector destroys the node object)
minimal_publisher.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()