@ -0,0 +1,220 @@ | |||
cmake_minimum_required(VERSION 3.0.2) | |||
project(vz_acoustic_scene_analysis) | |||
## Compile as C++11, supported in ROS Kinetic and newer | |||
# add_compile_options(-std=c++11) | |||
## Find catkin macros and libraries | |||
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) | |||
## is used, also find other catkin packages | |||
find_package(catkin REQUIRED COMPONENTS | |||
cv_bridge | |||
# opencv2 # ananya this does not compile | |||
roscpp | |||
rospy | |||
audio_common_msgs | |||
sensor_msgs | |||
std_msgs | |||
message_generation | |||
) | |||
find_package(PkgConfig) | |||
pkg_check_modules(GST1.0 gstreamer-1.0 REQUIRED) | |||
## System dependencies are found with CMake's conventions | |||
find_package(Boost REQUIRED COMPONENTS thread) | |||
## Uncomment this if the package has a setup.py. This macro ensures | |||
## modules and global scripts declared therein get installed | |||
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html | |||
# catkin_python_setup() | |||
################################################ | |||
## Declare ROS messages, services and actions ## | |||
################################################ | |||
## To declare and build messages, services or actions from within this | |||
## package, follow these steps: | |||
## * Let MSG_DEP_SET be the set of packages whose message types you use in | |||
## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). | |||
## * In the file package.xml: | |||
## * add a build_depend tag for "message_generation" | |||
## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET | |||
## * If MSG_DEP_SET isn't empty the following dependency has been pulled in | |||
## but can be declared for certainty nonetheless: | |||
## * add a exec_depend tag for "message_runtime" | |||
## * In this file (CMakeLists.txt): | |||
## * add "message_generation" and every package in MSG_DEP_SET to | |||
## find_package(catkin REQUIRED COMPONENTS ...) | |||
## * add "message_runtime" and every package in MSG_DEP_SET to | |||
## catkin_package(CATKIN_DEPENDS ...) | |||
## * uncomment the add_*_files sections below as needed | |||
## and list every .msg/.srv/.action file to be processed | |||
## * uncomment the generate_messages entry below | |||
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) | |||
## Generate messages in the 'msg' folder | |||
add_message_files( | |||
FILES | |||
MyAudioInfo.msg | |||
MyAudioData.msg | |||
) | |||
## Generate services in the 'srv' folder | |||
# add_service_files( | |||
# FILES | |||
# Service1.srv | |||
# Service2.srv | |||
# ) | |||
## Generate actions in the 'action' folder | |||
# add_action_files( | |||
# FILES | |||
# Action1.action | |||
# Action2.action | |||
# ) | |||
## Generate added messages and services with any dependencies listed here | |||
generate_messages( | |||
DEPENDENCIES | |||
std_msgs | |||
) | |||
################################################ | |||
## Declare ROS dynamic reconfigure parameters ## | |||
################################################ | |||
## To declare and build dynamic reconfigure parameters within this | |||
## package, follow these steps: | |||
## * In the file package.xml: | |||
## * add a build_depend and a exec_depend tag for "dynamic_reconfigure" | |||
## * In this file (CMakeLists.txt): | |||
## * add "dynamic_reconfigure" to | |||
## find_package(catkin REQUIRED COMPONENTS ...) | |||
## * uncomment the "generate_dynamic_reconfigure_options" section below | |||
## and list every .cfg file to be processed | |||
## Generate dynamic reconfigure parameters in the 'cfg' folder | |||
# generate_dynamic_reconfigure_options( | |||
# cfg/DynReconf1.cfg | |||
# cfg/DynReconf2.cfg | |||
# ) | |||
################################### | |||
## catkin specific configuration ## | |||
################################### | |||
## The catkin_package macro generates cmake config files for your package | |||
## Declare things to be passed to dependent projects | |||
## INCLUDE_DIRS: uncomment this if your package contains header files | |||
## LIBRARIES: libraries you create in this project that dependent projects also need | |||
## CATKIN_DEPENDS: catkin_packages dependent projects also need | |||
## DEPENDS: system dependencies of this project that dependent projects also need | |||
catkin_package( | |||
# INCLUDE_DIRS include | |||
# LIBRARIES vz_acoustic_scene_analysis | |||
CATKIN_DEPENDS roscpp rospy sensor_msgs std_msgs message_runtime | |||
# DEPENDS system_lib | |||
) | |||
########### | |||
## Build ## | |||
########### | |||
## Specify additional locations of header files | |||
## Your package locations should be listed before other locations | |||
include_directories( | |||
# include | |||
${catkin_INCLUDE_DIRS} | |||
${Boost_INCLUDE_DIRS} | |||
${GST1.0_INCLUDE_DIRS} | |||
) | |||
## Declare a C++ library | |||
# add_library(${PROJECT_NAME} | |||
# src/${PROJECT_NAME}/vz_ros_wrappers.cpp | |||
# ) | |||
## Add cmake target dependencies of the library | |||
## as an example, code may need to be generated before libraries | |||
## either from message generation or dynamic reconfigure | |||
# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) | |||
## Declare a C++ executable | |||
## With catkin_make all packages are built within a single CMake context | |||
## The recommended prefix ensures that target names across packages don't collide | |||
add_executable(audio_capture scripts/audio_capture.cpp) | |||
## Rename C++ executable without prefix | |||
## The above recommended prefix causes long target names, the following renames the | |||
## target back to the shorter version for ease of user use | |||
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" | |||
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") | |||
## Add cmake target dependencies of the executable | |||
## same as for the library above | |||
add_dependencies(audio_capture ${catkin_EXPORTED_TARGETS}) | |||
## Specify libraries to link a library or executable target against | |||
target_link_libraries(audio_capture | |||
${catkin_LIBRARIES} | |||
${GST1.0_LIBRARIES} | |||
${Boost_LIBRARIES} | |||
) | |||
############# | |||
## Install ## | |||
############# | |||
# all install targets should use catkin DESTINATION variables | |||
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html | |||
## Mark executable scripts (Python etc.) for installation | |||
## in contrast to setup.py, you can choose the destination | |||
# catkin_install_python(PROGRAMS | |||
# scripts/my_python_script | |||
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} | |||
# ) | |||
## Mark executables for installation | |||
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html | |||
install(TARGETS audio_capture | |||
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} | |||
) | |||
## Mark libraries for installation | |||
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html | |||
# install(TARGETS ${PROJECT_NAME} | |||
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} | |||
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} | |||
# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} | |||
# ) | |||
## Mark cpp header files for installation | |||
install(DIRECTORY launch | |||
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} | |||
# FILES_MATCHING PATTERN "*.h" | |||
# PATTERN ".svn" EXCLUDE | |||
) | |||
## Mark other files for installation (e.g. launch and bag files, etc.) | |||
# install(FILES | |||
# # myfile1 | |||
# # myfile2 | |||
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} | |||
# ) | |||
############# | |||
## Testing ## | |||
############# | |||
## Add gtest based cpp test target and link libraries | |||
# catkin_add_gtest(${PROJECT_NAME}-test test/test_vz_ros_wrappers.cpp) | |||
# if(TARGET ${PROJECT_NAME}-test) | |||
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) | |||
# endif() | |||
## Add folders to be run by python nosetests | |||
# catkin_add_nosetests(test) |
@ -0,0 +1 @@ | |||
uint16[] data |
@ -0,0 +1,85 @@ | |||
<?xml version="1.0"?> | |||
<package format="2"> | |||
<name>vz_acoustic_scene_analysis</name> | |||
<version>0.0.0</version> | |||
<description>The vz_acoustic_scene_analysis package</description> | |||
<!-- One maintainer tag required, multiple allowed, one person per tag --> | |||
<!-- Example: --> | |||
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> --> | |||
<maintainer email="ananya@todo.todo">ananya</maintainer> | |||
<!-- One license tag required, multiple allowed, one license per tag --> | |||
<!-- Commonly used license strings: --> | |||
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 --> | |||
<license>TODO</license> | |||
<!-- Url tags are optional, but multiple are allowed, one per tag --> | |||
<!-- Optional attribute type can be: website, bugtracker, or repository --> | |||
<!-- Example: --> | |||
<!-- <url type="website">http://wiki.ros.org/vz_acoustic_scene_analysis</url> --> | |||
<!-- Author tags are optional, multiple are allowed, one per tag --> | |||
<!-- Authors do not have to be maintainers, but could be --> | |||
<!-- Example: --> | |||
<!-- <author email="jane.doe@example.com">Jane Doe</author> --> | |||
<!-- The *depend tags are used to specify dependencies --> | |||
<!-- Dependencies can be catkin packages or system dependencies --> | |||
<!-- Examples: --> | |||
<!-- Use depend as a shortcut for packages that are both build and exec dependencies --> | |||
<!-- <depend>roscpp</depend> --> | |||
<!-- Note that this is equivalent to the following: --> | |||
<!-- <build_depend>roscpp</build_depend> --> | |||
<!-- <exec_depend>roscpp</exec_depend> --> | |||
<!-- Use build_depend for packages you need at compile time: --> | |||
<!-- <build_depend>message_generation</build_depend> --> | |||
<!-- Use build_export_depend for packages you need in order to build against this package: --> | |||
<!-- <build_export_depend>message_generation</build_export_depend> --> | |||
<!-- Use buildtool_depend for build tool packages: --> | |||
<!-- <buildtool_depend>catkin</buildtool_depend> --> | |||
<!-- Use exec_depend for packages you need at runtime: --> | |||
<!-- <exec_depend>message_runtime</exec_depend> --> | |||
<!-- Use test_depend for packages you need only for testing: --> | |||
<!-- <test_depend>gtest</test_depend> --> | |||
<!-- Use doc_depend for packages you need only for building documentation: --> | |||
<!-- <doc_depend>doxygen</doc_depend> --> | |||
<buildtool_depend>catkin</buildtool_depend> | |||
<build_depend>cv_bridge</build_depend> | |||
<!-- <build_depend>opencv2</build_depend> --> | |||
<build_depend>roscpp</build_depend> | |||
<build_depend>audio_common_msgs</build_depend> | |||
<build_depend>rospy</build_depend> | |||
<build_depend>sensor_msgs</build_depend> | |||
<build_depend>libgstreamer1.0-dev</build_depend> | |||
<build_depend>libgstreamer-plugins-base1.0-dev</build_depend> | |||
<build_depend>std_msgs</build_depend> | |||
<build_depend>message_generation</build_depend> | |||
<!-- <build_export_depend>opencv2</build_export_depend> --> | |||
<build_export_depend>roscpp</build_export_depend> | |||
<build_export_depend>rospy</build_export_depend> | |||
<build_export_depend>sensor_msgs</build_export_depend> | |||
<build_export_depend>std_msgs</build_export_depend> | |||
<!-- <exec_depend>opencv2</exec_depend> --> | |||
<exec_depend>roscpp</exec_depend> | |||
<exec_depend>rospy</exec_depend> | |||
<exec_depend>sensor_msgs</exec_depend> | |||
<exec_depend>std_msgs</exec_depend> | |||
<exec_depend>message_runtime</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> | |||
<!-- The export tag contains other, unspecified, tags --> | |||
<export> | |||
<!-- Other tools can request additional information be placed here --> | |||
</export> | |||
</package> |
@ -0,0 +1,85 @@ | |||
#! /usr/bin/python3 | |||
from sklearn.cluster import k_means | |||
import rospy | |||
import numpy as np | |||
from vz_acoustic_scene_analysis.msg import MyAudioData | |||
from std_msgs.msg import String | |||
from scipy.io.wavfile import write | |||
from collections import deque | |||
import time | |||
from pathlib import Path | |||
# Non ROS import | |||
# import acoustic_scene_analysis as asa | |||
class RosInterface: | |||
def __init__(self): | |||
home_dir = str(Path.home()) | |||
self.save_dir = home_dir + "/Music/" | |||
# 1) Write subscriber to /audio topic and populate a numpy data structure (array) with the uint8[] data | |||
# self.maxSize = 7 | |||
# self.queue = [None] * 7 | |||
# self.head = self.tail = -1 | |||
self.nparray = np.empty(1) | |||
self.arraylength = 0 | |||
self.msg_count = 0 | |||
rospy.Subscriber("/audio", MyAudioData, self.raw_callback) | |||
def enqueue(self,data): | |||
# if queue is full | |||
if ((self.tail+1) % self.k == self.head): | |||
# convert to mp3 | |||
# publish mp3 | |||
# remove the first element (call dequeue) | |||
pass | |||
elif (self.head == -1): | |||
self.head = 0 | |||
self.tail = 0 | |||
else: | |||
self.tail = (self.tail +1) % self.maxSize | |||
self.queue[self.tail] = data | |||
def dequeue(self): | |||
# if empty queue | |||
if (self.head == -1): | |||
pass | |||
# if the self | |||
else: | |||
temp = self.queue[self.head] | |||
def raw_callback(self, msg): | |||
# print("Length of uint8[]:", len(msg.data)) | |||
if (self.msg_count < 50): | |||
self.arraylength += len(msg.data) | |||
np.append(self.nparray,bytes) | |||
# print(len(bytes)) | |||
# else : | |||
# self.byteArray[self.msg_count] = bytes | |||
# print(len(bytes)) | |||
self.msg_count += 1 | |||
def on_shutdown(self): | |||
print(str(self.arraylength)) | |||
write(self.save_dir +'test.wav', self.arraylength, self.nparray) | |||
print("check music") | |||
pass | |||
# 2) Check you're "Decoding" the audio ROS message correctly by saving to a .wav file | |||
# 3) Be curious. Listen to the .wav file and see if it sounds gucci, and then maybe twiddle about with the encoding on the audio_capture.cpp, seeing if that changes anything e.g. encoding with mp3 instead. | |||
# 4) If you've made it this far, well done. Try find Utku's function to pass the np array. | |||
if __name__ == '__main__': | |||
try: | |||
rospy.init_node('ros_interface', anonymous=True) | |||
ros_int = RosInterface() | |||
rospy.on_shutdown(ros_int.on_shutdown) | |||
rospy.spin() | |||
except rospy.ROSInterruptException: | |||
print('Audio converter node failed!') | |||
pass |
@ -1,12 +0,0 @@ | |||
cmake_minimum_required(VERSION 2.8.3) | |||
project(audio_common_msgs) | |||
find_package(catkin REQUIRED COMPONENTS message_generation) | |||
add_message_files(DIRECTORY msg FILES | |||
AudioData.msg | |||
AudioInfo.msg | |||
) | |||
generate_messages() | |||
catkin_package(CATKIN_DEPENDS message_runtime) |
@ -1 +0,0 @@ | |||
uint8[] data |
@ -1,20 +0,0 @@ | |||
<package> | |||
<name>audio_common_msgs</name> | |||
<version>0.3.12</version> | |||
<description> | |||
Messages for transmitting audio via ROS | |||
</description> | |||
<maintainer email="namniart@gmail.com">Austin Hendrix</maintainer> | |||
<maintainer email="shingogo.5511@gmail.com">Shingo Kitagawa</maintainer> | |||
<author>Nate Koenig</author> | |||
<license>BSD</license> | |||
<url type="website">http://ros.org/wiki/audio_common_msgs</url> | |||
<url type="repository">https://github.com/ros-drivers/audio_common</url> | |||
<url type="bugtracker">https://github.com/ros-drivers/audio_common/issues</url> | |||
<buildtool_depend>catkin</buildtool_depend> | |||
<build_depend>message_generation</build_depend> | |||
<run_depend>message_runtime</run_depend> | |||
</package> |
@ -1,37 +0,0 @@ | |||
#! /usr/bin/python3 | |||
import rospy | |||
import numpy as np | |||
from audio_common_msgs.msg import AudioData | |||
from std_msgs.msg import String | |||
from scipy.io.wavfile import wavf | |||
class D435i: | |||
def __init__(self): | |||
# 1) Write subscriber to /audio topic and populate a numpy data structure (array) with the uint8[] data | |||
self.raw_audio_sub = rospy.Subscriber('/audio', AudioData, self.raw_callback) | |||
self.byteArray = np.array(1) | |||
self.msg_count = 0 | |||
def raw_callback(self, bytes): | |||
if (self.msg_count > 0): | |||
self.byteArray.append(bytes) | |||
else : | |||
self.byteArray() | |||
self.msg_count += 1 | |||
# 2) Check you're "Decoding" the audio ROS message correctly by saving to a .wav file | |||
# 3) Be curious. Listen to the .wav file and see if it sounds gucci, and then maybe twiddle about with the encoding on the audio_capture.cpp, seeing if that changes anything e.g. encoding with mp3 instead. | |||
# 4) If you've made it this far, well done. Try find Utku's function to pass the np array. | |||
def run(self): | |||
while not rospy.is_shutdown(): | |||
pass | |||
if __name__ == '__main__': | |||
try: | |||
rospy.init_node('audio_converter', anonymous=True) | |||
except rospy.ROSInterruptException: | |||
print('Audio converter node failed!') | |||
pass |