|
From: <wgh...@us...> - 2009-09-04 00:47:17
|
Revision: 23800
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23800&view=rev
Author: wghassan
Date: 2009-09-04 00:47:08 +0000 (Fri, 04 Sep 2009)
Log Message:
-----------
reorg
Added Paths:
-----------
pkg/trunk/sandbox/web/sample_application/src/sample_application/cgibin/
pkg/trunk/sandbox/web/sample_application/src/sample_application/images/
pkg/trunk/sandbox/web/sample_application/src/sample_application/jslib/
pkg/trunk/sandbox/web/sample_application/src/sample_application/listener
pkg/trunk/sandbox/web/sample_application/src/sample_application/listener.py
pkg/trunk/sandbox/web/sample_application/src/sample_application/talker
pkg/trunk/sandbox/web/sample_application/src/sample_application/talker.py
pkg/trunk/sandbox/web/sample_application/src/sample_application/templates/
pkg/trunk/sandbox/web/sample_application/webhandler.py
Removed Paths:
-------------
pkg/trunk/sandbox/web/sample_application/README
pkg/trunk/sandbox/web/sample_application/cgibin/
pkg/trunk/sandbox/web/sample_application/images/
pkg/trunk/sandbox/web/sample_application/jslib/
pkg/trunk/sandbox/web/sample_application/listener
pkg/trunk/sandbox/web/sample_application/listener.py
pkg/trunk/sandbox/web/sample_application/talker
pkg/trunk/sandbox/web/sample_application/talker.py
pkg/trunk/sandbox/web/sample_application/templates/
Deleted: pkg/trunk/sandbox/web/sample_application/README
===================================================================
--- pkg/trunk/sandbox/web/sample_application/README 2009-09-04 00:46:13 UTC (rev 23799)
+++ pkg/trunk/sandbox/web/sample_application/README 2009-09-04 00:47:08 UTC (rev 23800)
@@ -1,3 +0,0 @@
-This is the simplest rospy demo: a talker node that publishes
-std_msgs/String to the /chatter topic and a listener node that subscribes
-to these messages.
Deleted: pkg/trunk/sandbox/web/sample_application/listener
===================================================================
--- pkg/trunk/sandbox/web/sample_application/listener 2009-09-04 00:46:13 UTC (rev 23799)
+++ pkg/trunk/sandbox/web/sample_application/listener 2009-09-04 00:47:08 UTC (rev 23800)
@@ -1 +0,0 @@
-link listener.py
\ No newline at end of file
Deleted: pkg/trunk/sandbox/web/sample_application/listener.py
===================================================================
--- pkg/trunk/sandbox/web/sample_application/listener.py 2009-09-04 00:46:13 UTC (rev 23799)
+++ pkg/trunk/sandbox/web/sample_application/listener.py 2009-09-04 00:47:08 UTC (rev 23800)
@@ -1,63 +0,0 @@
-#!/usr/bin/env python
-# Software License Agreement (BSD License)
-#
-# Copyright (c) 2008, Willow Garage, Inc.
-# All rights reserved.
-#
-# Redistribution and use in source and binary forms, with or without
-# modification, are permitted provided that the following conditions
-# are met:
-#
-# * Redistributions of source code must retain the above copyright
-# notice, this list of conditions and the following disclaimer.
-# * Redistributions in binary form must reproduce the above
-# copyright notice, this list of conditions and the following
-# disclaimer in the documentation and/or other materials provided
-# with the distribution.
-# * Neither the name of Willow Garage, Inc. nor the names of its
-# contributors may be used to endorse or promote products derived
-# from this software without specific prior written permission.
-#
-# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
-# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
-# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-# POSSIBILITY OF SUCH DAMAGE.
-#
-# Revision $Id: listener.py 5263 2009-07-17 23:30:38Z sfkwc $
-
-## Simple talker demo that listens to std_msgs/Strings published
-## to the 'chatter' topic
-
-PKG = 'rospy_tutorials' # this package name
-import roslib; roslib.load_manifest(PKG)
-
-import rospy
-from std_msgs.msg import String
-
-def callback(data):
- rospy.loginfo(rospy.get_caller_id()+"I heard %s",data.data)
-
-def listener():
-
- # in ROS, nodes are unique named. If two nodes with the same
- # node are launched, the previous one is kicked off. The
- # anonymous=True flag means that rospy will choose a unique
- # name for our 'talker' node so that multiple talkers can
- # run simultaenously.
- rospy.init_node('listener', anonymous=True)
-
- rospy.Subscriber("chatter", String, callback)
-
- # spin() simply keeps python from exiting until this node is stopped
- rospy.spin()
-
-if __name__ == '__main__':
- listener()
Property changes on: pkg/trunk/sandbox/web/sample_application/src/sample_application/cgibin
___________________________________________________________________
Added: svn:mergeinfo
+
Property changes on: pkg/trunk/sandbox/web/sample_application/src/sample_application/images
___________________________________________________________________
Added: svn:mergeinfo
+
Property changes on: pkg/trunk/sandbox/web/sample_application/src/sample_application/jslib
___________________________________________________________________
Added: svn:mergeinfo
+
Added: pkg/trunk/sandbox/web/sample_application/src/sample_application/listener
===================================================================
--- pkg/trunk/sandbox/web/sample_application/src/sample_application/listener (rev 0)
+++ pkg/trunk/sandbox/web/sample_application/src/sample_application/listener 2009-09-04 00:47:08 UTC (rev 23800)
@@ -0,0 +1 @@
+link listener.py
\ No newline at end of file
Property changes on: pkg/trunk/sandbox/web/sample_application/src/sample_application/listener
___________________________________________________________________
Added: svn:special
+ *
Added: pkg/trunk/sandbox/web/sample_application/src/sample_application/listener.py
===================================================================
--- pkg/trunk/sandbox/web/sample_application/src/sample_application/listener.py (rev 0)
+++ pkg/trunk/sandbox/web/sample_application/src/sample_application/listener.py 2009-09-04 00:47:08 UTC (rev 23800)
@@ -0,0 +1,63 @@
+#!/usr/bin/env python
+# Software License Agreement (BSD License)
+#
+# Copyright (c) 2008, Willow Garage, Inc.
+# All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# * Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# * Redistributions in binary form must reproduce the above
+# copyright notice, this list of conditions and the following
+# disclaimer in the documentation and/or other materials provided
+# with the distribution.
+# * Neither the name of Willow Garage, Inc. nor the names of its
+# contributors may be used to endorse or promote products derived
+# from this software without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+# Revision $Id: listener.py 5263 2009-07-17 23:30:38Z sfkwc $
+
+## Simple talker demo that listens to std_msgs/Strings published
+## to the 'chatter' topic
+
+PKG = 'rospy_tutorials' # this package name
+import roslib; roslib.load_manifest(PKG)
+
+import rospy
+from std_msgs.msg import String
+
+def callback(data):
+ rospy.loginfo(rospy.get_caller_id()+"I heard %s",data.data)
+
+def listener():
+
+ # in ROS, nodes are unique named. If two nodes with the same
+ # node are launched, the previous one is kicked off. The
+ # anonymous=True flag means that rospy will choose a unique
+ # name for our 'talker' node so that multiple talkers can
+ # run simultaenously.
+ rospy.init_node('listener', anonymous=True)
+
+ rospy.Subscriber("chatter", String, callback)
+
+ # spin() simply keeps python from exiting until this node is stopped
+ rospy.spin()
+
+if __name__ == '__main__':
+ listener()
Property changes on: pkg/trunk/sandbox/web/sample_application/src/sample_application/listener.py
___________________________________________________________________
Added: svn:executable
+ *
Added: pkg/trunk/sandbox/web/sample_application/src/sample_application/talker
===================================================================
--- pkg/trunk/sandbox/web/sample_application/src/sample_application/talker (rev 0)
+++ pkg/trunk/sandbox/web/sample_application/src/sample_application/talker 2009-09-04 00:47:08 UTC (rev 23800)
@@ -0,0 +1 @@
+link talker.py
\ No newline at end of file
Property changes on: pkg/trunk/sandbox/web/sample_application/src/sample_application/talker
___________________________________________________________________
Added: svn:special
+ *
Added: pkg/trunk/sandbox/web/sample_application/src/sample_application/talker.py
===================================================================
--- pkg/trunk/sandbox/web/sample_application/src/sample_application/talker.py (rev 0)
+++ pkg/trunk/sandbox/web/sample_application/src/sample_application/talker.py 2009-09-04 00:47:08 UTC (rev 23800)
@@ -0,0 +1,57 @@
+#!/usr/bin/env python
+# Software License Agreement (BSD License)
+#
+# Copyright (c) 2008, Willow Garage, Inc.
+# All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# * Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# * Redistributions in binary form must reproduce the above
+# copyright notice, this list of conditions and the following
+# disclaimer in the documentation and/or other materials provided
+# with the distribution.
+# * Neither the name of Willow Garage, Inc. nor the names of its
+# contributors may be used to endorse or promote products derived
+# from this software without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+# Revision $Id: talker.py 5263 2009-07-17 23:30:38Z sfkwc $
+
+## Simple talker demo that published std_msgs/Strings messages
+## to the 'chatter' topic
+
+import roslib; roslib.load_manifest('rospy_tutorials')
+
+import rospy
+from std_msgs.msg import String
+
+def talker():
+ pub = rospy.Publisher('chatter', String)
+ rospy.init_node('talker', anonymous=True)
+ r = rospy.Rate(1) # 10hz
+ while not rospy.is_shutdown():
+ str = "hello world %s"%rospy.get_time()
+ rospy.loginfo(str)
+ pub.publish(str)
+ r.sleep()
+
+if __name__ == '__main__':
+ try:
+ talker()
+ except rospy.ROSInterruptException: pass
Property changes on: pkg/trunk/sandbox/web/sample_application/src/sample_application/talker.py
___________________________________________________________________
Added: svn:executable
+ *
Property changes on: pkg/trunk/sandbox/web/sample_application/src/sample_application/templates
___________________________________________________________________
Added: svn:mergeinfo
+
Deleted: pkg/trunk/sandbox/web/sample_application/talker
===================================================================
--- pkg/trunk/sandbox/web/sample_application/talker 2009-09-04 00:46:13 UTC (rev 23799)
+++ pkg/trunk/sandbox/web/sample_application/talker 2009-09-04 00:47:08 UTC (rev 23800)
@@ -1 +0,0 @@
-link talker.py
\ No newline at end of file
Deleted: pkg/trunk/sandbox/web/sample_application/talker.py
===================================================================
--- pkg/trunk/sandbox/web/sample_application/talker.py 2009-09-04 00:46:13 UTC (rev 23799)
+++ pkg/trunk/sandbox/web/sample_application/talker.py 2009-09-04 00:47:08 UTC (rev 23800)
@@ -1,57 +0,0 @@
-#!/usr/bin/env python
-# Software License Agreement (BSD License)
-#
-# Copyright (c) 2008, Willow Garage, Inc.
-# All rights reserved.
-#
-# Redistribution and use in source and binary forms, with or without
-# modification, are permitted provided that the following conditions
-# are met:
-#
-# * Redistributions of source code must retain the above copyright
-# notice, this list of conditions and the following disclaimer.
-# * Redistributions in binary form must reproduce the above
-# copyright notice, this list of conditions and the following
-# disclaimer in the documentation and/or other materials provided
-# with the distribution.
-# * Neither the name of Willow Garage, Inc. nor the names of its
-# contributors may be used to endorse or promote products derived
-# from this software without specific prior written permission.
-#
-# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
-# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
-# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-# POSSIBILITY OF SUCH DAMAGE.
-#
-# Revision $Id: talker.py 5263 2009-07-17 23:30:38Z sfkwc $
-
-## Simple talker demo that published std_msgs/Strings messages
-## to the 'chatter' topic
-
-import roslib; roslib.load_manifest('rospy_tutorials')
-
-import rospy
-from std_msgs.msg import String
-
-def talker():
- pub = rospy.Publisher('chatter', String)
- rospy.init_node('talker', anonymous=True)
- r = rospy.Rate(1) # 10hz
- while not rospy.is_shutdown():
- str = "hello world %s"%rospy.get_time()
- rospy.loginfo(str)
- pub.publish(str)
- r.sleep()
-
-if __name__ == '__main__':
- try:
- talker()
- except rospy.ROSInterruptException: pass
Added: pkg/trunk/sandbox/web/sample_application/webhandler.py
===================================================================
--- pkg/trunk/sandbox/web/sample_application/webhandler.py (rev 0)
+++ pkg/trunk/sandbox/web/sample_application/webhandler.py 2009-09-04 00:47:08 UTC (rev 23800)
@@ -0,0 +1,15 @@
+#! /usr/bin/env python
+
+import rosweb
+from std_msgs.msg import String
+
+def config_plugin(context):
+ context.register_subtopic("/chatter:more", UpperChatterSubtopic)
+
+class UpperChatterSubtopic(rosweb.ROSWebSubTopic):
+ def __init__(self, topic, factory, main_rwt):
+ rosweb.ROSWebSubTopic.__init__(self, topic, factory, main_rwt)
+
+ def transform(self, msg):
+ newmsg = String(msg.data.upper())
+ return newmsg
Property changes on: pkg/trunk/sandbox/web/sample_application/webhandler.py
___________________________________________________________________
Added: svn:executable
+ *
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|