From 132b607af33cc6a479bbe437f0d48a69e93959e2 Mon Sep 17 00:00:00 2001 From: dk_snow Date: Thu, 14 Oct 2021 23:28:17 +0800 Subject: [PATCH] [Modify] some fixes & optimize memory & optimize online (#26) 1. fix some errors in cyberdog_audio 2. optimize memory using in cyberdog_audio while recording and playing 3. update audio online work mode Signed-off-by: northdk --- CHANGELOG.md | 10 +- .../include/audio_assistant/combiner.hpp | 6 + .../audio_assistant/src/ai_keyword.cpp | 19 +- .../src/ai_online/AivsMain.cpp | 127 ++++---- .../src/ai_online/StorageCapabilityImpl.cpp | 5 +- .../audio_assistant/src/combiner.cpp | 280 +++++++----------- .../include/audio_base/audio_player.hpp | 17 +- .../include/audio_base/audio_queue.hpp | 115 +++++++ .../audio_base/include/audio_base/mempool.hpp | 146 +++++++++ .../audio_base/src/audio_player.cpp | 79 +++-- .../include/audio_interaction/voice_cmd.hpp | 22 +- .../audio_interaction/src/voice_cmd.cpp | 60 +++- .../cyberdog_audio/CMakeLists.txt | 2 + .../cyberdog_audio/data/ai_mode.toml | 2 + .../include/audio_backtrace/back_trace.h | 4 +- 15 files changed, 579 insertions(+), 315 deletions(-) create mode 100644 cyberdog_interaction/cyberdog_audio/audio_base/include/audio_base/audio_queue.hpp create mode 100644 cyberdog_interaction/cyberdog_audio/audio_base/include/audio_base/mempool.hpp create mode 100644 cyberdog_interaction/cyberdog_audio/cyberdog_audio/data/ai_mode.toml diff --git a/CHANGELOG.md b/CHANGELOG.md index 691b7da..495c234 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -4,14 +4,16 @@ Xiaomi CyberDog's first release. -## 1.0.1 (2021-09-16) +### 1.0.0.1 (2021-09-16) Move the repositories to GitHub and replace the athena keyword with cyberdog in batches. -## 1.0.2 (2021-09-27) +### 1.0.0.2 (2021-09-27) Add grpc_vendor, lcm_vendor, mpg123_vendor, sdl2main_vendor, sdl2mixer_vendor and opencv_vendor to constrain the building environment. -## 1.0.3 (2021-10-14) +### 1.0.0.3 (2021-10-14) -Remove opencv_vendor, combine sdl2main_vendor & sdl2mixer_vendor into sdl2_vendor. Remove vision pkgs. +- Remove opencv_vendor, combine sdl2main_vendor & sdl2mixer_vendor into sdl2_vendor. Remove vision pkgs. +- Add behaviortreecppv3_vendor +- Optimize audio pkgs diff --git a/cyberdog_interaction/cyberdog_audio/audio_assistant/include/audio_assistant/combiner.hpp b/cyberdog_interaction/cyberdog_audio/audio_assistant/include/audio_assistant/combiner.hpp index bc0235e..d5f71b4 100644 --- a/cyberdog_interaction/cyberdog_audio/audio_assistant/include/audio_assistant/combiner.hpp +++ b/cyberdog_interaction/cyberdog_audio/audio_assistant/include/audio_assistant/combiner.hpp @@ -17,10 +17,13 @@ #include #include +#include #include "sys/stat.h" #include "sys/types.h" +#include "audio_base/audio_player.hpp" +#include "audio_base/audio_queue.hpp" #ifdef __cplusplus extern "C" @@ -30,6 +33,9 @@ extern "C" #ifdef __cplusplus } #endif // __cplusplus + +#define DELAY_TIMES 10 + extern bool player_end; void recorder_work_loop(void); diff --git a/cyberdog_interaction/cyberdog_audio/audio_assistant/src/ai_keyword.cpp b/cyberdog_interaction/cyberdog_audio/audio_assistant/src/ai_keyword.cpp index 0a5512c..bb36d0d 100644 --- a/cyberdog_interaction/cyberdog_audio/audio_assistant/src/ai_keyword.cpp +++ b/cyberdog_interaction/cyberdog_audio/audio_assistant/src/ai_keyword.cpp @@ -19,6 +19,7 @@ #include "rclcpp/rclcpp.hpp" #include "xiaoai_sdk/vpm/vpm_sdk.h" #include "audio_base/debug/ai_debugger.hpp" +#include "audio_base/audio_queue.hpp" #include "audio_assistant/mp3decoder.hpp" #define VPM_CONFIG_FILE_PATH "/opt/ros2/cyberdog/ai_conf/xaudio_engine.conf" @@ -36,10 +37,9 @@ typedef struct { unsigned char * start; unsigned int length; - std::mutex mutex; } vpm_input_buf_t; -extern vpm_input_buf_t vpm_input_buffer; +extern athena_audio::MsgQueue vpm_msg_queue; extern bool vpm_buf_ready; extern void ai_nativeasr_data_handler(asr_msg_type_t msg, unsigned char * buf, int buf_size); void ai_vpm_work_loop(); @@ -154,9 +154,9 @@ static void vpm_wakeup_data_handle( return; } + // close interrupt while audio playing // std::shared_ptr mp3decoder_ptr = mp3decoder::GetInstance(); - // if ( mp3decoder_ptr->tts_player_is_playing() == true ) - // { + // if ( mp3decoder_ptr->tts_player_is_playing() == true ) { // aivs_set_interrupt(); // tts_stream_flush(); // mp3decoder_ptr->tts_player_stop_now(); @@ -341,6 +341,7 @@ static int setParas(int type, int value) void ai_vpm_work_loop() { + fprintf(stdout, "vc: ai vp work loop on call\n"); for (;; ) { if (getAiWakeupRunStatus() == false) { printf("vc:vpm: getAiWakeupRunStatus shitch off\n"); @@ -352,12 +353,12 @@ void ai_vpm_work_loop() if (vpm_buf_ready == false) { continue; } - // will check here for open/close input to wakeup sdk - vpm_input_buffer.mutex.lock(); - input.raw = reinterpret_cast(vpm_input_buffer.start); - input.size = vpm_input_buffer.length; + + vpm_input_buf_t vpm_data; + vpm_msg_queue.DeQueue(vpm_data); + input.raw = reinterpret_cast(vpm_data.start); + input.size = vpm_data.length; vpm_process(&input); - vpm_input_buffer.mutex.unlock(); } /*release vpm*/ diff --git a/cyberdog_interaction/cyberdog_audio/audio_assistant/src/ai_online/AivsMain.cpp b/cyberdog_interaction/cyberdog_audio/audio_assistant/src/ai_online/AivsMain.cpp index e24e1b9..3832efd 100755 --- a/cyberdog_interaction/cyberdog_audio/audio_assistant/src/ai_online/AivsMain.cpp +++ b/cyberdog_interaction/cyberdog_audio/audio_assistant/src/ai_online/AivsMain.cpp @@ -50,6 +50,7 @@ #include "xiaoai_sdk/aivs/ClientLoggerHooker.h" #include "xiaoai_sdk/audio_config/config.h" #include "audio_assistant/audio_assitant.hpp" +#include "audio_base/audio_queue.hpp" #include "audio_assistant/mp3decoder.hpp" #include "xiaoai_sdk/aivs/RobotController.h" @@ -96,6 +97,13 @@ typedef struct tts_info tts_type_t type; unsigned char * address; unsigned int length; + void free_mem() + { + if (address != nullptr) { + fprintf(stdout, "vc: free ttsinfo memory\n"); + free(address); + } + } } tts_info_t; typedef struct tts_queue @@ -105,6 +113,8 @@ typedef struct tts_queue } tts_queue_t; static tts_queue_t mMsgQueueTts; +static athena_audio::MsgQueue TTSMsgQueue; + bool getAivsTtsRunStatus(void) { return mAivsTtsRunStatus; @@ -139,12 +149,7 @@ int tts_player_decode_paly(void); int tts_stream_flush(void) { - // will check here - std::cout << "vc: befor clear, queue.size " << mMsgQueueTts.queue.size() << std::endl; - mMsgQueueTts.mutex.lock(); // queue lock - mMsgQueueTts.queue.clear(); - mMsgQueueTts.mutex.unlock(); // queue unlock - std::cout << "vc: befor clear, queue.size " << mMsgQueueTts.queue.size() << std::endl; + TTSMsgQueue.Clear(); return 0; } @@ -159,47 +164,38 @@ int aivs_set_interrupt(void) return 0; } -int ai_push_msg_playback(tts_info_t ttsInfo) +int ai_push_msg_playback(const tts_info_t & ttsInfo) { - std::cout << "vc: enter ai_push_msg_playback()" << std::endl; - tts_info_t ttsInfoPlayback = {TTS_TYPE_INVALID, NULL, 0}; - tts_info_t ttsInfoPlayStart = {TTS_TYPE_INVALID, NULL, 0}; - tts_info_t ttsInfoPlayStop = {TTS_TYPE_INVALID, NULL, 0}; + std::cout << "vc: enter ai_push_msg_playback(), type: " << ttsInfo.type << std::endl; + tts_info_t ttsInfoPlay = {ttsInfo.type, NULL, ttsInfo.length}; switch (ttsInfo.type) { case TTS_TYPE_STREAM: std::cout << "vc: TTS_TYPE_STREAM Case !!" << std::endl; if (ttsInfo.address == NULL || ttsInfo.length == 0) { - std::cout << "vc: ai_push_msg_playback invalid paramter !!!" << std::endl; + std::cout << "vc: ai_push_msg_playback invalid paramter, stream addr is null !!!" << + std::endl; return -1; } else { - mMsgQueueTts.mutex.lock(); // queue lock - ttsInfoPlayback.type = ttsInfo.type; - ttsInfoPlayback.length = ttsInfo.length; - ttsInfoPlayback.address = (unsigned char *)malloc(ttsInfo.length); - if (ttsInfoPlayback.address != NULL) { - memcpy(ttsInfoPlayback.address, ttsInfo.address, ttsInfoPlayback.length); - mMsgQueueTts.queue.push_front(ttsInfoPlayback); + ttsInfoPlay.address = (unsigned char *)malloc(ttsInfo.length); + if (ttsInfoPlay.address != NULL) { + memcpy(ttsInfoPlay.address, ttsInfo.address, ttsInfoPlay.length); + TTSMsgQueue.EnQueue(ttsInfoPlay); + } else { + std::cout << "vc: ai_push_msg_playback failed, cannot allocate memory!" << std::endl; } - mMsgQueueTts.mutex.unlock(); // queue unlock } break; case TTS_TYPE_SYNC_START: std::cout << "vc: TTS_TYPE_SYNC_START Case !!" << std::endl; - mMsgQueueTts.mutex.lock(); // queue lock - ttsInfoPlayStart.type = ttsInfo.type; - mMsgQueueTts.queue.push_front(ttsInfoPlayStart); - mMsgQueueTts.mutex.unlock(); // queue unlock + TTSMsgQueue.EnQueue(ttsInfoPlay); break; case TTS_TYPE_SYNC_STOP: std::cout << "vc: TTS_TYPE_SYNC_STOP Case !!" << std::endl; - mMsgQueueTts.mutex.lock(); // queue lock - ttsInfoPlayStop.type = ttsInfo.type; - mMsgQueueTts.queue.push_front(ttsInfoPlayStop); - mMsgQueueTts.mutex.unlock(); // queue unlock + TTSMsgQueue.EnQueue(ttsInfoPlay); break; default: @@ -222,51 +218,46 @@ int aivsTtsHandler(void) continue; } - mMsgQueueTts.mutex.lock(); // queue lock - if (!mMsgQueueTts.queue.empty()) { - ttsInfoPlayback = mMsgQueueTts.queue.back(); - mMsgQueueTts.queue.pop_back(); - mMsgQueueTts.mutex.unlock(); // queue unlock - switch (ttsInfoPlayback.type) { - case TTS_TYPE_STREAM: - if (ttsInfoPlayback.address == NULL || ttsInfoPlayback.length == 0) { - usleep(1000 * 100); - continue; - } else { - std::cout << "vc: Process TTS_TYPE_STREAM " << std::endl; - cyberdog_audio::mp3decoder::GetInstance()->tts_player_accumulate( - ttsInfoPlayback.address, - ttsInfoPlayback.length); - free(ttsInfoPlayback.address); - } - break; + if (!TTSMsgQueue.DeQueue(ttsInfoPlayback)) { + std::cout << "vc: aivsTtsHandler get msg with empty, skip once!" << std::endl; + continue; + } - case TTS_TYPE_SYNC_START: - std::cout << "vc: Process TTS_TYPE_SYNC_START " << std::endl; - cyberdog_audio::mp3decoder::GetInstance()->tts_player_init(); - ai_push_msg(101); /*led control for start-dialog status*/ - break; + switch (ttsInfoPlayback.type) { + case TTS_TYPE_STREAM: + if (ttsInfoPlayback.address == NULL || ttsInfoPlayback.length == 0) { + usleep(1000 * 100); + continue; + } else { + std::cout << "vc: Process TTS_TYPE_STREAM " << std::endl; + cyberdog_audio::mp3decoder::GetInstance()->tts_player_accumulate( + ttsInfoPlayback.address, + ttsInfoPlayback.length); + free(ttsInfoPlayback.address); + } + break; - case TTS_TYPE_SYNC_STOP: - std::cout << "vc: Process TTS_TYPE_SYNC_STOP " << std::endl; + case TTS_TYPE_SYNC_START: + std::cout << "vc: Process TTS_TYPE_SYNC_START " << std::endl; + cyberdog_audio::mp3decoder::GetInstance()->tts_player_init(); + ai_push_msg(101); /*led control for start-dialog status*/ + break; - if (cyberdog_audio::mp3decoder::GetInstance() == nullptr) { - fprintf(stderr, "Process TTS_TYPE_SYNC_STOP Error with invalid pointer!\n"); - break; - } + case TTS_TYPE_SYNC_STOP: + std::cout << "vc: Process TTS_TYPE_SYNC_STOP " << std::endl; - cyberdog_audio::mp3decoder::GetInstance()->tts_player_decode_paly(); - // ai_push_msg(104);/*led control for end -dialog status*/ + if (cyberdog_audio::mp3decoder::GetInstance() == nullptr) { + fprintf(stderr, "Process TTS_TYPE_SYNC_STOP Error with invalid pointer!\n"); break; + } - default: - std::cout << "vc: Process default case !!" << std::endl; - break; - } - } else { - mMsgQueueTts.mutex.unlock(); // queue unlock - usleep(1000 * 100); - continue; + cyberdog_audio::mp3decoder::GetInstance()->tts_player_decode_paly(); + // ai_push_msg(104);/*led control for end -dialog status*/ + break; + + default: + std::cout << "vc: Process default case !!" << std::endl; + break; } } } @@ -778,6 +769,8 @@ void initAivsDeviceOAuth() clientInfo->setDeviceId(DEVICE_OAUTH_DEVICE_ID); auto config = getAudioConfig(); + config->putBoolean(aivs::AivsConfig::Auth::REQ_TOKEN_HYBRID, true); + config->putBoolean(aivs::AivsConfig::Auth::REQ_TOKEN_BY_SDK, true); gEngine = aivs::Engine::create(config, clientInfo, aivs::Engine::ENGINE_AUTH_DEVICE_OAUTH); } diff --git a/cyberdog_interaction/cyberdog_audio/audio_assistant/src/ai_online/StorageCapabilityImpl.cpp b/cyberdog_interaction/cyberdog_audio/audio_assistant/src/ai_online/StorageCapabilityImpl.cpp index 24bf9ac..727b8a8 100755 --- a/cyberdog_interaction/cyberdog_audio/audio_assistant/src/ai_online/StorageCapabilityImpl.cpp +++ b/cyberdog_interaction/cyberdog_audio/audio_assistant/src/ai_online/StorageCapabilityImpl.cpp @@ -23,11 +23,12 @@ StorageCapabilityImpl::StorageCapabilityImpl() { -#ifndef __NuttX__ +/* #ifndef __NuttX__ storageFilePath = "data.json"; #else storageFilePath = "/tmp/data.json"; -#endif +#endif */ + storageFilePath = "/opt/ros2/cyberdog/data/token.json"; loadKeyValuesFromFile(); } diff --git a/cyberdog_interaction/cyberdog_audio/audio_assistant/src/combiner.cpp b/cyberdog_interaction/cyberdog_audio/audio_assistant/src/combiner.cpp index d699d42..77d2e68 100644 --- a/cyberdog_interaction/cyberdog_audio/audio_assistant/src/combiner.cpp +++ b/cyberdog_interaction/cyberdog_audio/audio_assistant/src/combiner.cpp @@ -14,6 +14,7 @@ #include #include +#include #include #include @@ -23,14 +24,18 @@ #include "audio_assistant/combiner.hpp" #include "audio_base/capture.hpp" #include "audio_base/debug/ai_debugger.hpp" - -static bool mCaptureRunStatus = true; -bool player_end; +#include "audio_base/mempool.hpp" // vpm #define AI_RECORD_DEBUG -void ai_rawdata_handle(char * buf, int buf_size); -bool getMainCaptureRunStatus(void); +static bool mCaptureRunStatus = true; +bool vpm_buf_ready = false; +bool record_on_status = true; +bool player_end; +extern bool audiodata_silence_mode; +bool sound_ready = false; +bool ref_ready = false; +bool gNeedRunning = false; // for debug static int raw_dump_fd = -1; @@ -40,125 +45,61 @@ typedef struct { unsigned char * start; unsigned int length; - std::mutex mutex; + void free_mem() {} } vpm_input_buf_t; vpm_input_buf_t vpm_input_buffer; -bool vpm_buf_ready = false; -bool record_on_status = true; - -static unsigned char buffer[2 * 7 * 320 + 14 * 2]; - -std::condition_variable cond_sound; -std::condition_variable cond_ref; -std::mutex mutex_sound; -std::mutex mutex_ref; -bool sound_ready = false; -bool ref_ready = false; -bool gNeedRunning = false; -extern bool audiodata_silence_mode; -typedef struct -{ - snd_pcm_t * handle; - char * buf_1; - char * buf_2; - snd_pcm_uframes_t frames; - int size; -} pcm_params_t; +athena_audio::MsgQueue vpm_msg_queue; +std::shared_ptr vpm_mp = + std::make_shared(128, 2 * 7 * 320); -void * pcm_read_sound(pcm_params_t params) +bool getMainCaptureRunStatus(void) { - pcm_params_t pcm_params = params; - snd_pcm_t * hdl = pcm_params.handle; - char * buffer_1 = pcm_params.buf_1; - char * buffer_2 = pcm_params.buf_2; - int frames = pcm_params.frames; - int size = pcm_params.size; - printf("vc:combiner: %s enter\n", __func__); - while (gNeedRunning) { - // if (getMainCaptureRunStatus() == false) { - // usleep(1000 * 50); - // continue; - // } - snd_pcm_readi(hdl, buffer_1, frames); - memcpy(buffer_2, buffer_1, size); - sound_ready = true; - cond_sound.notify_one(); - } - printf("vc:combiner: %s exit\n", __func__); - return nullptr; + return mCaptureRunStatus; } -void * pcm_read_ref(pcm_params_t params) +int setMainCaptureRunStatus(bool on) { - pcm_params_t pcm_params = params; - snd_pcm_t * hdl = pcm_params.handle; - char * buffer_1 = pcm_params.buf_1; - char * buffer_2 = pcm_params.buf_2; - int frames = pcm_params.frames; - int size = pcm_params.size; - printf("vc:combiner: %s enter\n", __func__); - while (gNeedRunning) { - // if (getMainCaptureRunStatus() == false) { - // usleep(1000 * 50); - // continue; - // } - snd_pcm_readi(hdl, buffer_1, frames); - memcpy(buffer_2, buffer_1, size); - - ref_ready = true; - cond_ref.notify_one(); - } - printf("vc:combiner: %s exit\n", __func__); - return nullptr; + mCaptureRunStatus = on; + return 0; } void ai_rawdata_handle(unsigned char * buf, int buf_size) { - if (vpm_input_buffer.mutex.try_lock()) { - memcpy(vpm_input_buffer.start, buf, buf_size); - vpm_input_buffer.mutex.unlock(); + if (audiodata_silence_mode) { + if (!vpm_msg_queue.Empty()) { + vpm_msg_queue.Clear(); + } + } else { + vpm_input_buf_t vpm_data; + vpm_data.length = buf_size; + vpm_mp->GetMemory(&vpm_data.start); + memcpy(vpm_data.start, buf, vpm_data.length); + vpm_msg_queue.EnQueueOne(vpm_data); } } -void setup_vpm_input_buffer(void) +bool setup_vpm_input_buffer(void) { - memset(buffer, 0x0, 2 * 7 * 320); - vpm_input_buffer.start = buffer; - vpm_input_buffer.length = 2 * 7 * 320; + if (!vpm_mp->Create(true)) { + fprintf(stderr, "vc: create vpm buffer failed!\n"); + return false; + } vpm_buf_ready = true; -} - -bool getMainCaptureRunStatus(void) -{ - return mCaptureRunStatus; -} - -int setMainCaptureRunStatus(bool on) -{ - mCaptureRunStatus = on; - return 0; + return true; } void recorder_work_loop() { player_end = true; unsigned char * buffer_mix; - unsigned char * buffer_output; - int output_size; - int output_pos = 0; - int output_left; - snd_pcm_t * handle_ref; snd_pcm_t * handle_sound; - char dev_ref[] = "hw:1,0"; char dev_snd[] = "hw:1,1"; - int dir_ref, dir_sound; - unsigned int val_ref, val_sound; - snd_pcm_uframes_t frames_ref = 320; + int dir_sound; + unsigned int val_sound; snd_pcm_uframes_t frames_sound = 320; - snd_pcm_hw_params_t * params_ref; snd_pcm_hw_params_t * params_sound; int chk_index = 0; int rc; @@ -177,32 +118,7 @@ void recorder_work_loop() setup_vpm_input_buffer(); printf("vc:combiner: open refernce data device \n"); - - while ((rc = snd_pcm_open(&handle_ref, dev_ref, SND_PCM_STREAM_CAPTURE, 0)) < 0) { - printf("vc:combiner: unable to open pcm device: %s/n", snd_strerror(rc)); - sleep(1); - } - - printf("vc:combiner: open pcm device: %s successful/n", snd_strerror(rc)); - snd_pcm_hw_params_alloca(¶ms_ref); - snd_pcm_hw_params_any(handle_ref, params_ref); - snd_pcm_hw_params_set_access( - handle_ref, params_ref, - SND_PCM_ACCESS_RW_INTERLEAVED); - snd_pcm_hw_params_set_format( - handle_ref, params_ref, - SND_PCM_FORMAT_S16_LE); - snd_pcm_hw_params_set_channels(handle_ref, params_ref, 1); - val_ref = RATE; - snd_pcm_hw_params_set_rate_near(handle_ref, params_ref, &val_ref, &dir_ref); - snd_pcm_hw_params_set_period_size_near(handle_ref, params_ref, &frames_ref, &dir_ref); - rc = snd_pcm_hw_params(handle_ref, params_ref); - snd_pcm_hw_params_get_period_time(params_ref, &val_ref, &dir_ref); - snd_pcm_hw_params_get_period_size(params_ref, &frames_ref, &dir_ref); - if (rc < 0) { - printf("vc:combiner: unable to set hw parameters: %s/n", snd_strerror(rc)); - exit(1); - } + auto recorder_ = std::make_shared(3); printf("vc:combiner: open mic data device \n"); rc = snd_pcm_open( @@ -238,46 +154,72 @@ void recorder_work_loop() int buffer_size_sound = 2 * 6 * frames_sound; int buffer_size_ref = 2 * 1 * frames_sound; int buffer_size_mix = 2 * 7 * frames_sound; - output_size = buffer_size_mix * 5; - output_left = output_size; - - buffer_mix = (unsigned char *)malloc(buffer_size_mix); - buffer_output = (unsigned char *)malloc(output_size); - char * buffer_sound_1 = reinterpret_cast(malloc(buffer_size_sound)); - char * buffer_sound_2 = reinterpret_cast(malloc(buffer_size_sound)); - char * buffer_ref_1 = reinterpret_cast(malloc(buffer_size_ref)); - char * buffer_ref_2 = reinterpret_cast(malloc(buffer_size_ref)); - pcm_params_t pcm_params_sound = - {handle_sound, buffer_sound_1, buffer_sound_2, frames_sound, buffer_size_sound}; - pcm_params_t pcm_params_ref = - {handle_ref, buffer_ref_1, buffer_ref_2, frames_ref, buffer_size_ref}; + std::shared_ptr mp = std::make_shared( + DELAY_TIMES * 10, + buffer_size_sound); + if (!mp->Create()) { + fprintf(stderr, "vc: combiner cannot allocate memory pool!\n"); + return; + } - printf("vc:combiner: sound/ref thread create \n"); - gNeedRunning = true; - std::thread record_ref(pcm_read_ref, pcm_params_ref); - usleep(5000); - std::thread record_sound(pcm_read_sound, pcm_params_sound); + char * buffer_sound; + bool reference_start = false; + bool combiner_start = false; + char * buffer_ref = reinterpret_cast(malloc(buffer_size_ref)); + buffer_mix = (unsigned char *)malloc(buffer_size_mix); + std::queue sound_queue = std::queue(); - printf("vc:combiner: before mix sound/ref data \n"); + fprintf(stdout, "vc:combiner: before mix sound/ref data \n"); for (;; ) { - std::unique_lock lock_sound(mutex_sound); + // if (audiodata_silence_mode) { + // usleep(5000 * 100); + // continue; + // } + if (reference_start == false) { + reference_start = true; + recorder_->OpenReference(buffer_size_ref); + } + while (true) { + if (recorder_->HaveReferenceData() == false) { + usleep(1000); + continue; + } + recorder_->GetReferenceData(buffer_ref); + break; + } - if (audiodata_silence_mode || !player_end) { - usleep(5000 * 100); + // sound_queue.push(reinterpret_cast(malloc(buffer_size_sound))); + char * src; + int mp_flag = mp->GetMemory(&src); + sound_queue.push(src); + while (true) { + rc = snd_pcm_readi(handle_sound, sound_queue.back(), frames_sound); + if (rc == -EAGAIN) { + usleep(1000); + continue; + } else if (rc == -EPIPE) { + std::cout << "vc:combiner:[sound]Overrun occured\n"; + snd_pcm_prepare(handle_sound); + continue; + } else if (rc < 0) { + std::cout << "vc:combiner:[sound]Read Error: " << snd_strerror(rc) << "\n"; + } + break; + } + if (combiner_start == false) { + if (static_cast(sound_queue.size()) == DELAY_TIMES) { + combiner_start = true; + } continue; + } else { + buffer_sound = sound_queue.front(); + sound_queue.pop(); } - cond_sound.wait(lock_sound, [] {return sound_ready;}); - sound_ready = false; - - std::unique_lock lock_ref(mutex_ref); - cond_ref.wait(lock_ref, [] {return ref_ready;}); - ref_ready = false; - for (uint32_t i = 0; i < frames_sound; i++) { - memcpy(buffer_mix + 14 * i, buffer_sound_2 + 12 * i, 12); - memcpy(buffer_mix + 14 * i + 12, buffer_ref_2 + 2 * i, 2); + memcpy(buffer_mix + 14 * i, buffer_sound + 12 * i, 12); + memcpy(buffer_mix + 14 * i + 12, buffer_ref + 2 * i, 2); } if (chk_index % 100 == 0) { @@ -295,31 +237,17 @@ void recorder_work_loop() /*pass the data to ai keyword processing*/ ai_rawdata_handle(buffer_mix, buffer_size_mix); - - if (output_left > buffer_size_mix) { - memcpy(buffer_output + output_pos, buffer_mix, buffer_size_mix); - output_pos += buffer_size_mix; - } else if (output_left == buffer_size_mix) { - memcpy(buffer_output + output_pos, buffer_mix, buffer_size_mix); - output_pos = 0; - } else { - memcpy(buffer_output + output_pos, buffer_mix, output_left); - memcpy(buffer_output, buffer_mix + output_left, buffer_size_mix - output_left); - output_pos = buffer_size_mix - output_left; - } - output_left = output_size - output_pos; + mp->Release(mp_flag); } - - gNeedRunning = false; - - snd_pcm_drain(handle_ref); + recorder_->CloseReference(); + // while (sound_queue.empty() == false) { + // free(sound_queue.front()); + // sound_queue.pop(); + // } + mp->Clear(); snd_pcm_drain(handle_sound); - snd_pcm_close(handle_ref); snd_pcm_close(handle_sound); free(buffer_mix); - free(buffer_output); - free(buffer_sound_1); - free(buffer_sound_2); - free(buffer_ref_1); - free(buffer_ref_2); + // free(buffer_output); + free(buffer_ref); } diff --git a/cyberdog_interaction/cyberdog_audio/audio_base/include/audio_base/audio_player.hpp b/cyberdog_interaction/cyberdog_audio/audio_base/include/audio_base/audio_player.hpp index 8c6fc00..7f3372c 100644 --- a/cyberdog_interaction/cyberdog_audio/audio_base/include/audio_base/audio_player.hpp +++ b/cyberdog_interaction/cyberdog_audio/audio_base/include/audio_base/audio_player.hpp @@ -41,6 +41,8 @@ namespace cyberdog_audio #define INDE_VOLUME_GROUP -1 +#define MAX_QUEUE_BUFF_NUM 100 + using chuck_ptr = std::shared_ptr; using callback = std::function; @@ -56,14 +58,16 @@ class AudioPlayer static int GetFreeChannel(); static bool InitSuccess(); - static bool OpenReference(); + static bool OpenReference(int buffsize); static void CloseReference(); - static int GetReferenceData(Uint8 * buff, int need_size); - static size_t GetReferenceDataSize(); + static bool GetReferenceData(char * buff); + static bool HaveReferenceData(); + static void ClearReferenceData(); void SetFinishCallBack(callback finish_callback); + void SetChuckVolume(int volume); int SetVolume(int volume); - void SetVolumeGroup(int volume_gp); + void SetVolumeGroup(int volume_gp, int default_volume); int GetVolume(); void AddPlay(Uint8 * buff, int len); @@ -77,15 +81,16 @@ class AudioPlayer inline static int channelNum_; inline static int activeNum_; inline static std::vector thread_num_; - inline static std::vector volume_; + inline static std::vector chuck_volume_; inline static std::vector volume_group_; inline static std::map> chucks_; inline static std::map> databuff_; inline static std::map finish_callbacks_; - inline static std::queue reference_data_; + inline static std::queue reference_data_; inline static SDL_AudioDeviceID reference_id_; inline static SDL_AudioSpec obtained_spec_; + inline static int ref_buffsize_; int self_channel_; int init_ready_; diff --git a/cyberdog_interaction/cyberdog_audio/audio_base/include/audio_base/audio_queue.hpp b/cyberdog_interaction/cyberdog_audio/audio_base/include/audio_base/audio_queue.hpp new file mode 100644 index 0000000..d3bb763 --- /dev/null +++ b/cyberdog_interaction/cyberdog_audio/audio_base/include/audio_base/audio_queue.hpp @@ -0,0 +1,115 @@ +// Copyright (c) 2021 Xiaomi Corporation +// +// 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. + +#ifndef AUDIO_BASE__AUDIO_QUEUE_HPP_ +#define AUDIO_BASE__AUDIO_QUEUE_HPP_ + +#include +#include +#include + +namespace athena_audio +{ +template +class MsgQueue +{ +public: + MsgQueue() + { + is_wait = false; + } + ~MsgQueue() + { + if (!data_list.empty()) { + data_list.clear(); + } + if (is_wait) { + read_signal.notify_all(); + } + } + + bool EnQueue(const T & t) + { + std::unique_lock lk(data_lock); + data_list.emplace_front(t); + if (is_wait) { + is_wait = false; + read_signal.notify_one(); + } + return true; + } + + bool EnQueueOne(const T & t) + { + std::unique_lock lk(data_lock); + if (!Empty()) { + return false; + } else { + data_list.emplace_front(t); + if (is_wait) { + is_wait = false; + read_signal.notify_one(); + } + } + return true; + } + + bool DeQueue(T & t) + { + std::unique_lock lk(data_lock); + if (data_list.empty()) { + is_wait = true; + read_signal.wait(lk); + } + if (data_list.empty()) { + return false; + } else { + t = data_list.back(); + data_list.pop_back(); + return true; + } + } + + void Clear() + { + std::unique_lock lk(data_lock); + fprintf(stdout, "vc: msgqueue size: %d\n", static_cast(data_list.size())); + while (!data_list.empty()) { + T t = data_list.front(); + t.free_mem(); // need a detect operation, make sure func calling is correct + data_list.pop_front(); + } + fprintf(stdout, "vc: msgqueue size: %d\n", static_cast(data_list.size())); + } + + int Size() + { + std::unique_lock lk(data_lock); + return static_cast(data_list.size()); + } + + bool Empty() + { + return data_list.empty(); + } + +private: + std::condition_variable read_signal; + std::mutex data_lock; + std::list data_list; + bool is_wait; +}; // class MsgQueue +} // namespace athena_audio + +#endif // AUDIO_BASE__AUDIO_QUEUE_HPP_ diff --git a/cyberdog_interaction/cyberdog_audio/audio_base/include/audio_base/mempool.hpp b/cyberdog_interaction/cyberdog_audio/audio_base/include/audio_base/mempool.hpp new file mode 100644 index 0000000..95de025 --- /dev/null +++ b/cyberdog_interaction/cyberdog_audio/audio_base/include/audio_base/mempool.hpp @@ -0,0 +1,146 @@ +// Copyright (c) 2021 Beijing Xiaomi Mobile Software Co., Ltd. +// +// 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. + + +#ifndef AUDIO_BASE__MEMPOOL_HPP_ +#define AUDIO_BASE__MEMPOOL_HPP_ + +#include +#include +#include + +namespace audio_base +{ +class MemPool +{ +public: + MemPool(int size, int chunk) + : m_iSize(size), m_iChunkSize(chunk) + {} + + ~MemPool() + { + Clear(); + Reset(); + } + + bool Create(bool need_set = false) + { + /** + * @brief malloc memory, prepare for wokring + * + * @return bool, 0 success + */ + bool result = true; + for (int i = 0; i < m_iSize; ++i) { + char * p = reinterpret_cast(malloc(m_iChunkSize)); + if (p == nullptr) { + Clear(i); + result = false; + break; + } else { + if (need_set) { + memset(p, 0x0, m_iChunkSize); + } + m_vPointer.push_back(p); + } + } + + if (result) { + for (int i = 0; i < m_iSize; ++i) { + m_mRecorder.insert(std::make_pair(i, false)); + } + } + return true; + } + + bool Clear(int position = -1) + { + /** + * @brief free memory fron 0 to position, default free all + * + */ + bool result = true; + int free_size = position == -1 ? m_iSize : position; + free_size = free_size > m_iSize ? m_iSize : free_size; + for (int i = 0; i < free_size; ++i) { + if (m_vPointer[i] != nullptr) { + free(m_vPointer[i]); + m_vPointer[i] = nullptr; + } else { + result = false; + } + } + if (result) { + Reset(); + } + return result; + } + + void Reset() + { + for (auto iter = m_mRecorder.begin(); iter != m_mRecorder.end(); ++iter) { + iter->second = false; + } + } + + int GetMemory(char ** src) + { + /** + * @brief get an unused memory block, after using must call Release + * + */ + m_iWorker++; + m_iWorker %= m_iSize; + // fprintf(stdout, "vc:combiner mempool get memory worker: %d, sizeL %d\n", m_iWorker, m_iSize); + // need check safety in future, depend user using Release correctly + *src = reinterpret_cast(m_vPointer[m_iWorker]); + m_mRecorder.at(m_iWorker) = true; + return m_iWorker; + } + + int GetMemory(unsigned char ** src) + { + /** + * @brief get an unused memory block, after using must call Release + * + */ + m_iWorker++; + m_iWorker %= m_iSize; + // fprintf(stdout, "vc:combiner mempool get memory worker: %d, sizeL %d\n", m_iWorker, m_iSize); + // need check safety in future, depend user using Release correctly + *src = reinterpret_cast(m_vPointer[m_iWorker]); + m_mRecorder.at(m_iWorker) = true; + return m_iWorker; + } + + bool Release(int index) + { + auto iter = m_mRecorder.find(index); + if (iter != m_mRecorder.end()) { + iter->second = false; + return true; + } + return false; + } + +private: + int m_iSize; + int m_iChunkSize; + int m_iWorker; + std::vector m_vPointer; + std::map m_mRecorder; +}; // MemPool +} // namespace audio_base +#endif // AUDIO_BASE__MEMPOOL_HPP_ diff --git a/cyberdog_interaction/cyberdog_audio/audio_base/src/audio_player.cpp b/cyberdog_interaction/cyberdog_audio/audio_base/src/audio_player.cpp index 10d0508..7731f70 100644 --- a/cyberdog_interaction/cyberdog_audio/audio_base/src/audio_player.cpp +++ b/cyberdog_interaction/cyberdog_audio/audio_base/src/audio_player.cpp @@ -30,7 +30,7 @@ cyberdog_audio::AudioPlayer::AudioPlayer( init_success_ = Init(); channelNum_ = Mix_AllocateChannels(DEFAULT_PLAY_CHANNEL_NUM); thread_num_ = std::vector(channelNum_, 0); - volume_ = std::vector(channelNum_, volume); + chuck_volume_ = std::vector(channelNum_, MIX_MAX_VOLUME); volume_group_ = std::vector(channelNum_, INDE_VOLUME_GROUP); Mix_ChannelFinished(chuckFinish_callback); chucks_ = std::map>(); @@ -63,14 +63,13 @@ cyberdog_audio::AudioPlayer::AudioPlayer( channelNum_ = Mix_AllocateChannels(self_channel_ + 1); for (int ch = thread_num_.size(); ch < channelNum_; ch++) { thread_num_.push_back(0); - volume_.push_back(volume); + chuck_volume_.push_back(MIX_MAX_VOLUME); volume_group_.push_back(volume_group); } } init_ready_ = true; thread_num_[self_channel_] = 0; - volume_[self_channel_] = GetGroupVolume(volume_group, volume); - volume_group_[self_channel_] = volume_group; + SetVolumeGroup(volume_group, volume); std::cout << "[AudioPlayer]Open on Channel[" << self_channel_ << "].\n"; } else { std::cout << "[AudioPlayer]Init_Error, Channel[" << self_channel_ << "] be used.\n"; @@ -110,7 +109,7 @@ bool cyberdog_audio::AudioPlayer::InitSuccess() return init_success_; } -bool cyberdog_audio::AudioPlayer::OpenReference() +bool cyberdog_audio::AudioPlayer::OpenReference(int buffsize) { if (init_success_ == false && reference_id_ != 0) {return false;} int deviceNum = SDL_GetNumAudioDevices(SDL_TRUE); @@ -123,7 +122,7 @@ bool cyberdog_audio::AudioPlayer::OpenReference() desired_spec.freq = AUDIO_FREQUENCY; desired_spec.format = AUDIO_FORMAT; desired_spec.channels = AUDIO_CHANNELS; - desired_spec.samples = AUDIO_CHUCKSIZE; + desired_spec.samples = buffsize * 0.5; desired_spec.callback = audioRecording_callback; reference_id_ = SDL_OpenAudioDevice( SDL_GetAudioDeviceName(0, SDL_TRUE), @@ -136,7 +135,8 @@ bool cyberdog_audio::AudioPlayer::OpenReference() return false; } else { SDL_PauseAudioDevice(reference_id_, SDL_FALSE); - reference_data_ = std::queue(); + ref_buffsize_ = buffsize; + reference_data_ = std::queue(); std::cout << "[AudioPlayer]Success open reference channel\n"; return true; } @@ -150,27 +150,34 @@ void cyberdog_audio::AudioPlayer::CloseReference() SDL_CloseAudioDevice(reference_id_); reference_id_ = 0; while (reference_data_.empty() == false) { + delete[] reference_data_.front(); reference_data_.pop(); } std::cout << "[AudioPlayer]Close reference channel\n"; } -int cyberdog_audio::AudioPlayer::GetReferenceData(Uint8 * buff, int need_size) +bool cyberdog_audio::AudioPlayer::GetReferenceData(char * buff) { - if (reference_id_ != 0) { - int out_size = std::min(need_size, static_cast(reference_data_.size())); - for (int a = 0; a < out_size; a++) { - buff[a] = reference_data_.front(); - reference_data_.pop(); - } - return out_size; + if (reference_id_ != 0 && reference_data_.empty() == false) { + memcpy(buff, reference_data_.front(), ref_buffsize_); + delete[] reference_data_.front(); + reference_data_.pop(); + return true; } - return 0; + return false; } -size_t cyberdog_audio::AudioPlayer::GetReferenceDataSize() +bool cyberdog_audio::AudioPlayer::HaveReferenceData() { - return reference_data_.size(); + return reference_data_.size() != 0; +} + +void cyberdog_audio::AudioPlayer::ClearReferenceData() +{ + for (int a = 0; a < static_cast(reference_data_.size()); a++) { + delete[] reference_data_.front(); + reference_data_.pop(); + } } void cyberdog_audio::AudioPlayer::SetFinishCallBack(callback finish_callback) @@ -179,6 +186,12 @@ void cyberdog_audio::AudioPlayer::SetFinishCallBack(callback finish_callback) finish_callbacks_[self_channel_] = finish_callback; } +void cyberdog_audio::AudioPlayer::SetChuckVolume(int volume) +{ + if (init_ready_ == false) {return;} + chuck_volume_[self_channel_] = volume; +} + int cyberdog_audio::AudioPlayer::SetVolume(int volume) { if (init_ready_ == false) {return -1;} @@ -195,29 +208,30 @@ int cyberdog_audio::AudioPlayer::SetVolume(int volume) return real_set; } -void cyberdog_audio::AudioPlayer::SetVolumeGroup(int volume_gp) +void cyberdog_audio::AudioPlayer::SetVolumeGroup(int volume_gp, int default_volume) { if (init_ready_ == false) {return;} - volume_[self_channel_] = GetGroupVolume(volume_gp, volume_[self_channel_]); + SetSingleVolume(self_channel_, GetGroupVolume(volume_gp, default_volume)); volume_group_[self_channel_] = volume_gp; } int cyberdog_audio::AudioPlayer::GetVolume() { if (init_ready_ == false) {return -1;} - return volume_[self_channel_]; + return Mix_Volume(self_channel_, -1); } void cyberdog_audio::AudioPlayer::AddPlay(Uint8 * buff, int len) { if (self_channel_ >= 0 && init_ready_ && buff != nullptr && len > 0) { + std::cout << "[AudioPlayer]Get play request\n"; auto chuck = std::make_shared(); Uint8 * p = new Uint8[len]; memcpy(p, buff, len); databuff_[self_channel_].push(p); chuck->abuf = p; chuck->alen = len; - chuck->volume = volume_[self_channel_]; + chuck->volume = chuck_volume_[self_channel_]; chucks_[self_channel_].push(chuck); if (chucks_[self_channel_].size() == 1) { auto play_thread_ = std::thread(PlayThreadFunc, self_channel_, ++thread_num_[self_channel_]); @@ -288,9 +302,7 @@ int cyberdog_audio::AudioPlayer::SetSingleVolume(int channel, int volume) { if (init_ready_ == false) {return -1;} volume = volume < 0 ? 0 : (volume > 128 ? 128 : volume); - Mix_Volume(channel, volume); - volume_[channel] = volume; - return volume; + return Mix_Volume(channel, volume); } int cyberdog_audio::AudioPlayer::GetGroupVolume(int volume_group, int default_volume) @@ -298,7 +310,7 @@ int cyberdog_audio::AudioPlayer::GetGroupVolume(int volume_group, int default_vo if (volume_group != INDE_VOLUME_GROUP) { for (int ch = 0; ch < static_cast(volume_group_.size()); ch++) { if (volume_group_[ch] == volume_group) { - return volume_[ch]; + return Mix_Volume(ch, -1); } } } @@ -317,8 +329,9 @@ bool cyberdog_audio::AudioPlayer::PopEmpty(int channel) void cyberdog_audio::AudioPlayer::PlayThreadFunc(int channel, int thread_num) { + std::cout << "[AudioPlayer]Channel[" << channel << "] thread start\n"; auto p_chucks = *chucks_[channel].front(); - p_chucks.volume = volume_[channel]; + p_chucks.volume = chuck_volume_[channel]; Mix_PlayChannel(channel, &p_chucks, 0); while (thread_num_[channel] == thread_num && Mix_Playing(channel)) { SDL_Delay(DELAY_CHECK_TIME); @@ -340,7 +353,15 @@ void cyberdog_audio::AudioPlayer::chuckFinish_callback(int channel) void cyberdog_audio::AudioPlayer::audioRecording_callback(void *, Uint8 * stream, int len) { - for (int a = 0; a < len; a++) { - reference_data_.push(stream[a]); + auto new_buff = new Uint8[len]; + memcpy(new_buff, stream, len); + reference_data_.push(new_buff); + int overflow = static_cast(reference_data_.size()) - MAX_QUEUE_BUFF_NUM; + if (overflow > 0) { + std::cout << "[AudioPlayer]Warning reference channel data overflow\n"; + for (int a = 0; a < overflow; a++) { + delete[] reference_data_.front(); + reference_data_.pop(); + } } } diff --git a/cyberdog_interaction/cyberdog_audio/audio_interaction/include/audio_interaction/voice_cmd.hpp b/cyberdog_interaction/cyberdog_audio/audio_interaction/include/audio_interaction/voice_cmd.hpp index 436764f..1a61da5 100644 --- a/cyberdog_interaction/cyberdog_audio/audio_interaction/include/audio_interaction/voice_cmd.hpp +++ b/cyberdog_interaction/cyberdog_audio/audio_interaction/include/audio_interaction/voice_cmd.hpp @@ -65,6 +65,7 @@ #define TOKEN_FILE "/opt/ros2/cyberdog/data/token.toml" #define AI_STATUS_FILE "/opt/ros2/cyberdog/data/ai_status.toml" +#define VOLUME_FILE "/opt/ros2/cyberdog/data/volume.toml" #define WAV_DIR "/opt/ros2/cyberdog/data/wav/" #define FAC_TEST_FILE "/opt/ros2/cyberdog/ai_conf/ai_off" #define WAKE_UP_SIGNAL 100 @@ -124,15 +125,15 @@ class VoiceCmd : public cyberdog_utils::LifecycleNode enum ai_switch { - AI_ONLINE_ON = 0x0001, // 1 - AI_OFFLINE_ON = 0x0010, // 16 - AI_MASK = 0x0000 // 0 + AI_OFF = 0, + AI_ONLINE_ON, + AI_OFFLINE_ON, }; enum token_state { TOKEN_READY = 1, - DEVICE_ID_READY, + DEVICE_ID_READY }; enum order_name @@ -144,7 +145,7 @@ class VoiceCmd : public cyberdog_utils::LifecycleNode ORDER_STEP_BACK, ORDER_TURN_AROUND, ORDER_HI_FIVE, - ORDER_DANCE, + ORDER_DANCE }; std::array vol_value = {0, 15, 30, 45, 60, 75, 90, 100, 110, 120, 128}; @@ -202,6 +203,7 @@ class VoiceCmd : public cyberdog_utils::LifecycleNode void play_callback(); void volume_set(int vol); int volume_get(); + int64_t volume_check(); int get_ai_status(); int Detectwifi(); int ExecuteCMD(const char * cmd, char * result); @@ -235,6 +237,7 @@ class VoiceCmd : public cyberdog_utils::LifecycleNode /* Action */ std::unique_ptr play_server_; + std::shared_ptr orderback_; int loop_rate_; rclcpp::Node::SharedPtr play_client_node_; @@ -242,6 +245,15 @@ class VoiceCmd : public cyberdog_utils::LifecycleNode rclcpp::Node::SharedPtr ExtMon_client_node_; rclcpp_action::Client::SharedPtr ExtMon_client_; + +/* TEMP */ + rclcpp::TimerBase::SharedPtr timer_temp_; + rclcpp::Node::SharedPtr temp_node_; + + /* Thread */ + std::shared_ptr play_thread_; + std::shared_ptr wake_play_thread_; + std::shared_ptr order_play_thread_; }; // class VoiceCmd } // namespace cyberdog_audio diff --git a/cyberdog_interaction/cyberdog_audio/audio_interaction/src/voice_cmd.cpp b/cyberdog_interaction/cyberdog_audio/audio_interaction/src/voice_cmd.cpp index f19a370..1f9b07c 100644 --- a/cyberdog_interaction/cyberdog_audio/audio_interaction/src/voice_cmd.cpp +++ b/cyberdog_interaction/cyberdog_audio/audio_interaction/src/voice_cmd.cpp @@ -105,11 +105,8 @@ cyberdog_utils::CallbackReturn VoiceCmd::on_configure(const rclcpp_lifecycle::St cyberdog_utils::CallbackReturn VoiceCmd::on_activate(const rclcpp_lifecycle::State &) { + int ai_status, pub_status, volume_value; RCLCPP_INFO(get_logger(), "Activating"); - RCLCPP_INFO( - get_logger(), "Activating, (AI_OFFLINE_ON & AI_MASK) & (AI_ONLINE_ON & AI_MASK): %d", - (AI_OFFLINE_ON & AI_MASK) & (AI_ONLINE_ON & AI_MASK)); - RCLCPP_INFO(get_logger(), "Activating, AI_OFFLINE_ON | AI_MASK: %d", AI_OFFLINE_ON | AI_MASK); player_init(); sleep(10); play_server_->activate(); @@ -118,7 +115,6 @@ cyberdog_utils::CallbackReturn VoiceCmd::on_activate(const rclcpp_lifecycle::Sta token_ready_pub_->on_activate(); std::string device_id = getDeviceId(); - int ai_status, pub_status; const auto token = toml::parse(TOKEN_FILE); std::string title_toml = toml::find(token, "title"); RCLCPP_INFO(get_logger(), "toml title: %s", title_toml.c_str()); @@ -143,18 +139,25 @@ cyberdog_utils::CallbackReturn VoiceCmd::on_activate(const rclcpp_lifecycle::Sta ai_status = get_ai_require_status(); if (fac_test_flage(FAC_TEST_FILE)) { RCLCPP_INFO(get_logger(), "factory force xiaoai on"); - pub_status = AI_ONLINE_ON | AI_MASK; + pub_status = AI_ONLINE_ON; } else { if (ai_status == -1) { - pub_status = (AI_OFFLINE_ON & AI_MASK) & (AI_ONLINE_ON & AI_MASK); + pub_status = AI_OFF; } else if (ai_status == AI_OFFLINE_ON) { - pub_status = AI_OFFLINE_ON | AI_MASK; + pub_status = AI_OFFLINE_ON; } else if (ai_status == AI_ONLINE_ON) { - pub_status = AI_ONLINE_ON | AI_MASK; + pub_status = AI_ONLINE_ON; } else { - pub_status = AI_MASK; + pub_status = AI_OFF; } } + + volume_value = volume_check(); + if (volume_value == -1) { + volume_set(7); + } else { + volume_set(volume_value); + } PublishAiSwitch(pub_status); set_ai_require_status(pub_status); @@ -503,6 +506,8 @@ void VoiceCmd::check_play_request() // auto order_user = goal->order.user; auto order_name = goal->order.name.id; rclcpp::WallRate r(std::chrono::seconds(1)); + int volume_memory = volume_get(); + RCLCPP_INFO(get_logger(), "volume_get: %d.", volume_memory); bool new_goal(false); RCLCPP_INFO( get_logger(), "Got order goal %d from %s.", goal->order.name.id, @@ -517,6 +522,10 @@ void VoiceCmd::check_play_request() play_server_->succeeded_current(result); return; } + + if (order_name == 8 || order_name == 9) { + volume_set(7); + } new_goal = true; RCLCPP_INFO( get_logger(), "Received playback order %d, the song while to be played or rejected.", @@ -569,6 +578,9 @@ void VoiceCmd::check_play_request() /* RCLCPP_INFO( get_logger(), "Playorder %d executed failed.", order_name); */ + if (order_name == 8 || order_name == 9) { + volume_set(volume_memory); + } return; } } @@ -628,15 +640,15 @@ void VoiceCmd::check_app_order( } response_->flage = TokenPassT::Response::DID_SUCCEED; } else if (request_->ask == TokenPassT::Request::ASK_XIAOAI_OFF) { - ai_pub_status = (AI_OFFLINE_ON & AI_MASK) & (AI_ONLINE_ON & AI_MASK); + ai_pub_status = AI_OFF; RCLCPP_INFO( get_logger(), "recive xiaoai off ask from app, the ask will pub to audio assitant: %d.", ai_pub_status); PublishAiSwitch(ai_pub_status); - set_ai_require_status(AI_MASK); + set_ai_require_status(AI_OFF); response_->flage = TokenPassT::Response::XIAOAI_OFF_SUCCEED; } else if (request_->ask == TokenPassT::Request::ASK_XIAOAI_ON) { - ai_pub_status = AI_ONLINE_ON | AI_MASK; + ai_pub_status = AI_ONLINE_ON; RCLCPP_INFO( get_logger(), "recive xiaoai on ask from app, the ask will pub to audio assitant: %d.", ai_pub_status); @@ -660,9 +672,9 @@ void VoiceCmd::check_app_order( } else if (ai_status_temp == AI_OFFLINE_ON) { response_->flage = TokenPassT::Response::XIAOAI_OFFLINE_ON; RCLCPP_INFO(get_logger(), "response XIAOAI_OFFLINE_ON to app: %d.", AI_OFFLINE_ON); - } else if (ai_status_temp == AI_MASK || ai_status_temp == -1) { + } else if (ai_status_temp == AI_OFF || ai_status_temp == -1) { response_->flage = TokenPassT::Response::XIAOAI_OFF; - RCLCPP_INFO(get_logger(), "response AI_OFFLINE_ON to app: %d.", AI_MASK); + RCLCPP_INFO(get_logger(), "response AI_OFFLINE_ON to app: %d.", AI_OFF); } } else { RCLCPP_ERROR(get_logger(), "recive unknow ask from app."); @@ -1000,6 +1012,14 @@ void VoiceCmd::volume_set(int vol) volume = vol; } player_->SetVolume(vol_value[volume]); + const auto volume_toml = toml::parse(VOLUME_FILE); + const toml::value toml_t{ + {"title", "volume status"}, + {"volume", volume}, + }; + std::ofstream ofs(VOLUME_FILE, std::ofstream::out); + ofs << toml_t; + ofs.close(); } int VoiceCmd::volume_get() @@ -1020,6 +1040,16 @@ int VoiceCmd::volume_get() return 0; } +int64_t VoiceCmd::volume_check() +{ + const auto volume_toml = toml::parse(VOLUME_FILE); + + std::int64_t volume_value = toml::find(volume_toml, "volume"); + RCLCPP_INFO(get_logger(), "volume_value(toml) : %d", volume_value); + + return volume_value; +} + void VoiceCmd::player_init() { player_ = diff --git a/cyberdog_interaction/cyberdog_audio/cyberdog_audio/CMakeLists.txt b/cyberdog_interaction/cyberdog_audio/cyberdog_audio/CMakeLists.txt index 4aa7bfc..f15556c 100644 --- a/cyberdog_interaction/cyberdog_audio/cyberdog_audio/CMakeLists.txt +++ b/cyberdog_interaction/cyberdog_audio/cyberdog_audio/CMakeLists.txt @@ -38,6 +38,8 @@ add_executable(${executable_name} src/main.cpp ) +target_compile_definitions(${executable_name} PRIVATE "ENABLE_BACKTRACE") + if(audio_assistant_FOUND AND XIAOMI_XIAOAI) target_compile_definitions(${executable_name} PRIVATE "ENABLE_ASSISTANT") set(dependencies diff --git a/cyberdog_interaction/cyberdog_audio/cyberdog_audio/data/ai_mode.toml b/cyberdog_interaction/cyberdog_audio/cyberdog_audio/data/ai_mode.toml new file mode 100644 index 0000000..950454c --- /dev/null +++ b/cyberdog_interaction/cyberdog_audio/cyberdog_audio/data/ai_mode.toml @@ -0,0 +1,2 @@ +title = "ai_mode" +val_env = 0 diff --git a/cyberdog_interaction/cyberdog_audio/cyberdog_audio/include/audio_backtrace/back_trace.h b/cyberdog_interaction/cyberdog_audio/cyberdog_audio/include/audio_backtrace/back_trace.h index 3da70db..a1e3e1f 100644 --- a/cyberdog_interaction/cyberdog_audio/cyberdog_audio/include/audio_backtrace/back_trace.h +++ b/cyberdog_interaction/cyberdog_audio/cyberdog_audio/include/audio_backtrace/back_trace.h @@ -49,8 +49,8 @@ static void dump(void) static void signal_handler(int signo) { - fprintf(stderr, "=========>>>catch signal %d <<<=========", signo); - fprintf(stderr, "backtrace start..."); + fprintf(stderr, "=========>>>catch signal %d <<<=========\n", signo); + fprintf(stderr, "backtrace start...\n"); dump(); fprintf(stderr, "backtrace end...\n");