diff --git a/audio_video_recorder/CMakeLists.txt b/audio_video_recorder/CMakeLists.txt
index 626236ba8..f2e2d2447 100644
--- a/audio_video_recorder/CMakeLists.txt
+++ b/audio_video_recorder/CMakeLists.txt
@@ -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
@@ -28,8 +52,11 @@ 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})
-install(DIRECTORY launch sample
+install(DIRECTORY launch sample euslisp
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
diff --git a/audio_video_recorder/README.md b/audio_video_recorder/README.md
index ab37e48b3..5b2b5a195 100644
--- a/audio_video_recorder/README.md
+++ b/audio_video_recorder/README.md
@@ -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`)
@@ -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`)
@@ -55,7 +69,7 @@ Node: `audio_video_recorder/audio_video_recorder`
Audio sample rate
-### Video parameters
+##### Video parameters
- `video_encoding` (`String`, default: `RGB`)
@@ -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.
diff --git a/audio_video_recorder/euslisp/audio-video-recorder-client.l b/audio_video_recorder/euslisp/audio-video-recorder-client.l
new file mode 100644
index 000000000..20fb33114
--- /dev/null
+++ b/audio_video_recorder/euslisp/audio-video-recorder-client.l
@@ -0,0 +1,76 @@
+(ros::load-ros-manifest "audio_video_recorder")
+(ros::load-ros-manifest "sensor_msgs")
+
+
+(defun call-start-record-service
+ (audio-topic-name
+ image-topic-name
+ file-name
+ video-framerate
+ &key
+ (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 nil)
+ (video-width nil))
+ (let (msg req res)
+ (if (or (not video-height) (not video-width))
+ (progn
+ (setq msg (one-shot-subscribe image-topic-name sensor_msgs::Image :timeout 5000))
+ (if (not msg)
+ (progn
+ (ros::ros-error "Image is not published from ~A" image-topic-name)
+ (return-from call-start-record-service nil)))
+ (setq video-height (send msg :height))
+ (setq video-width (send msg :width))))
+ (setq req (instance audio_video_recorder::StartRecordRequest :init))
+ (send req :task :audio_topic_name audio-topic-name)
+ (send req :task :image_topic_name image-topic-name)
+ (send req :task :queue_size queue-size)
+ (send req :task :file_name file-name)
+ (send req :task :file_format file-format)
+ (send req :task :audio_format audio-format)
+ (send req :task :audio_sample_format audio-sample-format)
+ (send req :task :audio_channels audio-channels)
+ (send req :task :audio_depth audio-depth)
+ (send req :task :audio_sample_rate audio-sample-rate)
+ (send req :task :video_encoding video-encoding)
+ (send req :task :video_height video-height)
+ (send req :task :video_width video-width)
+ (send req :task :video_framerate video-framerate)
+ (setq res (ros::service-call "/audio_video_recorder_server/start_record" req t))
+ (if (not (send res :success))
+ (progn
+ (ros::ros-error "Failed to start recording: ~A" (send res :message))
+ (return-from call-start-record-service nil)))
+ (send res :success)
+ ))
+
+(defun call-stop-record-service
+ (file-name)
+ (let (req res)
+ (setq req (instance audio_video_recorder::StopRecordRequest :init))
+ (send req :file_name file-name)
+ (setq res (ros::service-call "/audio_video_recorder_server/stop_record" req t))
+ (if (not (send res :success))
+ (progn
+ (ros::ros-error "Failed to stop recording: ~A" (send res :message))
+ (return-from call-stop-record-service nil)))
+ (send res :success)
+ ))
+
+(defun get-recording-task-array
+ ()
+ (let (msg)
+ (setq msg (one-shot-subscribe "/audio_video_recorder_server/record_tasks" audio_video_recorder::RecordTaskArray :timeout 10000))
+ (if (not msg)
+ (progn
+ (ros::ros-error "Failed to get a task array message.")
+ (return-from get-recording-task-array nil)))
+ (send msg :array)
+ ))
diff --git a/audio_video_recorder/euslisp/sample-audio-video-recorder-client.l b/audio_video_recorder/euslisp/sample-audio-video-recorder-client.l
new file mode 100755
index 000000000..23f35b957
--- /dev/null
+++ b/audio_video_recorder/euslisp/sample-audio-video-recorder-client.l
@@ -0,0 +1,38 @@
+#!/usr/bin/env roseus
+
+(ros::load-ros-manifest "sensor_msgs")
+(ros::load-ros-manifest "audio_common_msgs")
+
+(load "package://audio_video_recorder/euslisp/audio-video-recorder-client.l")
+
+(ros::roseus "audio_video_recorder_client_demo")
+
+(setq destination (ros::get-param "~destination" "/tmp/"))
+(setq file-name-01 (concatenate string destination "audio_video_recorder_server_demo_01.avi"))
+(setq file-name-02 (concatenate string destination "audio_video_recorder_server_demo_02.avi"))
+
+(setq msg-image (one-shot-subscribe "/usb_cam_node/image_raw" sensor_msgs::Image :timeout 10000))
+(setq msg-audio (one-shot-subscribe "/audio" audio_common_msgs::AudioData :timeout 10000))
+
+(if (or (not msg-image) (not msg-audio))
+ (progn
+ (ros::ros-error "Failed to get image or audio message")
+ (exit 1)))
+
+(ros::ros-info "Start a recording task")
+(call-start-record-service "/audio" "/usb_cam_node/image_raw" file-name-01 30)
+(unix::sleep 5)
+(ros::ros-info "Start another recording task")
+(call-start-record-service "/audio" "/usb_cam_node/image_raw" file-name-02 30)
+(unix::sleep 2)
+(ros::ros-info "Get a recording task array")
+(setq task-array (get-recording-task-array))
+(ros::ros-info " : ~A" task-array)
+(unix::sleep 3)
+(ros::ros-info "Stopped the first recording task.")
+(call-stop-record-service file-name-01)
+(unix::sleep 5)
+(ros::ros-info "Stopped the second recording task.")
+(call-stop-record-service file-name-02)
+
+(exit 0)
diff --git a/audio_video_recorder/launch/audio_video_recorder.launch b/audio_video_recorder/launch/audio_video_recorder.launch
index 24098b219..e135b0f32 100644
--- a/audio_video_recorder/launch/audio_video_recorder.launch
+++ b/audio_video_recorder/launch/audio_video_recorder.launch
@@ -13,7 +13,7 @@
-
diff --git a/audio_video_recorder/launch/audio_video_recorder_server.launch b/audio_video_recorder/launch/audio_video_recorder_server.launch
new file mode 100644
index 000000000..879055f46
--- /dev/null
+++ b/audio_video_recorder/launch/audio_video_recorder_server.launch
@@ -0,0 +1,7 @@
+
+
+
diff --git a/audio_video_recorder/msg/RecordTask.msg b/audio_video_recorder/msg/RecordTask.msg
new file mode 100644
index 000000000..05f22ac8e
--- /dev/null
+++ b/audio_video_recorder/msg/RecordTask.msg
@@ -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
diff --git a/audio_video_recorder/msg/RecordTaskArray.msg b/audio_video_recorder/msg/RecordTaskArray.msg
new file mode 100644
index 000000000..3124aa061
--- /dev/null
+++ b/audio_video_recorder/msg/RecordTaskArray.msg
@@ -0,0 +1 @@
+audio_video_recorder/RecordTask[] array
diff --git a/audio_video_recorder/node_scripts/audio_video_recorder_server b/audio_video_recorder/node_scripts/audio_video_recorder_server
new file mode 100755
index 000000000..d7ec3dcf6
--- /dev/null
+++ b/audio_video_recorder/node_scripts/audio_video_recorder_server
@@ -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()
diff --git a/audio_video_recorder/node_scripts/sample_audio_video_recorder_client.py b/audio_video_recorder/node_scripts/sample_audio_video_recorder_client.py
new file mode 100755
index 000000000..aab950ef7
--- /dev/null
+++ b/audio_video_recorder/node_scripts/sample_audio_video_recorder_client.py
@@ -0,0 +1,43 @@
+#!/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 a recording task')
+ client.start_record('/audio','/usb_cam_node/image_raw',file_name_01,30)
+ rospy.sleep(5)
+ rospy.loginfo('Start another recording task')
+ client.start_record('/audio','/usb_cam_node/image_raw',file_name_02,30)
+ rospy.sleep(2)
+ task_array = client.get_record_task_array()
+ rospy.loginfo('Get a recording task array : {}'.format(task_array))
+ rospy.sleep(3)
+ rospy.loginfo('Stop the first recording task')
+ client.stop_record(file_name_01)
+ rospy.sleep(5)
+ rospy.loginfo('Stop the second recording task')
+ client.stop_record(file_name_02)
+
+
+if __name__ == '__main__':
+ main()
diff --git a/audio_video_recorder/package.xml b/audio_video_recorder/package.xml
index ac5b7a282..06118f24b 100644
--- a/audio_video_recorder/package.xml
+++ b/audio_video_recorder/package.xml
@@ -12,18 +12,23 @@
catkin
roscpp
+ rospy
audio_common_msgs
libgstreamer1.0-dev
libgstreamer-plugins-base1.0-dev
message_filters
+ message_generation
sensor_msgs
roscpp
+ roslaunch
+ rospy
audio_common_msgs
gstreamer1.0
gstreamer1.0-plugins-base
gstreamer1.0-plugins-good
gstreamer1.0-plugins-ugly
message_filters
+ message_runtime
sensor_msgs
diff --git a/audio_video_recorder/sample/sample_audio_video_recorder_server.launch b/audio_video_recorder/sample/sample_audio_video_recorder_server.launch
new file mode 100644
index 000000000..ec28406db
--- /dev/null
+++ b/audio_video_recorder/sample/sample_audio_video_recorder_server.launch
@@ -0,0 +1,37 @@
+
+
+
+ bitrate: 128
+ device: ""
+ channels: 1
+ sample_rate: 16000
+ format: mp3
+ sample_format: S16LE
+
+
+
+
+
+ pixel_format: yuyv
+ image_height: 480
+ image_width: 640
+ framerate: 30
+
+
+
+
+
+
+
+
diff --git a/audio_video_recorder/sample/sample_audio_video_recorder_server_with_roseus.launch b/audio_video_recorder/sample/sample_audio_video_recorder_server_with_roseus.launch
new file mode 100644
index 000000000..4ab25ec44
--- /dev/null
+++ b/audio_video_recorder/sample/sample_audio_video_recorder_server_with_roseus.launch
@@ -0,0 +1,37 @@
+
+
+
+ bitrate: 128
+ device: ""
+ channels: 1
+ sample_rate: 16000
+ format: mp3
+ sample_format: S16LE
+
+
+
+
+
+ pixel_format: yuyv
+ image_height: 480
+ image_width: 640
+ framerate: 30
+
+
+
+
+
+
+
+
diff --git a/audio_video_recorder/setup.py b/audio_video_recorder/setup.py
new file mode 100644
index 000000000..52605f4d2
--- /dev/null
+++ b/audio_video_recorder/setup.py
@@ -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)
diff --git a/audio_video_recorder/src/audio_video_recorder/__init__.py b/audio_video_recorder/src/audio_video_recorder/__init__.py
new file mode 100644
index 000000000..e69de29bb
diff --git a/audio_video_recorder/src/audio_video_recorder/audio_video_recorder_client.py b/audio_video_recorder/src/audio_video_recorder/audio_video_recorder_client.py
new file mode 100644
index 000000000..a0dd48ccb
--- /dev/null
+++ b/audio_video_recorder/src/audio_video_recorder/audio_video_recorder_client.py
@@ -0,0 +1,88 @@
+# -*- encoding: utf-8 -*-
+
+import rospy
+import roslaunch
+
+from sensor_msgs.msg import Image
+from audio_video_recorder.msg import RecordTask, RecordTaskArray
+from audio_video_recorder.srv import StartRecord, StartRecordRequest, StartRecordResponse
+from audio_video_recorder.srv import StopRecord, StopRecordRequest, StopRecordResponse
+
+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
diff --git a/audio_video_recorder/src/audio_video_recorder/audio_video_recorder_server.py b/audio_video_recorder/src/audio_video_recorder/audio_video_recorder_server.py
new file mode 100644
index 000000000..e81b9b4f9
--- /dev/null
+++ b/audio_video_recorder/src/audio_video_recorder/audio_video_recorder_server.py
@@ -0,0 +1,124 @@
+# -*- encoding: utf-8 -*-
+
+import rospy
+import rospkg
+import roslaunch
+
+from audio_video_recorder.msg import RecordTask, RecordTaskArray
+from audio_video_recorder.srv import StartRecord, StartRecordRequest, StartRecordResponse
+from audio_video_recorder.srv import StopRecord, StopRecordRequest, StopRecordResponse
+
+import threading
+
+
+class AudioVideoRecorderServer:
+
+ def __init__(self):
+
+ self.pub_record_task_array = rospy.Publisher('~record_tasks', RecordTaskArray, queue_size=1)
+
+ self.list_record_task_and_launch = {}
+ self.lock_for_list = threading.Lock()
+
+ roslaunch.pmon._init_signal_handlers()
+
+ self.srv_start_record = rospy.Service('~start_record', StartRecord, self.handler_start_record)
+ self.srv_stop_record = rospy.Service('~stop_record', StopRecord, self.handler_stop_record)
+
+ def __publish_tasks(self):
+
+ self.lock_for_list.acquire()
+ msg = RecordTaskArray()
+ for key, item in self.list_record_task_and_launch.items():
+ msg.array.append(item['task'])
+ self.pub_record_task_array.publish(msg)
+ self.lock_for_list.release()
+
+ def __start_record(self, record_task):
+
+ if not isinstance(record_task, RecordTask):
+ return False, 'Argument is not an instance of RecordTask'
+ self.lock_for_list.acquire()
+ if record_task.file_name in self.list_record_task_and_launch:
+ self.lock_for_list.release()
+ return False, 'There is already a recording task with the same name.'
+ # start roslaunch
+ uuid = roslaunch.rlutil.get_or_generate_uuid(None, False)
+ roslaunch_path = rospkg.RosPack().get_path('audio_video_recorder') + '/launch/audio_video_recorder.launch'
+ roslaunch_args = [ \
+ 'audio_topic_name:={}'.format(record_task.audio_topic_name),
+ 'image_topic_name:={}'.format(record_task.image_topic_name),
+ 'queue_size:={}'.format(record_task.queue_size),
+ 'file_name:={}'.format(record_task.file_name),
+ 'file_format:={}'.format(record_task.file_format),
+ 'audio_format:={}'.format(record_task.audio_format),
+ 'audio_sample_format:={}'.format(record_task.audio_sample_format),
+ 'audio_channels:={}'.format(record_task.audio_channels),
+ 'audio_depth:={}'.format(record_task.audio_depth),
+ 'audio_sample_rate:={}'.format(record_task.audio_sample_rate),
+ 'video_encoding:={}'.format(record_task.video_encoding),
+ 'video_height:={}'.format(record_task.video_height),
+ 'video_width:={}'.format(record_task.video_width),
+ 'video_framerate:={}'.format(record_task.video_framerate)
+ ]
+ roslaunch_file = [(
+ roslaunch.rlutil.resolve_launch_arguments([roslaunch_path])[0],
+ roslaunch_args)]
+ roslaunch_parent = roslaunch.parent.ROSLaunchParent(
+ uuid,
+ roslaunch_file,
+ is_core=False
+ )
+ roslaunch_parent.start()
+ # Add task to list
+ self.list_record_task_and_launch[record_task.file_name] = {
+ 'task': record_task,
+ 'launch_handler': roslaunch_parent,
+ }
+
+ self.lock_for_list.release()
+ return True, 'Success'
+
+ def __stop_record(self, file_name):
+
+ if not isinstance(file_name, str):
+ return False, 'Argument is not an instance of str'
+ self.lock_for_list.acquire()
+ if file_name not in self.list_record_task_and_launch:
+ self.lock_for_list.release()
+ return False, 'There is no recording task with the specified name.'
+ self.list_record_task_and_launch[file_name]['launch_handler'].shutdown()
+ del self.list_record_task_and_launch[file_name]
+ self.lock_for_list.release()
+ return True, 'Success'
+
+ def handler_start_record(self, req):
+
+ success, message = self.__start_record(req.task)
+ if success:
+ rospy.loginfo('Start recoding to {}: {}'.format(req.task.file_name, message))
+ else:
+ rospy.logerr('Failed to start recoding to {}: {}'.format(req.task.file_name, message))
+ response = StartRecordResponse()
+ response.success = success
+ response.message = message
+ return response
+
+ def handler_stop_record(self, req):
+
+ success, message = self.__stop_record(req.file_name)
+ if success:
+ rospy.loginfo('Stop recoding to {}: {}'.format(req.file_name, message))
+ else:
+ rospy.logerr('Failed to stop recoding to {}: {}'.format(req.file_name, message))
+ response = StopRecordResponse()
+ response.success = success
+ response.message = message
+ return response
+
+ def spin(self):
+
+ rate = rospy.Rate(1)
+ while not rospy.is_shutdown():
+ rate.sleep()
+ self.__publish_tasks()
diff --git a/audio_video_recorder/srv/StartRecord.srv b/audio_video_recorder/srv/StartRecord.srv
new file mode 100644
index 000000000..b0cfd3fe3
--- /dev/null
+++ b/audio_video_recorder/srv/StartRecord.srv
@@ -0,0 +1,4 @@
+audio_video_recorder/RecordTask task
+---
+bool success
+string message
diff --git a/audio_video_recorder/srv/StopRecord.srv b/audio_video_recorder/srv/StopRecord.srv
new file mode 100644
index 000000000..2ad887544
--- /dev/null
+++ b/audio_video_recorder/srv/StopRecord.srv
@@ -0,0 +1,4 @@
+string file_name
+---
+bool success
+string message