master
Logical 4 years ago
parent 42ece29ffd
commit c295bd09be

@ -1,124 +0,0 @@
#!/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")

@ -1,6 +0,0 @@
#!/usr/bin/env python
# -*- coding: UTF-8 -*-
import os
os.system("conda run -n base python ~/Desktop/voiceprint-linux/infer_contrast.py")

@ -1,27 +0,0 @@
#!/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

@ -1,56 +0,0 @@
#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;
}

@ -1,289 +0,0 @@
#include <ros/ros.h>
#include <user_interface.h>
#include "hidapi.h"
#include <unistd.h>
#include <signal.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 <string.h>
#include <cmath>
#include <iostream>
#include <std_msgs/Int32.h>
#include <std_msgs/Int8.h>
#include <geometry_msgs/PoseWithCovarianceStamped.h>
#include <string>
#include <locale>
#include <codecvt>
#include <std_msgs/Int8.h>
#include <std_msgs/Int32.h>
#include <sys/stat.h>
double orientation_z;
double orientation_w;
double direction_r;
double direction;
double angle = 0; //语音唤醒角度
double last_direction = 0;
int awake_flag = 0; //唤醒标志位
int last_mic=0; //主麦编号历史值
int nav_reach = 0; //小车是否到达指定的导航地点
ros::ServiceClient Set_Major_Mic_client; //定义设置主麦服务的客户端
ros::Publisher current_angle_pub; //定义当前小车的相对唤醒角度
/**************************************************************************
sub
awake_angle voice_control.cpp
**************************************************************************/
void angle_Callback(std_msgs::Int32 msg)
{
angle = msg.data;
if(angle>=30 && angle<=90) //判断唤醒时主麦方向
last_mic = 1;
else if(angle>=90 && angle<=150)
last_mic = 2;
else if(angle>=150 && angle<=210)
last_mic = 3;
else if(angle>=210 && angle<=270)
last_mic = 4;
else if(angle>=270 && angle<=330)
last_mic = 5;
else
last_mic = 0;
printf("last_mic_init = %d-----\n",last_mic);
}
/**************************************************************************
sub
awake_flag_msg voice_control.cpp
**************************************************************************/
void awake_flag_Callback(std_msgs::Int8 msg)
{
last_direction = direction;
awake_flag = msg.data;
printf("awake_flag = %d\n",awake_flag);
}
/***
nav_reach
'whether_reach' Int8
***/
void reach_Callback(std_msgs::Int32 msg)
{
nav_reach = msg.data;
printf("nav_reach = %d\n",nav_reach);
}
/**************************************************************************
姿sub
Pose turn_on_wheeltec_robot.launch
**************************************************************************/
void pose_callback(const geometry_msgs::PoseWithCovarianceStamped& msg)
{
orientation_z = msg.pose.pose.orientation.z; //获取最新的里程计方位值
orientation_w = msg.pose.pose.orientation.w;
printf("z = %f-----\n",orientation_z);
printf("w = %f-----\n",orientation_w);
direction_r = atan2(2*(orientation_w*orientation_z),1-2*(pow(orientation_z,2.0)));
direction = direction_r*180/3.1415926;
if(direction<0)
{direction+=360;}
if(awake_flag) //若在唤醒状态则进入主麦刷新检测
{
//printf("direction = %f-----\n",direction);
double dire_error = direction-last_direction; //计算方向误差值,弧度制换算成角度制
//printf("dire_error = %f-----\n",dire_error);
angle+=dire_error; //唤醒角度根据小车转向角度更新
//printf("angle = %f-----\n",angle);
last_direction = direction; //当前方向替换成历史方向
if(angle > 360) //处理angle大于360或小于0 的情况
angle-=360;
else if(angle < 0)
angle+=360;
/*******定义当前小车相对唤醒角度话题信息*******/
std_msgs::Int32 current_angle_msg;
current_angle_msg.data = int(angle);
current_angle_pub.publish(current_angle_msg); //发布话题,用于小车寻找声源
/********定义设置主麦服务客户端信息******/
xf_mic_asr_offline::Set_Major_Mic_srv num;
if(angle>=30 && angle<=90) //根据角度设定主麦方向
num.request.mic_id = 1;
else if(angle>=90 && angle<=150)
num.request.mic_id = 2;
else if(angle>=150 && angle<=210)
num.request.mic_id = 3;
else if(angle>=210 && angle<=270)
num.request.mic_id = 4;
else if(angle>=270 && angle<=330)
num.request.mic_id = 5;
else
num.request.mic_id = 0;
if(last_mic != num.request.mic_id) //若计算当前主麦值与历史值不等,则重新刷新主麦编号
{
Set_Major_Mic_client.call(num);
last_mic = num.request.mic_id;
}
}
}
/***
***/
bool Record_Start(xf_mic_asr_offline::Start_Record_srv::Request &req, xf_mic_asr_offline::Start_Record_srv::Response &res)
{
if (req.whether_start == 1)
{
ROS_INFO("got topic request,start to record ...\n");
int ret1 = start_to_record_denoised_sound();
if (ret1 == 0)
{
res.result = "ok";
res.fail_reason = "";
}
else
{
res.result = "fail";
res.fail_reason = "mic_did_not_open_error";
}
}
else if (req.whether_start == 0)
{
ROS_INFO("got topic request,stop to record ...\n");
int ret2 = finish_to_record_denoised_sound();
if (ret2 == 0)
{
res.result = "ok";
res.fail_reason = "";
}
else
{
res.result = "fail";
res.fail_reason = "mic_did_not_open_error";
}
}
return true;
}
/**************************************************************************
**************************************************************************/
int main(int argc, char** argv)
{
ros::init(argc, argv, "ref_mic"); //初始化ROS节点
ros::NodeHandle node; //创建句柄
/***创建当前唤醒角度话题发布者***/
current_angle_pub = node.advertise<std_msgs::Int32>("current_angle",1);
/***创建唤醒角度话题订阅者***/
ros::Subscriber angle_sub = node.subscribe("/mic/awake/angle", 1, angle_Callback);
/***创建唤醒标志位话题订阅者***/
ros::Subscriber awake_flag_sub = node.subscribe("awake_flag", 1, awake_flag_Callback);
/***创建小车姿态话题订阅者***/
ros::Subscriber pose_sub = node.subscribe("/robot_pose_ekf/odom_combined",1,pose_callback);
/***创建设置主麦服务客户端***/
Set_Major_Mic_client = node.serviceClient<xf_mic_asr_offline::Set_Major_Mic_srv>("xf_asr_offline_node/set_major_mic_srv");
/*srv 接收请求开启录音或关闭录音*/
ros::ServiceServer service_record_start = node.advertiseService("start_record_srv", Record_Start);
/**定义小车是否到达导航位置的订阅者**/
ros::Subscriber reach_sub = node.subscribe("whether_reach", 1, reach_Callback);
double rate2 = 5; //刷新频率5Hz
ros::Rate loopRate2(rate2);
/**
hid_device *handle = NULL;
//开启麦克风设备
handle = hid_open();
if (!handle)
{
printf(">>>>>无法打开麦克风设备,尝试重新连接进行测试\n");
return -1;
}
printf(">>>>>成功打开麦克风设备\n");
protocol_proc_init(send_to_usb_device, recv_from_usb_device, business_proc_callback, err_proc);
//获取麦克风状态,是否正常工作
get_system_status();
*/
while(ros::ok())
{
ros::spinOnce();
loopRate2.sleep();
if(nav_reach){
//删除原音频,如果不删除,音频只会叠加不会重置
system("rm /home/turtlebot/catkin_ws/src/xf_mic_asr_offline/audio/vvui_deno.pcm");
//拍照
system("python /home/turtlebot/catkin_ws/src/xf_mic_asr_offline/scripts/get_photo.py");
//将该照片移动到前端
system("cp -r /home/turtlebot/catkin_ws/src/xf_mic_asr_offline/scripts/get_photo.py /home/turtlebot/Desktop/voiceproject-linux-2/media");
//开始录音
system("rosservice call xf_asr_offline_node/start_record_srv 1");
//录音5s
sleep(5);
//结束录音
system("rosservice call xf_asr_offline_node/start_record_srv 0");
//修改音频格式 pcm~wav
system("python /home/turtlebot/catkin_ws/src/xf_mic_asr_offline/audio/change.py");
printf("成功转换格式!\n");
//调用模型
//system("python /home/turtlebot/catkin_ws/src/xf_mic_asr_offline/scripts/model.py");
system("conda run -n base python /home/turtlebot/Desktop/voiceprint-linux/infer_contrast.py");
printf("成功调用模型!\n");
//调用发布节点
system("python /home/turtlebot/catkin_ws/src/xf_mic_asr_offline/scripts/pubresult.py");
break;
}
//ros::spin();
}
return 0;
}

File diff suppressed because it is too large Load Diff
Loading…
Cancel
Save