[DEV] forst step of audio interface of ROS node
This commit is contained in:
commit
f6e2b2f1a1
14
audio_bringup/CMakeLists.txt
Normal file
14
audio_bringup/CMakeLists.txt
Normal file
@ -0,0 +1,14 @@
|
||||
cmake_minimum_required(VERSION 2.8.3)
|
||||
project(audio_bringup)
|
||||
|
||||
## Find catkin macros and libraries
|
||||
find_package(catkin REQUIRED)
|
||||
|
||||
##Needed for ros packages
|
||||
catkin_package(CATKIN_DEPENDS rospy audio_core)
|
||||
|
||||
install(DIRECTORY launch
|
||||
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
|
||||
|
||||
install(DIRECTORY config
|
||||
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
|
28
audio_bringup/config/config_aldebaran_nao.json
Normal file
28
audio_bringup/config/config_aldebaran_nao.json
Normal file
@ -0,0 +1,28 @@
|
||||
{
|
||||
speaker:{
|
||||
io:'output',
|
||||
map-on:{
|
||||
interface:'auto',
|
||||
name:'default',
|
||||
timestamp-mode:'trigered',
|
||||
},
|
||||
#group:'groupSynchro',
|
||||
frequency:0,
|
||||
channel-map:['front-left', 'front-right'],
|
||||
type:'auto',
|
||||
nb-chunk:1024,
|
||||
},
|
||||
microphone:{
|
||||
io:'input',
|
||||
map-on:{
|
||||
interface:'auto',
|
||||
name:'default',
|
||||
timestamp-mode:'trigered',
|
||||
},
|
||||
#group:'groupSynchro',
|
||||
frequency:0,
|
||||
channel-map:['front-left', 'front-right', 'rear-left', 'rear-right'],
|
||||
type:'auto',
|
||||
nb-chunk:1024
|
||||
}
|
||||
}
|
26
audio_bringup/config/config_pc.json
Normal file
26
audio_bringup/config/config_pc.json
Normal file
@ -0,0 +1,26 @@
|
||||
{
|
||||
speaker:{
|
||||
io:'output',
|
||||
map-on:{
|
||||
interface:'auto',
|
||||
name:'default',
|
||||
timestamp-mode:'trigered',
|
||||
},
|
||||
frequency:0,
|
||||
channel-map:['front-left', 'front-right'],
|
||||
type:'auto',
|
||||
nb-chunk:1024,
|
||||
},
|
||||
microphone:{
|
||||
io:'input',
|
||||
map-on:{
|
||||
interface:'auto',
|
||||
name:'default',
|
||||
timestamp-mode:'trigered',
|
||||
},
|
||||
frequency:0,
|
||||
channel-map:['front-left', 'front-right'],
|
||||
type:'auto',
|
||||
nb-chunk:1024
|
||||
}
|
||||
}
|
5
audio_bringup/launch/bringup_aldebaran_nao.launch
Normal file
5
audio_bringup/launch/bringup_aldebaran_nao.launch
Normal file
@ -0,0 +1,5 @@
|
||||
<?xml version="1.0"?>
|
||||
<launch>
|
||||
<!-- Nao Diagnostics -->
|
||||
<node pkg="audio_core" type="audio_core_node" name="audio" args="--hardware=$(find audio_bringup)/config/config_aldebaran_nao.json"/>
|
||||
</launch>
|
4
audio_bringup/launch/bringup_pc.launch
Normal file
4
audio_bringup/launch/bringup_pc.launch
Normal file
@ -0,0 +1,4 @@
|
||||
<?xml version="1.0"?>
|
||||
<launch>
|
||||
<node pkg="audio_core" type="audio_core_node" name="audio" args="--hardware=$(find audio_bringup)/config/config_pc.json"/>
|
||||
</launch>
|
12
audio_bringup/package.xml
Normal file
12
audio_bringup/package.xml
Normal file
@ -0,0 +1,12 @@
|
||||
<package>
|
||||
<name>audio_bringup</name>
|
||||
<version>0.0.2</version>
|
||||
<description>Generic Audio bringup</description>
|
||||
<maintainer email="yui.heero@gmail.com">Edouard DUPIN</maintainer>
|
||||
<license>Apache-2.0</license>
|
||||
|
||||
<buildtool_depend>catkin</buildtool_depend>
|
||||
|
||||
<run_depend>rospy</run_depend>
|
||||
<run_depend>audio_core</run_depend>
|
||||
</package>
|
102
audio_core/CMakeLists.txt
Normal file
102
audio_core/CMakeLists.txt
Normal file
@ -0,0 +1,102 @@
|
||||
cmake_minimum_required(VERSION 2.8.3)
|
||||
project(audio_core)
|
||||
|
||||
set(CMAKE_VERBOSE_MAKEFILE ON)
|
||||
|
||||
## 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
|
||||
roscpp
|
||||
rospy
|
||||
std_msgs
|
||||
message_generation
|
||||
river
|
||||
)
|
||||
|
||||
################################################
|
||||
## 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 and a run_depend tag for each package in MSG_DEP_SET
|
||||
## * If MSG_DEP_SET isn't empty the following dependencies might have been
|
||||
## pulled in transitively but can be declared for certainty nonetheless:
|
||||
## * add a build_depend tag for "message_generation"
|
||||
## * add a run_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 services in the 'srv' folder
|
||||
add_service_files(
|
||||
FILES
|
||||
create.srv
|
||||
remove.srv
|
||||
write.srv
|
||||
getBufferTime.srv
|
||||
)
|
||||
|
||||
## Generate added messages and services with any dependencies listed here
|
||||
generate_messages(
|
||||
DEPENDENCIES
|
||||
std_msgs
|
||||
)
|
||||
|
||||
###################################
|
||||
## 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 you 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()
|
||||
|
||||
###########
|
||||
## Build ##
|
||||
###########
|
||||
|
||||
## Specify additional locations of header files
|
||||
## Your package locations should be listed before other locations
|
||||
include_directories(
|
||||
src/
|
||||
${catkin_INCLUDE_DIRS}
|
||||
)
|
||||
|
||||
## Declare a cpp executable
|
||||
add_executable(audio_core_node
|
||||
src/debug.cpp
|
||||
src/main.cpp
|
||||
)
|
||||
|
||||
set(CMAKE_CXX_FLAGS "-std=c++11 -DDEBUG_LEVEL=3 -DDEBUG=1 -D__CPP_VERSION__=2011")
|
||||
|
||||
## Add cmake target dependencies of the executable/library
|
||||
## as an example, message headers may need to be generated before nodes
|
||||
add_dependencies(${PROJECT_NAME}_node audio_core_generate_messages_cpp)
|
||||
|
||||
## Specify libraries to link a library or executable target against
|
||||
target_link_libraries(${PROJECT_NAME}_node
|
||||
${catkin_LIBRARIES}
|
||||
)
|
||||
|
||||
#############
|
||||
## Install ##
|
||||
#############
|
||||
|
||||
## Mark executables and/or libraries for installation
|
||||
install(TARGETS ${PROJECT_NAME}_node
|
||||
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
|
||||
)
|
0
audio_core/data/hardware.json
Normal file
0
audio_core/data/hardware.json
Normal file
32
audio_core/package.xml
Normal file
32
audio_core/package.xml
Normal file
@ -0,0 +1,32 @@
|
||||
<?xml version="1.0"?>
|
||||
<package>
|
||||
<name>audio_core</name>
|
||||
<version>0.0.1</version>
|
||||
<description>Generic Audio interface Input output (io is open all the time)</description>
|
||||
<maintainer email="yui.heero@gmail.com">Edouard DUPIN</maintainer>
|
||||
<license>Apache-2.0</license>
|
||||
|
||||
|
||||
<!-- The *_depend tags are used to specify dependencies -->
|
||||
<!-- Dependencies can be catkin packages or system dependencies -->
|
||||
<!-- Examples: -->
|
||||
<!-- Use build_depend for packages you need at compile time: -->
|
||||
<build_depend>message_generation</build_depend>
|
||||
<!-- Use buildtool_depend for build tool packages: -->
|
||||
<!-- <buildtool_depend>catkin</buildtool_depend> -->
|
||||
<!-- Use run_depend for packages you need at runtime: -->
|
||||
<run_depend>message_runtime</run_depend>
|
||||
<!-- Use test_depend for packages you need only for testing: -->
|
||||
<!-- <test_depend>gtest</test_depend> -->
|
||||
<buildtool_depend>catkin</buildtool_depend>
|
||||
<build_depend>roscpp</build_depend>
|
||||
<build_depend>rospy</build_depend>
|
||||
<build_depend>std_msgs</build_depend>
|
||||
<build_depend>audio_msg</build_depend>
|
||||
<build_depend>river</build_depend>
|
||||
<run_depend>roscpp</run_depend>
|
||||
<run_depend>rospy</run_depend>
|
||||
<run_depend>std_msgs</run_depend>
|
||||
<run_depend>audio_msg</run_depend>
|
||||
<run_depend>river</run_depend>
|
||||
</package>
|
15
audio_core/src/debug.cpp
Normal file
15
audio_core/src/debug.cpp
Normal file
@ -0,0 +1,15 @@
|
||||
/**
|
||||
* @author Edouard DUPIN
|
||||
*
|
||||
* @copyright 2010, Edouard DUPIN, all right reserved
|
||||
*
|
||||
* @license GPL v3 (see license file)
|
||||
*/
|
||||
|
||||
#include "debug.h"
|
||||
|
||||
int32_t appl::getLogId() {
|
||||
static int32_t g_val = etk::log::registerInstance("test");
|
||||
return g_val;
|
||||
}
|
||||
|
51
audio_core/src/debug.h
Normal file
51
audio_core/src/debug.h
Normal file
@ -0,0 +1,51 @@
|
||||
/**
|
||||
* @author Edouard DUPIN
|
||||
*
|
||||
* @copyright 2010, Edouard DUPIN, all right reserved
|
||||
*
|
||||
* @license GPL v3 (see license file)
|
||||
*/
|
||||
|
||||
#ifndef __APPL_DEBUG_H__
|
||||
#define __APPL_DEBUG_H__
|
||||
|
||||
#include <etk/log.h>
|
||||
|
||||
namespace appl {
|
||||
int32_t getLogId();
|
||||
};
|
||||
// TODO : Review this problem of multiple intanciation of "std::stringbuf sb"
|
||||
#define APPL_BASE(info,data) \
|
||||
do { \
|
||||
if (info <= etk::log::getLevel(appl::getLogId())) { \
|
||||
std::stringbuf sb; \
|
||||
std::ostream tmpStream(&sb); \
|
||||
tmpStream << data; \
|
||||
etk::log::logStream(appl::getLogId(), info, __LINE__, __class__, __func__, tmpStream); \
|
||||
} \
|
||||
} while(0)
|
||||
|
||||
#define APPL_CRITICAL(data) APPL_BASE(1, data)
|
||||
#define APPL_ERROR(data) APPL_BASE(2, data)
|
||||
#define APPL_WARNING(data) APPL_BASE(3, data)
|
||||
#ifdef DEBUG
|
||||
#define APPL_INFO(data) APPL_BASE(4, data)
|
||||
#define APPL_DEBUG(data) APPL_BASE(5, data)
|
||||
#define APPL_VERBOSE(data) APPL_BASE(6, data)
|
||||
#define APPL_TODO(data) APPL_BASE(4, "TODO : " << data)
|
||||
#else
|
||||
#define APPL_INFO(data) do { } while(false)
|
||||
#define APPL_DEBUG(data) do { } while(false)
|
||||
#define APPL_VERBOSE(data) do { } while(false)
|
||||
#define APPL_TODO(data) do { } while(false)
|
||||
#endif
|
||||
|
||||
#define APPL_ASSERT(cond,data) \
|
||||
do { \
|
||||
if (!(cond)) { \
|
||||
APPL_CRITICAL(data); \
|
||||
assert(!#cond); \
|
||||
} \
|
||||
} while (0)
|
||||
|
||||
#endif
|
417
audio_core/src/main.cpp
Normal file
417
audio_core/src/main.cpp
Normal file
@ -0,0 +1,417 @@
|
||||
|
||||
|
||||
#include <ros/ros.h>
|
||||
#include "audio_msg/AudioBuffer.h"
|
||||
#include "audio_core/create.h"
|
||||
#include "audio_core/remove.h"
|
||||
#include "audio_core/write.h"
|
||||
#include "audio_core/getBufferTime.h"
|
||||
#include <river/river.h>
|
||||
#include <river/Interface.h>
|
||||
#include <river/Manager.h>
|
||||
#include <boost/thread.hpp>
|
||||
#include <sstream>
|
||||
#include "debug.h"
|
||||
#include <etk/stdTools.h>
|
||||
|
||||
ros::Time startTime;
|
||||
/*
|
||||
static const double delayTimeBeforRemoveOutput = 30.0; // 30 second delay befor removing output that not create sound.
|
||||
|
||||
class IOPorperty {
|
||||
public:
|
||||
float frequencyIn;
|
||||
float frequencyOut;
|
||||
std::vector<uint8_t> inputChannelMap;
|
||||
std::vector<uint8_t> outputChannelMap;
|
||||
};
|
||||
IOPorperty audioProperties;
|
||||
|
||||
|
||||
class InterfacePorperty {
|
||||
public:
|
||||
int64_t uid;
|
||||
std::string descriptiveString;
|
||||
float frequency;
|
||||
std::vector<uint8_t> channelMap;
|
||||
std::vector<int16_t> data;
|
||||
double playTime;
|
||||
double requestTime;
|
||||
InterfacePorperty():
|
||||
uid(0),
|
||||
frequency(0),
|
||||
playTime(0),
|
||||
requestTime(0) {
|
||||
static int64_t suid = 25;
|
||||
uid = suid++;
|
||||
}
|
||||
};
|
||||
|
||||
std::vector<InterfacePorperty> listFlow;
|
||||
*/
|
||||
std11::mutex mutex;
|
||||
/*
|
||||
// RT audio input callback
|
||||
int inoutInput(void* _outputBuffer,
|
||||
void* _inputBuffer,
|
||||
unsigned int _nBufferFrames,
|
||||
double _streamTime,
|
||||
RtAudioStreamStatus _status,
|
||||
void* _data) {
|
||||
IOPorperty* audioProperty = (IOPorperty*)_data;
|
||||
// Since the number of input and output channels is equal, we can do
|
||||
// a simple buffer copy operation here.
|
||||
if (_status) {
|
||||
ROS_ERROR("Stream overflow detected.");
|
||||
}
|
||||
// check if someone suscribe to the output:
|
||||
if (stream_microphone.getNumSubscribers() > 0) {
|
||||
//ROS_INFO("Publish data ... %d frames time %lf", _nBufferFrames, _streamTime);
|
||||
audio_msg::AudioBuffer msg;
|
||||
// create the Ros timestamp
|
||||
msg.header.stamp = startTime + ros::Duration(_streamTime, (_streamTime-(int32_t)_streamTime)*1000000000.0);
|
||||
// set message frequency
|
||||
msg.frequency = audioProperty->frequencyIn;
|
||||
// set channel mas properties
|
||||
msg.channelMap = audioProperty->inputChannelMap;
|
||||
// copy data:
|
||||
msg.data.resize(_nBufferFrames*audioProperty->inputChannelMap.size());
|
||||
memcpy(&msg.data[0], _inputBuffer, _nBufferFrames*audioProperty->inputChannelMap.size()*sizeof(int16_t));
|
||||
// publish message
|
||||
stream_microphone.publish(msg);
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
// RT audio out callback
|
||||
int inoutOutput(void* _outputBuffer,
|
||||
void* _inputBuffer,
|
||||
unsigned int _nBufferFrames,
|
||||
double _streamTime,
|
||||
RtAudioStreamStatus _status,
|
||||
void* _data) {
|
||||
IOPorperty* audioProperty = (IOPorperty*)_data;
|
||||
// Since the number of input and output channels is equal, we can do
|
||||
// a simple buffer copy operation here.
|
||||
if (_status) {
|
||||
ROS_ERROR("Stream underflow detected.");
|
||||
}
|
||||
std::vector<int32_t> output;
|
||||
int32_t newsize = (int64_t)audioProperty->outputChannelMap.size()*(int64_t)_nBufferFrames;
|
||||
//ROS_INFO("read %d*%d=%d ", audioProperty->outputChannelMap.size(), _nBufferFrames, newsize);
|
||||
output.resize(newsize, 0);
|
||||
mutex.lock();
|
||||
std::vector<InterfacePorperty>::iterator it = listFlow.begin();
|
||||
while (it != listFlow.end()) {
|
||||
// copy data...
|
||||
size_t availlable = it->data.size();
|
||||
availlable = availlable<output.size()?availlable:output.size();
|
||||
if (availlable > 0) {
|
||||
for (size_t iii=0; iii<availlable; ++iii) {
|
||||
output[iii] += it->data[iii];
|
||||
}
|
||||
//ROS_INFO("write %ld (better have : %ld)", availlable, output.size());
|
||||
it->data.erase(it->data.begin(), it->data.begin()+availlable);
|
||||
it->playTime = _streamTime;
|
||||
} else {
|
||||
ROS_INFO("[%d] underflow %d", (int)it->uid, (int)output.size());
|
||||
if (it->playTime <= 0) {
|
||||
double delay = it->playTime + _streamTime;
|
||||
if (delay > delayTimeBeforRemoveOutput) {
|
||||
ROS_ERROR("[%d] underflow ==> too much : Remove interface (after %lf s)", (int)it->uid, delay);
|
||||
it = listFlow.erase(it);
|
||||
continue;
|
||||
}
|
||||
} else {
|
||||
it->playTime = -_streamTime;
|
||||
}
|
||||
}
|
||||
++it;
|
||||
}
|
||||
mutex.unlock();
|
||||
if (_outputBuffer == NULL) {
|
||||
ROS_ERROR("NULL output");
|
||||
return 0;
|
||||
}
|
||||
int16_t* outputPointer = (int16_t*)_outputBuffer;
|
||||
for (size_t iii=0; iii<output.size(); ++iii) {
|
||||
*outputPointer++ = output[iii]>32767?32767:(output[iii]<-32767?-32767:(int16_t)output[iii]);
|
||||
}
|
||||
// check if someone is connected
|
||||
if (stream_speaker.getNumSubscribers() > 0) {
|
||||
//ROS_INFO("Get data ... %d frames time %lf", _nBufferFrames, _streamTime);
|
||||
audio_msg::AudioBuffer msg;
|
||||
// Create the ROS message time
|
||||
msg.header.stamp = startTime + ros::Duration(_streamTime, (_streamTime-(int32_t)_streamTime)*1000000000.0);
|
||||
// set message frequency
|
||||
msg.frequency = audioProperty->frequencyOut;
|
||||
// set channel mas properties
|
||||
msg.channelMap = audioProperty->outputChannelMap;
|
||||
// copy data:
|
||||
msg.data.resize(_nBufferFrames*audioProperty->outputChannelMap.size());
|
||||
memcpy(&msg.data[0], _outputBuffer, _nBufferFrames*audioProperty->outputChannelMap.size()*sizeof(int16_t));
|
||||
// publish message
|
||||
stream_speaker.publish(msg);
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
*/
|
||||
|
||||
bool f_create(audio_core::create::Request &req,
|
||||
audio_core::create::Response &res) {
|
||||
/*
|
||||
InterfacePorperty newInterface;
|
||||
newInterface.descriptiveString = req.typeFlow;
|
||||
newInterface.frequency = req.frequency;
|
||||
newInterface.channelMap = req.channelMap;
|
||||
double requestTime = (double)req.stamp.sec + (double)req.stamp.nsec*0.0000000001;
|
||||
newInterface.requestTime = requestTime;
|
||||
newInterface.playTime = 0.0;
|
||||
res.handle = newInterface.uid;
|
||||
mutex.lock();
|
||||
listFlow.push_back(newInterface);
|
||||
mutex.unlock();
|
||||
ROS_INFO("create : [%d] type : %s", (int)res.handle, req.typeFlow.c_str());
|
||||
*/
|
||||
return true;
|
||||
}
|
||||
|
||||
bool f_remove(audio_core::remove::Request &req,
|
||||
audio_core::remove::Response &res) {
|
||||
/*
|
||||
mutex.lock();
|
||||
std::vector<InterfacePorperty>::iterator it = listFlow.begin();
|
||||
while (it != listFlow.end()) {
|
||||
if (it->uid == req.handle) {
|
||||
it = listFlow.erase(it);
|
||||
} else {
|
||||
++it;
|
||||
}
|
||||
}
|
||||
mutex.unlock();
|
||||
ROS_INFO("remove : [%d]", (int)req.handle);
|
||||
*/
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
bool f_write(audio_core::write::Request &req,
|
||||
audio_core::write::Response &res) {
|
||||
//ROS_INFO("write : [%ld] nbSample=%d", req.handle, (int32_t)req.data.size());
|
||||
/*
|
||||
mutex.lock();
|
||||
std::vector<InterfacePorperty>::iterator it = listFlow.begin();
|
||||
while (it != listFlow.end()) {
|
||||
if (it->uid == req.handle) {
|
||||
std::vector<int16_t> data = convert(it->channelMap, it->frequency, req.data, audioProperties.outputChannelMap, audioProperties.frequencyOut);
|
||||
size_t oldSize = it->data.size();
|
||||
it->data.resize(oldSize + data.size());
|
||||
memcpy(&it->data[oldSize], &data[0], data.size()*sizeof(int16_t));
|
||||
res.waitTime = (float)(it->data.size() / audioProperties.outputChannelMap.size()) / (float)audioProperties.frequencyOut * 1000000.0f;
|
||||
if (res.waitTime > 200000) {
|
||||
res.waitTime -= 200000;
|
||||
} else {
|
||||
res.waitTime = 0;
|
||||
}
|
||||
break;
|
||||
}
|
||||
++it;
|
||||
}
|
||||
mutex.unlock();
|
||||
*/
|
||||
return true;
|
||||
}
|
||||
|
||||
bool f_getBufferTime(audio_core::getBufferTime::Request &req,
|
||||
audio_core::getBufferTime::Response &res) {
|
||||
//ROS_INFO("get Time: [%ld]", req.handle, (int32_t)req.data.size());
|
||||
/*
|
||||
mutex.lock();
|
||||
std::vector<InterfacePorperty>::iterator it = listFlow.begin();
|
||||
while (it != listFlow.end()) {
|
||||
if (it->uid == req.handle) {
|
||||
res.time = (float)(it->data.size() / audioProperties.outputChannelMap.size()) / (float)audioProperties.frequencyOut * 1000000.0f;
|
||||
break;
|
||||
}
|
||||
++it;
|
||||
}
|
||||
mutex.unlock();
|
||||
*/
|
||||
return true;
|
||||
}
|
||||
/*
|
||||
output.push_back(audio_msg::AudioBuffer::CHANNEL_FRONT_LEFT);
|
||||
output.push_back(audio_msg::AudioBuffer::CHANNEL_FRONT_RIGHT);
|
||||
output.push_back(audio_msg::AudioBuffer::CHANNEL_REAR_LEFT);
|
||||
output.push_back(audio_msg::AudioBuffer::CHANNEL_REAR_RIGHT);
|
||||
output.push_back(audio_msg::AudioBuffer::CHANNEL_SURROUND_LEFT);
|
||||
output.push_back(audio_msg::AudioBuffer::CHANNEL_SURROUND_RIGHT);
|
||||
output.push_back(audio_msg::AudioBuffer::CHANNEL_LFE);
|
||||
output.push_back(audio_msg::AudioBuffer::CHANNEL_SUBWOOFER);
|
||||
*/
|
||||
|
||||
|
||||
|
||||
class InterfaceOutput {
|
||||
public:
|
||||
std::vector<audio::channel> m_channelMap;
|
||||
std11::shared_ptr<river::Manager> m_manager;
|
||||
std11::shared_ptr<river::Interface> m_interface;
|
||||
public:
|
||||
InterfaceOutput(std11::shared_ptr<river::Manager> _manager) :
|
||||
m_manager(_manager) {
|
||||
//Set stereo output:
|
||||
m_channelMap.push_back(audio::channel_frontLeft);
|
||||
m_channelMap.push_back(audio::channel_frontRight);
|
||||
m_interface = m_manager->createOutput(48000,
|
||||
m_channelMap,
|
||||
audio::format_int16,
|
||||
"speaker");
|
||||
if(m_interface == nullptr) {
|
||||
APPL_ERROR("nullptr interface");
|
||||
return;
|
||||
}
|
||||
m_interface->setReadwrite();
|
||||
}
|
||||
void start() {
|
||||
if(m_interface == nullptr) {
|
||||
APPL_ERROR("nullptr interface");
|
||||
return;
|
||||
}
|
||||
m_interface->start();
|
||||
}
|
||||
void stop() {
|
||||
//m_interface->write(&data[0], data.size()/m_channelMap.size());
|
||||
m_interface->stop();
|
||||
}
|
||||
};
|
||||
|
||||
|
||||
class InterfaceInput {
|
||||
public:
|
||||
std11::shared_ptr<river::Manager> m_manager;
|
||||
std11::shared_ptr<river::Interface> m_interface;
|
||||
ros::Publisher m_stream;
|
||||
std11::mutex mutex;
|
||||
public:
|
||||
InterfaceInput(std11::shared_ptr<river::Manager> _manager, const std::string& _input="microphone", const std::string& _publisher="microphone") :
|
||||
m_manager(_manager) {
|
||||
ros::NodeHandle nodeHandlePrivate("~");
|
||||
m_stream = nodeHandlePrivate.advertise<audio_msg::AudioBuffer>(_publisher, 100);
|
||||
//Set stereo output:
|
||||
std::vector<audio::channel> channelMap;
|
||||
channelMap.push_back(audio::channel_frontLeft);
|
||||
channelMap.push_back(audio::channel_frontRight);
|
||||
m_interface = m_manager->createInput(48000,
|
||||
channelMap,
|
||||
audio::format_int16,
|
||||
_input);
|
||||
if(m_interface == nullptr) {
|
||||
APPL_ERROR("nullptr interface");
|
||||
return;
|
||||
}
|
||||
// set callback mode ...
|
||||
m_interface->setInputCallback(std11::bind(&InterfaceInput::onDataReceived,
|
||||
this,
|
||||
std11::placeholders::_1,
|
||||
std11::placeholders::_2,
|
||||
std11::placeholders::_3,
|
||||
std11::placeholders::_4,
|
||||
std11::placeholders::_5,
|
||||
std11::placeholders::_6));
|
||||
m_interface->start();
|
||||
}
|
||||
~InterfaceInput() {
|
||||
if(m_interface == nullptr) {
|
||||
APPL_ERROR("nullptr interface");
|
||||
return;
|
||||
}
|
||||
m_interface->stop();
|
||||
m_interface.reset();
|
||||
}
|
||||
void onDataReceived(const void* _data,
|
||||
const std11::chrono::system_clock::time_point& _time,
|
||||
size_t _nbChunk,
|
||||
enum audio::format _format,
|
||||
uint32_t _frequency,
|
||||
const std::vector<audio::channel>& _map) {
|
||||
if (_format != audio::format_int16) {
|
||||
APPL_ERROR("call wrong type ... (need int16_t)");
|
||||
}
|
||||
// check if someone suscribe to the output:
|
||||
if (m_stream.getNumSubscribers() > 0) {
|
||||
//ROS_INFO("Publish data ... %d frames time %lf", _nBufferFrames, _streamTime);
|
||||
audio_msg::AudioBuffer msg;
|
||||
// create the Ros timestamp
|
||||
msg.header.stamp = ros::Time::now();//_time;
|
||||
// set message frequency
|
||||
msg.frequency = _frequency;
|
||||
// set channel mas properties
|
||||
//msg.channelMap = audioProperty->inputChannelMap;
|
||||
msg.channelMap.push_back(audio_msg::AudioBuffer::CHANNEL_FRONT_LEFT);
|
||||
msg.channelMap.push_back(audio_msg::AudioBuffer::CHANNEL_FRONT_RIGHT);
|
||||
// copy data:
|
||||
msg.data.resize(_nbChunk*_map.size());
|
||||
memcpy(&msg.data[0], _data, _nbChunk*_map.size()*sizeof(int16_t));
|
||||
// publish message
|
||||
m_stream.publish(msg);
|
||||
}
|
||||
}
|
||||
void start() {
|
||||
if(m_interface == nullptr) {
|
||||
APPL_ERROR("nullptr interface");
|
||||
return;
|
||||
}
|
||||
// wait 2 second ...
|
||||
usleep(20000000);
|
||||
m_interface->stop();
|
||||
}
|
||||
};
|
||||
|
||||
|
||||
|
||||
/**
|
||||
* This tutorial demonstrates simple sending of messages over the ROS system.
|
||||
*/
|
||||
int main(int _argc, char **_argv) {
|
||||
ros::init(_argc, _argv, "audio_interface");
|
||||
etk::log::setLevel(etk::log::logLevelVerbose);
|
||||
etk::initDefaultFolder(_argv[0]);
|
||||
etk::setArgZero(_argv[0]);
|
||||
for (int32_t iii=0; iii<_argc; ++iii) {
|
||||
APPL_ERROR("Argument : " << iii << " '" << _argv[iii] << "'");
|
||||
}
|
||||
std::string hardwareInterface="DATA:hardware.json";
|
||||
for (int32_t iii=0; iii<_argc; ++iii) {
|
||||
std::string arg = _argv[iii];
|
||||
if (etk::start_with(_argv[iii], "--hardware=") == true) {
|
||||
hardwareInterface = std::string(&_argv[iii][11]);
|
||||
APPL_INFO("Find hardware configuration ... : '" << hardwareInterface << "'");
|
||||
}
|
||||
}
|
||||
river::init(hardwareInterface);
|
||||
|
||||
ros::NodeHandle n;
|
||||
|
||||
ros::ServiceServer serviceCreate = n.advertiseService("create", f_create);
|
||||
ros::ServiceServer serviceRemove = n.advertiseService("remove", f_remove);
|
||||
ros::ServiceServer serviceWrite = n.advertiseService("write", f_write);
|
||||
ros::ServiceServer serviceGetBufferTime = n.advertiseService("getBufferTime", f_getBufferTime);
|
||||
|
||||
ros::NodeHandle nodeHandlePrivate("~");
|
||||
|
||||
std11::shared_ptr<river::Manager> m_manager = river::Manager::create("ROS node");
|
||||
|
||||
std11::shared_ptr<InterfaceInput> m_input = std11::make_shared<InterfaceInput>(m_manager, "microphone", "mic");
|
||||
|
||||
/*
|
||||
* A count of how many messages we have sent. This is used to create
|
||||
* a unique string for each message.
|
||||
*/
|
||||
ros::spin();
|
||||
m_input.reset();
|
||||
m_manager.reset();
|
||||
river::unInit();
|
||||
|
||||
return 0;
|
||||
}
|
2
audio_core/srv/activity.srv
Normal file
2
audio_core/srv/activity.srv
Normal file
@ -0,0 +1,2 @@
|
||||
bool activate
|
||||
---
|
10
audio_core/srv/create.srv
Normal file
10
audio_core/srv/create.srv
Normal file
@ -0,0 +1,10 @@
|
||||
# decriptive flow type
|
||||
string typeFlow
|
||||
# speaker timestamp playing request (0 to As soon as possible)
|
||||
time stamp
|
||||
# data frequency
|
||||
int32 frequency
|
||||
# channel order of the current buffer
|
||||
uint8[] channelMap
|
||||
---
|
||||
int64 handle
|
4
audio_core/srv/getBufferTime.srv
Normal file
4
audio_core/srv/getBufferTime.srv
Normal file
@ -0,0 +1,4 @@
|
||||
# audio interface UID
|
||||
int64 handle
|
||||
---
|
||||
uint32 time
|
3
audio_core/srv/read.srv
Normal file
3
audio_core/srv/read.srv
Normal file
@ -0,0 +1,3 @@
|
||||
int64 handle
|
||||
---
|
||||
int16[] data
|
2
audio_core/srv/remove.srv
Normal file
2
audio_core/srv/remove.srv
Normal file
@ -0,0 +1,2 @@
|
||||
int64 handle
|
||||
---
|
2
audio_core/srv/start.srv
Normal file
2
audio_core/srv/start.srv
Normal file
@ -0,0 +1,2 @@
|
||||
int64 handle
|
||||
---
|
2
audio_core/srv/stop.srv
Normal file
2
audio_core/srv/stop.srv
Normal file
@ -0,0 +1,2 @@
|
||||
int64 handle
|
||||
---
|
6
audio_core/srv/write.srv
Normal file
6
audio_core/srv/write.srv
Normal file
@ -0,0 +1,6 @@
|
||||
# audio interface UID
|
||||
int64 handle
|
||||
# interlaced data of the audio buffer
|
||||
int16[] data
|
||||
---
|
||||
uint32 waitTime
|
76
audio_msg/CMakeLists.txt
Normal file
76
audio_msg/CMakeLists.txt
Normal file
@ -0,0 +1,76 @@
|
||||
cmake_minimum_required(VERSION 2.8.3)
|
||||
project(audio_msg)
|
||||
|
||||
set(CMAKE_VERBOSE_MAKEFILE ON)
|
||||
|
||||
## 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
|
||||
roscpp
|
||||
rospy
|
||||
std_msgs
|
||||
message_generation
|
||||
)
|
||||
|
||||
|
||||
################################################
|
||||
## 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 and a run_depend tag for each package in MSG_DEP_SET
|
||||
## * If MSG_DEP_SET isn't empty the following dependencies might have been
|
||||
## pulled in transitively but can be declared for certainty nonetheless:
|
||||
## * add a build_depend tag for "message_generation"
|
||||
## * add a run_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
|
||||
AudioBuffer.msg
|
||||
)
|
||||
|
||||
## Generate added messages and services with any dependencies listed here
|
||||
generate_messages(
|
||||
DEPENDENCIES
|
||||
std_msgs
|
||||
)
|
||||
|
||||
###################################
|
||||
## 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 you 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(
|
||||
CATKIN_DEPENDS roscpp rospy std_msgs
|
||||
DEPENDS system_lib
|
||||
)
|
||||
|
||||
#############
|
||||
## Install ##
|
||||
#############
|
||||
|
||||
## Mark executables and/or libraries for installation
|
||||
install(TARGETS
|
||||
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
||||
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
||||
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
|
||||
)
|
19
audio_msg/msg/AudioBuffer.msg
Normal file
19
audio_msg/msg/AudioBuffer.msg
Normal file
@ -0,0 +1,19 @@
|
||||
# timestanp the audio buffer
|
||||
Header header
|
||||
# current frequency of the audio interface
|
||||
uint16 frequency
|
||||
# channel order properties :
|
||||
uint8 CHANNEL_FRONT_LEFT=0
|
||||
uint8 CHANNEL_FRONT_CENTER=1
|
||||
uint8 CHANNEL_FRONT_RIGHT=2
|
||||
uint8 CHANNEL_REAR_LEFT=3
|
||||
uint8 CHANNEL_REAR_CENTER=4
|
||||
uint8 CHANNEL_REAR_RIGHT=5
|
||||
uint8 CHANNEL_SURROUND_LEFT=6
|
||||
uint8 CHANNEL_SURROUND_RIGHT=7
|
||||
uint8 CHANNEL_SUBWOOFER=8
|
||||
uint8 CHANNEL_LFE=9
|
||||
# channel order of the current buffer
|
||||
uint8[] channelMap
|
||||
# interlaced data of the audio buffer
|
||||
int16[] data
|
22
audio_msg/package.xml
Normal file
22
audio_msg/package.xml
Normal file
@ -0,0 +1,22 @@
|
||||
<?xml version="1.0"?>
|
||||
<package>
|
||||
<name>audio_msg</name>
|
||||
<version>1.0.0</version>
|
||||
<description>Generic Audio messages</description>
|
||||
<maintainer email="yui.heero@gmail.com">Edouard DUPIN</maintainer>
|
||||
<license>Apache-2.0</license>
|
||||
|
||||
<build_depend>message_generation</build_depend>
|
||||
|
||||
<run_depend>message_runtime</run_depend>
|
||||
|
||||
<buildtool_depend>catkin</buildtool_depend>
|
||||
|
||||
<build_depend>roscpp</build_depend>
|
||||
<build_depend>rospy</build_depend>
|
||||
<build_depend>std_msgs</build_depend>
|
||||
|
||||
<run_depend>roscpp</run_depend>
|
||||
<run_depend>rospy</run_depend>
|
||||
<run_depend>std_msgs</run_depend>
|
||||
</package>
|
56
test/test_audio_recorder/CMakeLists.txt
Normal file
56
test/test_audio_recorder/CMakeLists.txt
Normal file
@ -0,0 +1,56 @@
|
||||
cmake_minimum_required(VERSION 2.8.3)
|
||||
project(test_audio_recorder)
|
||||
|
||||
set(CMAKE_VERBOSE_MAKEFILE ON)
|
||||
|
||||
## 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
|
||||
roscpp
|
||||
rospy
|
||||
std_msgs
|
||||
message_generation
|
||||
)
|
||||
|
||||
################################################
|
||||
## Declare ROS messages, services and actions ##
|
||||
################################################
|
||||
catkin_package()
|
||||
|
||||
###########
|
||||
## Build ##
|
||||
###########
|
||||
|
||||
## Specify additional locations of header files
|
||||
## Your package locations should be listed before other locations
|
||||
# include_directories(include)
|
||||
include_directories(
|
||||
${catkin_INCLUDE_DIRS}
|
||||
)
|
||||
|
||||
## Declare a cpp executable
|
||||
add_executable(${PROJECT_NAME}_node
|
||||
src/main.cpp
|
||||
)
|
||||
|
||||
target_link_libraries(${PROJECT_NAME}_node ${ALSA_LIBRARIES} pthread)
|
||||
|
||||
## Specify libraries to link a library or executable target against
|
||||
target_link_libraries(${PROJECT_NAME}_node
|
||||
${catkin_LIBRARIES}
|
||||
)
|
||||
|
||||
#############
|
||||
## Install ##
|
||||
#############
|
||||
|
||||
# all install targets should use catkin DESTINATION variables
|
||||
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
|
||||
|
||||
## Mark executables and/or libraries for installation
|
||||
install(TARGETS ${PROJECT_NAME}_node
|
||||
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
||||
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
||||
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
|
||||
)
|
22
test/test_audio_recorder/package.xml
Normal file
22
test/test_audio_recorder/package.xml
Normal file
@ -0,0 +1,22 @@
|
||||
<?xml version="1.0"?>
|
||||
<package>
|
||||
<name>test_audio_recorder</name>
|
||||
<version>0.0.1</version>
|
||||
<description>Generic Audio Recorder</description>
|
||||
<maintainer email="yui.heero@gmail.com">Edouard DUPIN</maintainer>
|
||||
<license>Apache-2.0</license>
|
||||
|
||||
<buildtool_depend>catkin</buildtool_depend>
|
||||
|
||||
<build_depend>message_generation</build_depend>
|
||||
<build_depend>roscpp</build_depend>
|
||||
<build_depend>std_msgs</build_depend>
|
||||
<build_depend>audio_msg</build_depend>
|
||||
|
||||
<run_depend>message_runtime</run_depend>
|
||||
<run_depend>roscpp</run_depend>
|
||||
<run_depend>std_msgs</run_depend>
|
||||
<run_depend>audio_core</run_depend>
|
||||
<run_depend>audio_msg</run_depend>
|
||||
|
||||
</package>
|
40
test/test_audio_recorder/src/main.cpp
Normal file
40
test/test_audio_recorder/src/main.cpp
Normal file
@ -0,0 +1,40 @@
|
||||
#include "ros/ros.h"
|
||||
#include "audio_msg/AudioBuffer.h"
|
||||
|
||||
#include <sstream>
|
||||
|
||||
FILE* filee = NULL;
|
||||
/**
|
||||
* This tutorial demonstrates simple receipt of messages over the ROS system.
|
||||
*/
|
||||
void audioCallback(const audio_msg::AudioBuffer::ConstPtr& msg) {
|
||||
fwrite(&msg->data[0] , sizeof(int16_t), msg->data.size(), filee);
|
||||
ROS_INFO_STREAM("get message: freq=" << msg->frequency << " nbChannel=" << msg->channelMap.size() << " nbSample=" << msg->data.size()/msg->channelMap.size());
|
||||
}
|
||||
|
||||
void usage() {
|
||||
ROS_INFO("test_audio_recorder usage [channel] [file]:");
|
||||
ROS_INFO(" [channel] Ros topic to get data");
|
||||
ROS_INFO(" [file] save file name (.raw only)");
|
||||
ROS_INFO("ex");
|
||||
ROS_INFO(" rosrun test_audio_recorder test_audio_recorder_node audio/microphone out.raw");
|
||||
exit (-1);
|
||||
}
|
||||
|
||||
int main(int argc, char **argv) {
|
||||
if (argc != 3 ) {
|
||||
ROS_ERROR ("not enought argument : %d", argc);
|
||||
usage();
|
||||
}
|
||||
std::string p_channelToRecord = argv[1];
|
||||
std::string p_fileToSave = argv[2];
|
||||
|
||||
filee = fopen(p_fileToSave.c_str(), "w");
|
||||
ros::init(argc, argv, "test_audio_recorder");
|
||||
ros::NodeHandle n;
|
||||
ros::Subscriber sub = n.subscribe(p_channelToRecord, 1000, audioCallback);
|
||||
ros::spin();
|
||||
fclose(filee);
|
||||
return 0;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user