master
parent
42ece29ffd
commit
c295bd09be
Binary file not shown.
Binary file not shown.
@ -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;
|
||||
}
|
File diff suppressed because it is too large
Load Diff
Loading…
Reference in new issue