Commit 1c43be4c authored by yoda's avatar yoda

added files from socrob_at_home and merged its webconsole

parent 95cd1f46
#! /usr/bin/env python
import subprocess
NODE_NAME = 'speech'
import roslib; roslib.load_manifest(NODE_NAME)
import rospy
from std_msgs.msg import *
from scout_msgs.srv import *
def speak(data):
subprocess.call("espeak '%s'"%(data), shell=True)
def speak_german(data):
subprocess.call("espeak -s 150 -v de-de '%s'"%(data), shell=True)
def speech_handler(msg):
speak(msg.data)
rospy.loginfo("Saying: "+msg.data)
def speech_german_handler(msg):
speak_german(msg.data)
rospy.loginfo("Saying: "+msg.data)
def speech_service(req):
speak(req.data)
rospy.loginfo("Said: "+req.data)
return SpeechSrvResponse(True)
def speech_service_german(req):
speak_german(req.data)
rospy.loginfo("Said: "+req.data)
return SpeechSrvResponse(True)
def main():
rospy.init_node(NODE_NAME)
rospy.Subscriber("speech", String, speech_handler, queue_size=1)
rospy.Subscriber("speech_german", String, speech_german_handler, queue_size=1)
rospy.Service("speech", SpeechSrv, speech_service)
rospy.Service("speech_german", SpeechSrv, speech_service_german)
rospy.loginfo("Speech node (BLOCKING) ready")
rospy.spin()
if __name__=="__main__":
main()
# EOF
#! /usr/bin/env python
import subprocess
NODE_NAME = 'speech'
import roslib; roslib.load_manifest(NODE_NAME)
import rospy
from std_msgs.msg import *
from scout_msgs.srv import *
def speak(data):
subprocess.call("echo '%s' | festival --tts"%(data), shell=True)
def speech_handler(msg):
speak(msg.data)
rospy.loginfo("Saying: "+msg.data)
def speech_service(req):
speak(req.data)
rospy.loginfo("Said: "+req.data)
return SpeechSrvResponse(True)
def main():
rospy.init_node(NODE_NAME)
rospy.Subscriber("speech", String, speech_handler, queue_size=1)
rospy.Service("speech", SpeechSrv, speech_service)
rospy.loginfo("Speech node (BLOCKING) ready")
rospy.spin()
if __name__=="__main__":
main()
# EOF
......@@ -41,6 +41,7 @@ ROOT_PATH = osp.dirname(osp.realpath(__file__))
STATIC_PATH = osp.join(ROOT_PATH, "static")
DEFAULT_HOME = "home_scout.html"
DEFAULT_CAMERA = "/stream?topic=/camera/image_raw"
DEFAULT_CAMPORT = None
CURRENT_MAP = None
......@@ -93,7 +94,7 @@ class Server(BaseHTTPRequestHandler):
stat = os.stat(fn)
with open(fn) as fh:
self.send_response(200)
self.send_header("Content-type", ctype)
self.send_header("Content-type", ctype[0])
self.send_header("Content-Length", str(stat[6]))
self.end_headers()
if method=='GET':
......@@ -160,6 +161,12 @@ class Server(BaseHTTPRequestHandler):
if method=='GET':
print >>self.wfile, res
def handle_cmd(self, method, args):
self.header("text/plain")
(suc, res) = proxy.send_cmd(args)
if method=='GET':
print >>self.wfile, res
# Keep this to the end of class definition
......@@ -172,7 +179,9 @@ class Server(BaseHTTPRequestHandler):
('set_location', handle_set_location),
('set_dct_goal', handle_set_dct_goal),
('set_route_goal', handle_set_route_goal),
('teleop', handle_teleop))
('teleop', handle_teleop),
('cmd', handle_cmd),
)
......@@ -187,14 +196,18 @@ class Proxy:
temperature = None
def __init__(self):
rospy.init_node(PKG_NAME, argv=sys.argv)
global CURRENT_MAP
rospy.init_node(NODE_NAME, argv=sys.argv)
global DEFAULT_MAP
global DEFAULT_HOME
global DEFAULT_CAMERA
global DEFAULT_CAMPORT
DEFAULT_HOME = rospy.get_param("~home", DEFAULT_HOME)
rospy.loginfo("home: %s"%(DEFAULT_HOME))
DEFAULT_CAMERA = rospy.get_param("~camera", DEFAULT_CAMERA)
rospy.loginfo("camera: %s"%(DEFAULT_CAMERA))
DEFAULT_CAMPORT = rospy.get_param("~camport", DEFAULT_CAMPORT)
if DEFAULT_CAMPORT is not None:
rospy.loginfo("camport: %s"%(DEFAULT_CAMPORT))
mapfile = rospy.get_param("navmap", rospy.get_param("map"))
rospy.loginfo("map: %s"%(mapfile))
CURRENT_MAP = mapfile
......@@ -208,6 +221,7 @@ class Proxy:
self.guid_srv = rospy.ServiceProxy("scout/guidance", GuidanceSrv)
self.teleop_srv = rospy.ServiceProxy("scout/teleop", TeleOpSrv)
self.speech_srv = rospy.ServiceProxy("speech", SpeechSrv)
self.cmd_pub = rospy.Publisher("webconsole/cmd", String)
#rospy.Subscriber("/tf", tfMessage, self.tf_handler, queue_size=1)
rospy.Subscriber("scan", LaserScan, self.lidar_handler, queue_size=1)
rospy.Subscriber("particlecloud", PoseArray, self.particlecloud_handler, queue_size=1)
......@@ -318,6 +332,10 @@ class Proxy:
except rospy.ServiceException:
return (False, "Teleoperation service unavailable")
def send_cmd(self, args):
self.cmd_pub.publish(String(args[0]))
return (True, "Done")
# tf_failed = False
# def tf_handler(self, msg):
......@@ -475,7 +493,10 @@ class Proxy:
xml += '<battery>%s</battery>\n'%(su.escape(self.battery))
if self.voltage is not None:
xml += '<voltage>%s</voltage>\n'%(su.escape(self.voltage))
xml += '<camera>%s</camera>\n'%(su.escape(DEFAULT_CAMERA))
if DEFAULT_CAMPORT is None:
xml += '<camera>%s</camera>\n'%(su.escape(DEFAULT_CAMERA))
else:
xml += '<camera port="%s">%s</camera>\n'%(su.escape(DEFAULT_CAMPORT),su.escape(DEFAULT_CAMERA))
maps = self.available_maps()
mapname = self.get_map_name(CURRENT_MAP)
xml += '<maps current="%s">%s</maps>\n'%(su.escape(mapname), ''.join(['<m id="%s">%s</m>'%(su.escape(m),su.escape(m)) for m in maps]))
......
<!DOCTYPE HTML PUBLIC "-//IETF//DTD HTML//EN">
<html>
<head>
<title>SocRob@home web remote</title>
<link rel="stylesheet" type="text/css" href="main.css"/>
<!--script src="/static/jquery.js" type="text/javascript"></script-->
<!-- script src="/static/console.js" type="text/javascript"></script -->
<STYLE type="text/css">
A.button {
background: yellow;
font-size: 500%;
font-style: normal;
padding: 10px;
margin: 30px;
}
</STYLE>
</head>
<body>
<div class="header">
<span class="pagetitle">
SocRob@home web console
</span>
</div>
<br/>
<div>
<a href="/do/cmd?call" class="button">Call Mordomo</a>
<br/><br/>
</div>
<div class="footer">
(C) 2015 SocRob@home, Instituto Superior Tecnico
</div>
</body>
</html>
Markdown is supported
0%
or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment