parent
c4ef6240e7
commit
88cadcff40
@ -0,0 +1,324 @@
|
|||||||
|
cmake_minimum_required(VERSION 2.8.3)
|
||||||
|
project(xf_mic_asr_offline)
|
||||||
|
add_compile_options(-std=c++11)
|
||||||
|
## Compile as C++11, supported in ROS Kinetic and newer
|
||||||
|
# add_compile_options(-std=c++11)
|
||||||
|
set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -g ")
|
||||||
|
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
|
||||||
|
tf
|
||||||
|
)
|
||||||
|
|
||||||
|
link_directories(
|
||||||
|
lib/x64
|
||||||
|
)
|
||||||
|
## System dependencies are found with CMake's conventions
|
||||||
|
# find_package(Boost REQUIRED COMPONENTS system)
|
||||||
|
|
||||||
|
|
||||||
|
## 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
|
||||||
|
Pcm_Msg.msg
|
||||||
|
)
|
||||||
|
|
||||||
|
add_message_files(
|
||||||
|
FILES
|
||||||
|
position.msg
|
||||||
|
)
|
||||||
|
|
||||||
|
## Generate services in the 'srv' folder
|
||||||
|
add_service_files(
|
||||||
|
FILES
|
||||||
|
Get_Offline_Result_srv.srv
|
||||||
|
Set_Major_Mic_srv.srv
|
||||||
|
Get_Major_Mic_srv.srv
|
||||||
|
Start_Record_srv.srv
|
||||||
|
Set_Awake_Word_srv.srv
|
||||||
|
Set_Led_On_srv.srv
|
||||||
|
Get_Awake_Angle_srv.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(
|
||||||
|
CATKIN_DEPENDS message_runtime
|
||||||
|
# INCLUDE_DIRS include
|
||||||
|
# LIBRARIES xf_mic_api
|
||||||
|
# CATKIN_DEPENDS roscpp rospy senor_msgs std_msgs
|
||||||
|
# DEPENDS system_lib
|
||||||
|
)
|
||||||
|
|
||||||
|
###########
|
||||||
|
## Build ##
|
||||||
|
###########
|
||||||
|
|
||||||
|
## Specify additional locations of header files
|
||||||
|
## Your package locations should be listed before other location
|
||||||
|
## Declare a C++ library
|
||||||
|
## 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(${PROJECT_NAME}_node src/xf_mic_package_node.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(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
|
||||||
|
|
||||||
|
## Specify libraries to link a library or executable target against
|
||||||
|
# target_link_libraries(${PROJECT_NAME}_node
|
||||||
|
# ${catkin_LIBRARIES}
|
||||||
|
# )
|
||||||
|
|
||||||
|
|
||||||
|
#include_directories(
|
||||||
|
# include
|
||||||
|
# ${catkin_INCLUDE_DIRS}
|
||||||
|
#)
|
||||||
|
|
||||||
|
#add_executable(hid_test_auto src/hid_test_auto.cpp)
|
||||||
|
#add_dependencies(
|
||||||
|
# hid_test_auto
|
||||||
|
# ${xf_mic_package_EXPORTED_TARGETS}
|
||||||
|
# xf_mic_asr_offline_gencpp
|
||||||
|
#)
|
||||||
|
#target_link_libraries(hid_test_auto ${catkin_LIBRARIES} offline_record_lib hid_lib rt dl pthread stdc++ )
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
include_directories(
|
||||||
|
include
|
||||||
|
${catkin_INCLUDE_DIRS}
|
||||||
|
)
|
||||||
|
|
||||||
|
add_executable(voice_control src/voice_control.cpp)
|
||||||
|
add_dependencies(
|
||||||
|
voice_control
|
||||||
|
${xf_mic_package_EXPORTED_TARGETS}
|
||||||
|
xf_mic_asr_offline_gencpp
|
||||||
|
)
|
||||||
|
target_link_libraries(voice_control ${catkin_LIBRARIES} offline_record_lib hid_lib rt dl pthread stdc++ )
|
||||||
|
|
||||||
|
|
||||||
|
add_executable(record src/record.cpp)
|
||||||
|
add_dependencies(
|
||||||
|
record
|
||||||
|
${xf_mic_package_EXPORTED_TARGETS}
|
||||||
|
xf_mic_asr_offline_gencpp
|
||||||
|
)
|
||||||
|
target_link_libraries(record ${catkin_LIBRARIES} offline_record_lib hid_lib rt dl pthread stdc++ )
|
||||||
|
|
||||||
|
add_executable(call_recognition src/call_recognition.cpp)
|
||||||
|
add_dependencies(
|
||||||
|
call_recognition
|
||||||
|
${xf_mic_package_EXPORTED_TARGETS}
|
||||||
|
xf_mic_asr_offline_gencpp
|
||||||
|
)
|
||||||
|
target_link_libraries(
|
||||||
|
call_recognition
|
||||||
|
${catkin_LIBRARIES}
|
||||||
|
# offline_record_lib hid_lib rt dl pthread stdc++
|
||||||
|
)
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
add_executable(command_recognition
|
||||||
|
src/command_recognition.cpp
|
||||||
|
)
|
||||||
|
add_dependencies(
|
||||||
|
command_recognition
|
||||||
|
${xf_mic_package_EXPORTED_TARGETS}
|
||||||
|
xf_mic_asr_offline_gencpp
|
||||||
|
)
|
||||||
|
target_link_libraries(
|
||||||
|
command_recognition
|
||||||
|
${catkin_LIBRARIES}
|
||||||
|
# -ldl -lpthread -lm -lrt -lasound
|
||||||
|
)
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
add_executable(motion_control
|
||||||
|
src/motion_control.cpp
|
||||||
|
)
|
||||||
|
add_dependencies(
|
||||||
|
motion_control
|
||||||
|
${xf_mic_package_EXPORTED_TARGETS}
|
||||||
|
xf_mic_asr_offline_gencpp
|
||||||
|
)
|
||||||
|
target_link_libraries(
|
||||||
|
motion_control
|
||||||
|
${catkin_LIBRARIES}
|
||||||
|
# -ldl -lpthread -lm -lrt -lasound
|
||||||
|
)
|
||||||
|
|
||||||
|
add_executable(refresh_mic
|
||||||
|
src/refresh_mic.cpp
|
||||||
|
)
|
||||||
|
add_dependencies(
|
||||||
|
refresh_mic
|
||||||
|
${xf_mic_package_EXPORTED_TARGETS}
|
||||||
|
xf_mic_asr_offline_gencpp
|
||||||
|
)
|
||||||
|
target_link_libraries(
|
||||||
|
refresh_mic
|
||||||
|
${catkin_LIBRARIES}
|
||||||
|
offline_record_lib hid_lib rt dl pthread stdc++
|
||||||
|
-ldl -lpthread -lm -lrt -lasound
|
||||||
|
)
|
||||||
|
|
||||||
|
install(PROGRAMS
|
||||||
|
scripts/go_to_specific_point_on_map.py
|
||||||
|
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
|
||||||
|
)
|
||||||
|
|
||||||
|
#add_executable(test
|
||||||
|
# src/test.cpp
|
||||||
|
#)
|
||||||
|
|
||||||
|
#target_link_libraries(
|
||||||
|
# test
|
||||||
|
# ${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 executable scripts (Python etc.) for installation
|
||||||
|
## in contrast to setup.py, you can choose the destination
|
||||||
|
# install(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 ${PROJECT_NAME}_node
|
||||||
|
# RUNTIME 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 include/${PROJECT_NAME}/
|
||||||
|
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_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_xf_mic_package.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,31 @@
|
|||||||
|
# -*- coding: utf-8 -*-
|
||||||
|
"""
|
||||||
|
Created on Sat May 8 14:09:34 2021
|
||||||
|
|
||||||
|
@author: 59866
|
||||||
|
"""
|
||||||
|
|
||||||
|
import wave
|
||||||
|
import time
|
||||||
|
import os
|
||||||
|
def pcmToWav(in_file, out_file):
|
||||||
|
|
||||||
|
in_file = open(in_file, 'rb')
|
||||||
|
out_file = wave.open(out_file, 'wb')
|
||||||
|
|
||||||
|
#out_file.setnchannels(int(input("plese input channels [1/2]: ")))
|
||||||
|
#out_file.setframerate(int(input("plese input samplerate [32000]: ")))
|
||||||
|
out_file.setnchannels(1)
|
||||||
|
out_file.setframerate(16000)
|
||||||
|
out_file.setsampwidth(2) #16-bit
|
||||||
|
out_file.writeframesraw(in_file.read())
|
||||||
|
|
||||||
|
in_file.close()
|
||||||
|
out_file.close()
|
||||||
|
print('>>>>>complete recording, start to compare.....')
|
||||||
|
|
||||||
|
if __name__ == '__main__':
|
||||||
|
#IN_FILE = input(r'input the file name: ')
|
||||||
|
IN_FILE = ("/home/turtlebot/catkin_ws/src/xf_mic_asr_offline/audio/vvui_deno.pcm")
|
||||||
|
OUT_FILE = ("/home/turtlebot/catkin_ws/src/xf_mic_asr_offline/audio/vvui_deno.wav")
|
||||||
|
pcmToWav(IN_FILE, OUT_FILE)
|
@ -0,0 +1,31 @@
|
|||||||
|
# -*- coding: utf-8 -*-
|
||||||
|
"""
|
||||||
|
Created on Sat May 8 14:09:34 2021
|
||||||
|
|
||||||
|
@author: 59866
|
||||||
|
"""
|
||||||
|
|
||||||
|
import wave
|
||||||
|
import time
|
||||||
|
import os
|
||||||
|
def pcmToWav(in_file, out_file):
|
||||||
|
|
||||||
|
in_file = open(in_file, 'rb')
|
||||||
|
out_file = wave.open(out_file, 'wb')
|
||||||
|
|
||||||
|
#out_file.setnchannels(int(input("plese input channels [1/2]: ")))
|
||||||
|
#out_file.setframerate(int(input("plese input samplerate [32000]: ")))
|
||||||
|
out_file.setnchannels(1)
|
||||||
|
out_file.setframerate(16000)
|
||||||
|
out_file.setsampwidth(2) #16-bit
|
||||||
|
out_file.writeframesraw(in_file.read())
|
||||||
|
|
||||||
|
in_file.close()
|
||||||
|
out_file.close()
|
||||||
|
print('>>>>>complete recording, start to compare.....')
|
||||||
|
|
||||||
|
if __name__ == '__main__':
|
||||||
|
#IN_FILE = input(r'input the file name: ')
|
||||||
|
IN_FILE = ("/home/turtlebot/catkin_ws/src/xf_mic_asr_offline/audio/vvui_deno.pcm")
|
||||||
|
OUT_FILE = ("/home/turtlebot/catkin_ws/src/xf_mic_asr_offline/audio/vvui_deno.wav")
|
||||||
|
pcmToWav(IN_FILE, OUT_FILE)
|
Binary file not shown.
Binary file not shown.
@ -1,3 +1,3 @@
|
|||||||
confidence: 18
|
confidence: 18
|
||||||
seconds_per_order: 15
|
seconds_per_order: 15
|
||||||
appid: 5fa0b8b9
|
appid: 7c6a4b39
|
||||||
|
@ -0,0 +1,3 @@
|
|||||||
|
confidence: 18
|
||||||
|
seconds_per_order: 15
|
||||||
|
appid: 5fa0b8b9
|
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
@ -0,0 +1 @@
|
|||||||
|
{"_16k":["call"],"_8k":[]}
|
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
@ -0,0 +1,12 @@
|
|||||||
|
<launch>
|
||||||
|
<rosparam command="load" file="$(find xf_mic_asr_offline)/config/appid_params.yaml" />
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
<arg name="package_path" default = "$(find xf_mic_asr_offline)" />
|
||||||
|
<node pkg="xf_mic_asr_offline" type="refresh_mic" name="refresh_mic" />
|
||||||
|
<node pkg="xf_mic_asr_offline" type="go_to_specific_point_on_map.py" name="navigation" />
|
||||||
|
<node pkg="xf_mic_asr_offline" type="voice_control" name="xf_asr_offline_node" output="screen">
|
||||||
|
<param name="source_path" type="string" value="$(find xf_mic_asr_offline)"/>
|
||||||
|
</node>
|
||||||
|
</launch>
|
@ -0,0 +1,12 @@
|
|||||||
|
<launch>
|
||||||
|
<rosparam command="load" file="$(find xf_mic_asr_offline)/config/appid_params.yaml" />
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
<arg name="package_path" default = "$(find xf_mic_asr_offline)" />
|
||||||
|
<node pkg="xf_mic_asr_offline" type="refresh_mic" name="refresh_mic" />
|
||||||
|
<node pkg="xf_mic_asr_offline" type="go_to_specific_point_on_map.py" name="navigation" />
|
||||||
|
<node pkg="xf_mic_asr_offline" type="voice_control" name="xf_asr_offline_node" output="screen">
|
||||||
|
<param name="source_path" type="string" value="$(find xf_mic_asr_offline)"/>
|
||||||
|
</node>
|
||||||
|
</launch>
|
@ -0,0 +1,124 @@
|
|||||||
|
#!/usr/bin/env python
|
||||||
|
# -*- coding: UTF-8 -*-
|
||||||
|
# TurtleBot must have minimal.launch & amcl_demo.launch
|
||||||
|
# running prior to starting this script
|
||||||
|
# For simulation: launch gazebo world & amcl_demo prior to run this script
|
||||||
|
|
||||||
|
import rospy
|
||||||
|
from move_base_msgs.msg import MoveBaseAction, MoveBaseGoal
|
||||||
|
import actionlib
|
||||||
|
from actionlib_msgs.msg import *
|
||||||
|
from geometry_msgs.msg import Pose, Point, Quaternion
|
||||||
|
#定义消息的类型
|
||||||
|
from std_msgs.msg import Int32
|
||||||
|
from std_msgs.msg import String
|
||||||
|
import time
|
||||||
|
angle_of_wakeup = 0
|
||||||
|
# 回调函数
|
||||||
|
def callback(data):
|
||||||
|
angle_of_wakeup = data.data
|
||||||
|
rospy.loginfo(rospy.get_caller_id() + "I heard %d", data.data)
|
||||||
|
# 赋值角度
|
||||||
|
rospy.loginfo(rospy.get_caller_id() + "I heard angle: %d", angle_of_wakeup)
|
||||||
|
# 定义订阅者节点
|
||||||
|
def listener():
|
||||||
|
rospy.Subscriber("/mic/awake/angle", Int32, callback)
|
||||||
|
return True
|
||||||
|
|
||||||
|
class GoToPose():
|
||||||
|
|
||||||
|
def __init__(self):
|
||||||
|
self.goal_sent = False
|
||||||
|
|
||||||
|
# What to do if shut down (e.g. Ctrl-C or failure)
|
||||||
|
rospy.on_shutdown(self.shutdown)
|
||||||
|
|
||||||
|
# Tell the action client that we want to spin a thread by default
|
||||||
|
self.move_base = actionlib.SimpleActionClient("move_base", MoveBaseAction)
|
||||||
|
rospy.loginfo("Wait for the action server to come up")
|
||||||
|
|
||||||
|
# Allow up to 10 seconds for the action server to come up
|
||||||
|
self.move_base.wait_for_server(rospy.Duration(2))
|
||||||
|
|
||||||
|
def goto(self, pos, quat):
|
||||||
|
|
||||||
|
# Send a goal
|
||||||
|
self.goal_sent = True
|
||||||
|
goal = MoveBaseGoal()
|
||||||
|
goal.target_pose.header.frame_id = 'map'
|
||||||
|
goal.target_pose.header.stamp = rospy.Time.now()
|
||||||
|
goal.target_pose.pose = Pose(Point(pos['x'], pos['y'], 0.000),
|
||||||
|
Quaternion(quat['r1'], quat['r2'], quat['r3'], quat['r4']))
|
||||||
|
|
||||||
|
# Start moving
|
||||||
|
self.move_base.send_goal(goal)
|
||||||
|
|
||||||
|
# Allow TurtleBot up to 60 seconds to complete task
|
||||||
|
# Time to finish the navigation
|
||||||
|
# by lcp 2021/7/1
|
||||||
|
success = self.move_base.wait_for_result(rospy.Duration(60))
|
||||||
|
|
||||||
|
state = self.move_base.get_state()
|
||||||
|
result = False
|
||||||
|
|
||||||
|
if success and state == GoalStatus.SUCCEEDED:
|
||||||
|
# We made it!
|
||||||
|
result = True
|
||||||
|
else:
|
||||||
|
self.move_base.cancel_goal()
|
||||||
|
|
||||||
|
self.goal_sent = False
|
||||||
|
return result
|
||||||
|
|
||||||
|
def shutdown(self):
|
||||||
|
if self.goal_sent:
|
||||||
|
self.move_base.cancel_goal()
|
||||||
|
rospy.loginfo("Stop")
|
||||||
|
rospy.sleep(1)
|
||||||
|
|
||||||
|
if __name__ == '__main__':
|
||||||
|
|
||||||
|
try:
|
||||||
|
rospy.init_node('nav_test', anonymous=True)
|
||||||
|
#rospy.Subscriber("/mic/awake/angle", Int32, callback)
|
||||||
|
|
||||||
|
rospy.sleep(1)
|
||||||
|
whether_stranger = False
|
||||||
|
while not rospy.is_shutdown() and whether_stranger == False:
|
||||||
|
data = rospy.wait_for_message("/mic/awake/angle", Int32, timeout=None)
|
||||||
|
print(data.data)
|
||||||
|
if data.data!=0:
|
||||||
|
angle_of_wakeup = data.data
|
||||||
|
whether_stranger = True;
|
||||||
|
break;
|
||||||
|
navigator = GoToPose()
|
||||||
|
|
||||||
|
# Customize the following values so they are appropriate for your location
|
||||||
|
position_door = {'x': 1.33, 'y' : 3.3}
|
||||||
|
# position_window = {'x' : -0.8, 'y' : -0.12}
|
||||||
|
quaternion = {'r1' : 0.000, 'r2' : 0.000, 'r3' : 0.000, 'r4' : 1.000}
|
||||||
|
|
||||||
|
rospy.loginfo("Go to (%s, %s) pose", position_door['x'], position_door['y'])
|
||||||
|
success = navigator.goto(position_door, quaternion)
|
||||||
|
|
||||||
|
# 发布小车是否到达的消息
|
||||||
|
pub = rospy.Publisher('whether_reach', Int32, queue_size=10)
|
||||||
|
if success:
|
||||||
|
rospy.loginfo("Hooray, reached the desired pose")
|
||||||
|
while not rospy.is_shutdown():
|
||||||
|
|
||||||
|
pub.publish(1)
|
||||||
|
rospy.loginfo('yes')
|
||||||
|
else:
|
||||||
|
rospy.loginfo("The base failed to reach the desired pose")
|
||||||
|
while not rospy.is_shutdown():
|
||||||
|
|
||||||
|
pub.publish(1)
|
||||||
|
rospy.loginfo('no')
|
||||||
|
|
||||||
|
# Sleep to give the last log messages time to be sent
|
||||||
|
|
||||||
|
rospy.sleep(1)
|
||||||
|
|
||||||
|
except rospy.ROSInterruptException:
|
||||||
|
rospy.loginfo("Ctrl-C caught. Quitting")
|
@ -0,0 +1,124 @@
|
|||||||
|
#!/usr/bin/env python
|
||||||
|
# -*- coding: UTF-8 -*-
|
||||||
|
# TurtleBot must have minimal.launch & amcl_demo.launch
|
||||||
|
# running prior to starting this script
|
||||||
|
# For simulation: launch gazebo world & amcl_demo prior to run this script
|
||||||
|
|
||||||
|
import rospy
|
||||||
|
from move_base_msgs.msg import MoveBaseAction, MoveBaseGoal
|
||||||
|
import actionlib
|
||||||
|
from actionlib_msgs.msg import *
|
||||||
|
from geometry_msgs.msg import Pose, Point, Quaternion
|
||||||
|
#定义消息的类型
|
||||||
|
from std_msgs.msg import Int32
|
||||||
|
from std_msgs.msg import String
|
||||||
|
import time
|
||||||
|
angle_of_wakeup = 0
|
||||||
|
# 回调函数
|
||||||
|
def callback(data):
|
||||||
|
angle_of_wakeup = data.data
|
||||||
|
rospy.loginfo(rospy.get_caller_id() + "I heard %d", data.data)
|
||||||
|
# 赋值角度
|
||||||
|
rospy.loginfo(rospy.get_caller_id() + "I heard angle: %d", angle_of_wakeup)
|
||||||
|
# 定义订阅者节点
|
||||||
|
def listener():
|
||||||
|
rospy.Subscriber("/mic/awake/angle", Int32, callback)
|
||||||
|
return True
|
||||||
|
|
||||||
|
class GoToPose():
|
||||||
|
|
||||||
|
def __init__(self):
|
||||||
|
self.goal_sent = False
|
||||||
|
|
||||||
|
# What to do if shut down (e.g. Ctrl-C or failure)
|
||||||
|
rospy.on_shutdown(self.shutdown)
|
||||||
|
|
||||||
|
# Tell the action client that we want to spin a thread by default
|
||||||
|
self.move_base = actionlib.SimpleActionClient("move_base", MoveBaseAction)
|
||||||
|
rospy.loginfo("Wait for the action server to come up")
|
||||||
|
|
||||||
|
# Allow up to 10 seconds for the action server to come up
|
||||||
|
self.move_base.wait_for_server(rospy.Duration(2))
|
||||||
|
|
||||||
|
def goto(self, pos, quat):
|
||||||
|
|
||||||
|
# Send a goal
|
||||||
|
self.goal_sent = True
|
||||||
|
goal = MoveBaseGoal()
|
||||||
|
goal.target_pose.header.frame_id = 'map'
|
||||||
|
goal.target_pose.header.stamp = rospy.Time.now()
|
||||||
|
goal.target_pose.pose = Pose(Point(pos['x'], pos['y'], 0.000),
|
||||||
|
Quaternion(quat['r1'], quat['r2'], quat['r3'], quat['r4']))
|
||||||
|
|
||||||
|
# Start moving
|
||||||
|
self.move_base.send_goal(goal)
|
||||||
|
|
||||||
|
# Allow TurtleBot up to 60 seconds to complete task
|
||||||
|
# Time to finish the navigation
|
||||||
|
# by lcp 2021/7/1
|
||||||
|
success = self.move_base.wait_for_result(rospy.Duration(60))
|
||||||
|
|
||||||
|
state = self.move_base.get_state()
|
||||||
|
result = False
|
||||||
|
|
||||||
|
if success and state == GoalStatus.SUCCEEDED:
|
||||||
|
# We made it!
|
||||||
|
result = True
|
||||||
|
else:
|
||||||
|
self.move_base.cancel_goal()
|
||||||
|
|
||||||
|
self.goal_sent = False
|
||||||
|
return result
|
||||||
|
|
||||||
|
def shutdown(self):
|
||||||
|
if self.goal_sent:
|
||||||
|
self.move_base.cancel_goal()
|
||||||
|
rospy.loginfo("Stop")
|
||||||
|
rospy.sleep(1)
|
||||||
|
|
||||||
|
if __name__ == '__main__':
|
||||||
|
|
||||||
|
try:
|
||||||
|
rospy.init_node('nav_test', anonymous=True)
|
||||||
|
#rospy.Subscriber("/mic/awake/angle", Int32, callback)
|
||||||
|
|
||||||
|
rospy.sleep(1)
|
||||||
|
whether_stranger = False
|
||||||
|
while not rospy.is_shutdown() and whether_stranger == False:
|
||||||
|
data = rospy.wait_for_message("/mic/awake/angle", Int32, timeout=None)
|
||||||
|
print(data.data)
|
||||||
|
if data.data!=0:
|
||||||
|
angle_of_wakeup = data.data
|
||||||
|
whether_stranger = True;
|
||||||
|
break;
|
||||||
|
navigator = GoToPose()
|
||||||
|
|
||||||
|
# Customize the following values so they are appropriate for your location
|
||||||
|
position_door = {'x': 1.33, 'y' : 3.3}
|
||||||
|
# position_window = {'x' : -0.8, 'y' : -0.12}
|
||||||
|
quaternion = {'r1' : 0.000, 'r2' : 0.000, 'r3' : 0.000, 'r4' : 1.000}
|
||||||
|
|
||||||
|
rospy.loginfo("Go to (%s, %s) pose", position_door['x'], position_door['y'])
|
||||||
|
success = navigator.goto(position_door, quaternion)
|
||||||
|
|
||||||
|
# 发布小车是否到达的消息
|
||||||
|
pub = rospy.Publisher('whether_reach', Int32, queue_size=10)
|
||||||
|
if success:
|
||||||
|
rospy.loginfo("Hooray, reached the desired pose")
|
||||||
|
while not rospy.is_shutdown():
|
||||||
|
|
||||||
|
pub.publish(1)
|
||||||
|
rospy.loginfo('yes')
|
||||||
|
else:
|
||||||
|
rospy.loginfo("The base failed to reach the desired pose")
|
||||||
|
while not rospy.is_shutdown():
|
||||||
|
|
||||||
|
pub.publish(0)
|
||||||
|
rospy.loginfo('no')
|
||||||
|
|
||||||
|
# Sleep to give the last log messages time to be sent
|
||||||
|
|
||||||
|
rospy.sleep(1)
|
||||||
|
|
||||||
|
except rospy.ROSInterruptException:
|
||||||
|
rospy.loginfo("Ctrl-C caught. Quitting")
|
@ -0,0 +1,6 @@
|
|||||||
|
#!/usr/bin/env python
|
||||||
|
# -*- coding: UTF-8 -*-
|
||||||
|
|
||||||
|
import os
|
||||||
|
|
||||||
|
os.system("conda run python ~/Desktop/voiceprint-linux/infer_contrast.py")
|
@ -0,0 +1,6 @@
|
|||||||
|
#!/usr/bin/env python
|
||||||
|
# -*- coding: UTF-8 -*-
|
||||||
|
|
||||||
|
import os
|
||||||
|
|
||||||
|
os.system("conda run -n base python ~/Desktop/voiceprint-linux/infer_contrast.py")
|
@ -0,0 +1,26 @@
|
|||||||
|
#!/usr/bin/env python
|
||||||
|
# -*- coding: UTF-8 -*-
|
||||||
|
|
||||||
|
import rospy
|
||||||
|
from std_msgs.msg import String
|
||||||
|
resultstr = "no"
|
||||||
|
def talker():
|
||||||
|
pub = rospy.Publisher('chatter', String, queue_size=10)
|
||||||
|
rospy.init_node('talker', anonymous=True)
|
||||||
|
rate = rospy.Rate(10) # 10hz
|
||||||
|
while not rospy.is_shutdown():
|
||||||
|
rospy.loginfo(resultstr)
|
||||||
|
pub.publish(resultstr)
|
||||||
|
rate.sleep()
|
||||||
|
|
||||||
|
if __name__ == '__main__':
|
||||||
|
try:
|
||||||
|
# 读取结果
|
||||||
|
fresult = open("/home/turtlebot/myresult/result.txt")
|
||||||
|
resultstr = fresult.read(20)
|
||||||
|
talker()
|
||||||
|
print(resultstr)
|
||||||
|
fresult.close()
|
||||||
|
except rospy.ROSInterruptException:
|
||||||
|
pass
|
||||||
|
|
@ -0,0 +1,27 @@
|
|||||||
|
#!/usr/bin/env python
|
||||||
|
# -*- coding: UTF-8 -*-
|
||||||
|
|
||||||
|
import rospy
|
||||||
|
from std_msgs.msg import String
|
||||||
|
|
||||||
|
resultstr = "no"
|
||||||
|
def talker():
|
||||||
|
pub = rospy.Publisher('chatter', String, queue_size=10)
|
||||||
|
rospy.init_node('talker', anonymous=True)
|
||||||
|
rate = rospy.Rate(10) # 10hz
|
||||||
|
while not rospy.is_shutdown():
|
||||||
|
rospy.loginfo(resultstr)
|
||||||
|
pub.publish(resultstr)
|
||||||
|
rate.sleep()
|
||||||
|
|
||||||
|
if __name__ == '__main__':
|
||||||
|
try:
|
||||||
|
# 读取结果
|
||||||
|
fresult = open("/home/turtlebot/myresult/result.txt")
|
||||||
|
resultstr = fresult.read(20)
|
||||||
|
talker()
|
||||||
|
print(resultstr)
|
||||||
|
fresult.close()
|
||||||
|
except rospy.ROSInterruptException:
|
||||||
|
pass
|
||||||
|
|
@ -0,0 +1,56 @@
|
|||||||
|
#include <user_interface.h>
|
||||||
|
#include <string>
|
||||||
|
#include <locale>
|
||||||
|
#include <codecvt>
|
||||||
|
#include <ctime>
|
||||||
|
#include <time.h>
|
||||||
|
#include <ros/ros.h>
|
||||||
|
#include <std_msgs/String.h>
|
||||||
|
#include <xf_mic_asr_offline/Get_Offline_Result_srv.h>
|
||||||
|
#include <xf_mic_asr_offline/Set_Major_Mic_srv.h>
|
||||||
|
#include <xf_mic_asr_offline/Set_Led_On_srv.h>
|
||||||
|
#include <xf_mic_asr_offline/Get_Major_Mic_srv.h>
|
||||||
|
#include <xf_mic_asr_offline/Pcm_Msg.h>
|
||||||
|
#include <xf_mic_asr_offline/Start_Record_srv.h>
|
||||||
|
#include <xf_mic_asr_offline/Set_Awake_Word_srv.h>
|
||||||
|
#include <xf_mic_asr_offline/Get_Awake_Angle_srv.h>
|
||||||
|
#include <std_msgs/Int8.h>
|
||||||
|
#include <std_msgs/Int32.h>
|
||||||
|
#include <sys/stat.h>
|
||||||
|
bool record_symbol = false;
|
||||||
|
void chatterCallback(const std_msgs::Int32::ConstPtr& msg)
|
||||||
|
{
|
||||||
|
ROS_INFO("I heard: [%d]", msg->data);
|
||||||
|
record_symbol = msg->data;
|
||||||
|
}
|
||||||
|
|
||||||
|
int main(int argc, char **argv)
|
||||||
|
{
|
||||||
|
|
||||||
|
ros::init(argc, argv, "start");
|
||||||
|
|
||||||
|
ros::NodeHandle n;
|
||||||
|
ros::Subscriber sub = n.subscribe("whether_reach", 1, chatterCallback);
|
||||||
|
|
||||||
|
ros::spin();
|
||||||
|
|
||||||
|
//删除原有的音频
|
||||||
|
system("rm ~/catkin_ws/src/xf_mic_asr_offline/audio/vvui_deno.pcm");
|
||||||
|
if (record_symbol){
|
||||||
|
//开始录音
|
||||||
|
int symbol_of_start = start_to_record_denoised_sound();
|
||||||
|
//录音10s
|
||||||
|
sleep(10);
|
||||||
|
//停止录音
|
||||||
|
int symbol_of_stop = finish_to_record_denoised_sound();
|
||||||
|
}
|
||||||
|
//修改音频格式
|
||||||
|
system("python ~/catkin_ws/src/xf_mic_asr_offline/audio/change.py");
|
||||||
|
ros::waitForShutdown();
|
||||||
|
//sleep(2);
|
||||||
|
system("python3 /home/turtlebot/mymodel/voiceprint/infer_contrast.py");
|
||||||
|
printf("over!");
|
||||||
|
//关闭麦克风
|
||||||
|
hid_close();
|
||||||
|
return 0;
|
||||||
|
}
|
File diff suppressed because it is too large
Load Diff
Loading…
Reference in new issue