Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[audio_video_recorder] Add audio_video_recorder_server and client library to audio_video_recorder #1704

Open
wants to merge 13 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 9 commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
29 changes: 28 additions & 1 deletion audio_video_recorder/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,13 +2,37 @@ cmake_minimum_required(VERSION 2.8.3)

project(audio_video_recorder)

find_package(catkin REQUIRED COMPONENTS roscpp audio_common_msgs sensor_msgs)
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
audio_common_msgs
message_generation
sensor_msgs
)

find_package(PkgConfig)
pkg_check_modules(GST1.0 gstreamer-1.0 REQUIRED)

find_package(Boost REQUIRED COMPONENTS thread)

catkin_python_setup()

add_message_files(
FILES
RecordTask.msg
RecordTaskArray.msg
)

add_service_files(
FILES
StartRecord.srv
StopRecord.srv
)

generate_messages(
DEPENDENCIES
)

catkin_package(
INCLUDE_DIRS include
CATKIN_DEPENDS
Expand All @@ -28,6 +52,9 @@ add_executable(audio_video_recorder src/audio_video_recorder.cpp)
target_link_libraries(audio_video_recorder ${catkin_LIBRARIES} ${GST1.0_LIBRARIES} ${Boost_LIBRARIES})
add_dependencies(audio_video_recorder ${catkin_EXPORTED_TARGETS})

catkin_install_python(PROGRAMS node_scripts/audio_video_recorder_server node_scripts/sample_audio_video_recorder_client.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})

install(TARGETS audio_video_recorder
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})

Expand Down
42 changes: 38 additions & 4 deletions audio_video_recorder/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -15,11 +15,25 @@ You can record audio and video on your laptop.
roslaunch audio_video_recorder sample_audio_video_recorder.launch
```

## Parameters
If you want to sedd ROS Interface Sample (Topic/Service) of audio_video_recorder, Please run audio_video_recorder_server demo.

```
roslaunch audio_video_recorder sample_audio_video_recorder_server.launch
```

And if you want to see an example of client script for audio_video_recorder_server. please see [sample_audio_video_recorder_client.py](./node_scripts/sample_audio_video_recorder_client.py).

## Nodes

### audio_video_recorder

Node to record audio and video with given parameters.

#### Parameters

Node: `audio_video_recorder/audio_video_recorder`

### Common parameters
##### Common parameters

- `queue_size` (`Int`, default: `100`)

Expand All @@ -33,7 +47,7 @@ Node: `audio_video_recorder/audio_video_recorder`

Output file format (Only `avi` is supported now.)

### Audio parameters
##### Audio parameters

- `audio_format` (`String`, default: `mp3`)

Expand All @@ -55,7 +69,7 @@ Node: `audio_video_recorder/audio_video_recorder`

Audio sample rate

### Video parameters
##### Video parameters

- `video_encoding` (`String`, default: `RGB`)

Expand All @@ -72,3 +86,23 @@ Node: `audio_video_recorder/audio_video_recorder`
- `video_framerate` (`Int`, default: `30`)

Video frame rate

### audio_video_recorder_server

ROS Interface and recording task manager for audio_video_recorder.

#### Services

- `~start_record` (`audio_video_recorder/StartRecord`)

Start a recording task

- `~stop_record` (`audio_video_recorder/StopRecord`)

Stop a specified recording task

#### Publisher

- `~record_tasks` (`audio_video_recorder/RecordTaskArray`)

Recording tasks currently running.
2 changes: 1 addition & 1 deletion audio_video_recorder/launch/audio_video_recorder.launch
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
<arg name="video_framerate" />
<arg name="video_encoding" />

<node name="audio_video_recorder" pkg="audio_video_recorder"
<node name="$(anon audio_video_recorder)" pkg="audio_video_recorder"
type="audio_video_recorder" output="screen">
<remap from="~input/audio" to="$(arg audio_topic_name)" />
<remap from="~input/image" to="$(arg image_topic_name)" />
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
<launch>
<node
pkg="audio_video_recorder"
type="audio_video_recorder_server"
name="audio_video_recorder_server"
/>
</launch>
14 changes: 14 additions & 0 deletions audio_video_recorder/msg/RecordTask.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
string audio_topic_name
string image_topic_name
int32 queue_size
string file_name # This will be used as key
string file_format
string audio_format
string audio_sample_format
int32 audio_channels
int32 audio_depth
int32 audio_sample_rate
string video_encoding
int32 video_height
int32 video_width
int32 video_framerate
1 change: 1 addition & 0 deletions audio_video_recorder/msg/RecordTaskArray.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
audio_video_recorder/RecordTask[] array
16 changes: 16 additions & 0 deletions audio_video_recorder/node_scripts/audio_video_recorder_server
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
#!/usr/bin/env python
# -*- encoding: utf-8 -*-

import rospy
from audio_video_recorder.audio_video_recorder_server import AudioVideoRecorderServer


def main():

rospy.init_node('audio_video_recorder_server')
server = AudioVideoRecorderServer()
server.spin()


if __name__=='__main__':
main()
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
#!/usr/bin/env python
# -*- encoding: utf-8 -*-

import rospy
from audio_video_recorder.audio_video_recorder_client import AudioVideoRecorderClient
from sensor_msgs.msg import Image
from audio_common_msgs.msg import AudioData


def main():

rospy.init_node('audio_video_recorder_client_demo')

destination = rospy.get_param('~destination','/tmp/')
file_name_01 = destination + 'audio_video_recorder_server_demo_01.avi'
file_name_02 = destination + 'audio_video_recorder_server_demo_02.avi'

try:
msg_image = rospy.wait_for_message('/usb_cam_node/image_raw', Image, timeout=rospy.Duration(10))
msg_audio = rospy.wait_for_message('/audio', AudioData, timeout=rospy.Duration(10))
except rospy.ROSException as e:
rospy.logerr(e)
return

client = AudioVideoRecorderClient()
rospy.loginfo('Start recording')
client.start_record('/audio','/usb_cam_node/image_raw',file_name_01,30)
rospy.sleep(5)
client.start_record('/audio','/usb_cam_node/image_raw',file_name_02,30)
rospy.sleep(5)
rospy.loginfo('Stop recording')
client.stop_record(file_name_01)
rospy.sleep(5)
client.stop_record(file_name_02)


if __name__ == '__main__':
main()
5 changes: 5 additions & 0 deletions audio_video_recorder/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,18 +12,23 @@
<buildtool_depend>catkin</buildtool_depend>

<build_depend>roscpp</build_depend>
<build_depend>rospy</build_depend>
<build_depend>audio_common_msgs</build_depend>
<build_depend>libgstreamer1.0-dev</build_depend>
<build_depend>libgstreamer-plugins-base1.0-dev</build_depend>
<build_depend>message_filters</build_depend>
<build_depend>message_generation</build_depend>
<build_depend>sensor_msgs</build_depend>

<exec_depend>roscpp</exec_depend>
<exec_depend>roslaunch</exec_depend>
<exec_depend>rospy</exec_depend>
<exec_depend>audio_common_msgs</exec_depend>
<exec_depend>gstreamer1.0</exec_depend>
<exec_depend>gstreamer1.0-plugins-base</exec_depend>
<exec_depend>gstreamer1.0-plugins-good</exec_depend>
<exec_depend>gstreamer1.0-plugins-ugly</exec_depend>
<exec_depend>message_filters</exec_depend>
<exec_depend>message_runtime</exec_depend>
<exec_depend>sensor_msgs</exec_depend>
</package>
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
<launch>
<node pkg="audio_capture" type="audio_capture" name="audio_capture" output="log">
<rosparam subst_value="true">
bitrate: 128
device: ""
channels: 1
sample_rate: 16000
format: mp3
sample_format: S16LE
</rosparam>
</node>

<node name="usb_cam_node" pkg="usb_cam" type="usb_cam_node" output="log">
<rosparam subst_value="true">
pixel_format: yuyv
image_height: 480
image_width: 640
framerate: 30
</rosparam>
</node>

<node
pkg="audio_video_recorder"
type="audio_video_recorder_server"
name="audio_video_recorder_server"
output="screen"
/>

<node
pkg="audio_video_recorder"
type="sample_audio_video_recorder_client.py"
name="sample_audio_video_recorder_client"
required="true"
output="screen"
/>

</launch>
10 changes: 10 additions & 0 deletions audio_video_recorder/setup.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
from distutils.core import setup
from catkin_pkg.python_setup import generate_distutils_setup

d = generate_distutils_setup(
packages=['audio_video_recorder'],
scripts=[],
package_dir={'': 'src'}
)

setup(**d)
Empty file.
Original file line number Diff line number Diff line change
@@ -0,0 +1,88 @@
# -*- encoding: utf-8 -*-

import rospy
import roslaunch

from sensor_msgs.msg import Image
from .msg import RecordTask, RecordTaskArray
from .srv import StartRecord, StartRecordRequest, StartRecordResponse
from .srv import StopRecord, StopRecordRequest, StopRecordResponse
sktometometo marked this conversation as resolved.
Show resolved Hide resolved

import threading


class AudioVideoRecorderClient:

def __init__(self):

self.record_task_array = RecordTaskArray()

self.client_start_record = rospy.ServiceProxy(
'/audio_video_recorder_server/start_record',
StartRecord)
self.client_stop_record = rospy.ServiceProxy(
'/audio_video_recorder_server/stop_record',
StopRecord)
self.sub_record_task_array = rospy.Subscriber(
'/audio_video_recorder_server/record_tasks',
RecordTaskArray,
self.__callback
)

def __callback(self, msg):
self.record_task_array = msg

def start_record(self,
audio_topic_name,
image_topic_name,
file_name,
video_framerate,
queue_size=100,
file_format='avi',
audio_format='mp3',
audio_sample_format='S16LE',
audio_channels=1,
audio_depth=16,
audio_sample_rate=16000,
video_encoding='RGB',
video_height=None,
video_width=None
):
# Get width and height from message
if video_height is None or video_width is None:
try:
msg_image = rospy.wait_for_message(image_topic_name,Image,timeout=rospy.Duration(5))
video_height = msg_image.height
video_width = msg_image.width
except rospy.ROSException as e:
return False, 'Image topic not published.'
#
req = StartRecordRequest()
req.task.audio_topic_name = audio_topic_name
req.task.image_topic_name = image_topic_name
req.task.queue_size = queue_size
req.task.file_name = file_name
req.task.file_format = file_format
req.task.audio_format = audio_format
req.task.audio_sample_format = audio_sample_format
req.task.audio_channels = audio_channels
req.task.audio_depth = audio_depth
req.task.audio_sample_rate = audio_sample_rate
req.task.video_encoding = video_encoding
req.task.video_height = video_height
req.task.video_width = video_width
req.task.video_framerate = video_framerate
#
res = self.client_start_record(req)
return res.success, res.message

def get_record_task_array(self):
return self.record_task_array

def stop_record(self, file_name):
#
req = StopRecordRequest()
req.file_name = file_name
#
res = self.client_stop_record(req)
return res.success, res.message
Loading