|
From: <sf...@us...> - 2009-01-28 08:28:24
|
Revision: 10360
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=10360&view=rev
Author: sfkwc
Date: 2009-01-28 08:28:15 +0000 (Wed, 28 Jan 2009)
Log Message:
-----------
replace rospy.ready calls with rospy.init_node
Modified Paths:
--------------
pkg/trunk/demos/2dnav_pr2/pose_listen.py
pkg/trunk/drivers/robot/pr2/ocean_battery_driver/scripts/view_batteries
pkg/trunk/drivers/robot/pr2/pr2_power_board/scripts/view_power
pkg/trunk/hardware_test/runtime_monitor/scripts/log_runtime_messages
pkg/trunk/hardware_test/runtime_monitor/scripts/monitor
pkg/trunk/hardware_test/runtime_monitor/scripts/runtime_test
pkg/trunk/hardware_test/runtime_monitor/scripts/test_high_level
pkg/trunk/hardware_test/runtime_monitor/scripts/wxmonitor.py
pkg/trunk/hardware_test/runtime_monitor/testmonitor.py
pkg/trunk/mechanism/mechanism_control/scripts/detect.py
pkg/trunk/mechanism/mechanism_control/scripts/listen.py
pkg/trunk/mechanism/mechanism_control/scripts/writer.py
pkg/trunk/mechanism/mechanism_control/test/listenerpublisher_ms.py
pkg/trunk/mechanism/mechanism_control/test/test_ms.py
pkg/trunk/mechanism/mechanism_control/test/test_ms_cpp.py
pkg/trunk/nav/trajectory_rollout/scripts/listen.py
pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_prototype1/motor_monitor.py
pkg/trunk/simulators/simulator_integration_tests/world_3d_map_gazebo_tests/testcloud.py
pkg/trunk/util/ntp_monitor/ntp_monitor.py
pkg/trunk/vision/visual_odometry/nodes/camview_py.py
pkg/trunk/vision/visual_odometry/nodes/corrector.py
pkg/trunk/vision/visual_odometry/nodes/lineperf.py
pkg/trunk/vision/visual_odometry/nodes/vo.py
pkg/trunk/visualization/pr2_gui/src/pr2_gui/pr2_frame.py
pkg/trunk/visualization/wxpy_ros/tests/test_try.py
pkg/trunk/world_models/static_map_server/nodes/map_server
Modified: pkg/trunk/demos/2dnav_pr2/pose_listen.py
===================================================================
--- pkg/trunk/demos/2dnav_pr2/pose_listen.py 2009-01-28 08:14:01 UTC (rev 10359)
+++ pkg/trunk/demos/2dnav_pr2/pose_listen.py 2009-01-28 08:28:15 UTC (rev 10360)
@@ -16,7 +16,7 @@
def pose_listen():
rospy.TopicSub("/odom", RobotBase2DOdom, odom_callback)
rospy.TopicSub("/localizedpose", RobotBase2DOdom, localized_callback)
- rospy.ready(NAME, anonymous=True)
+ rospy.init_node(NAME, anonymous=True)
rospy.spin()
if __name__ == '__main__':
Modified: pkg/trunk/drivers/robot/pr2/ocean_battery_driver/scripts/view_batteries
===================================================================
--- pkg/trunk/drivers/robot/pr2/ocean_battery_driver/scripts/view_batteries 2009-01-28 08:14:01 UTC (rev 10359)
+++ pkg/trunk/drivers/robot/pr2/ocean_battery_driver/scripts/view_batteries 2009-01-28 08:28:15 UTC (rev 10360)
@@ -72,7 +72,7 @@
def listener():
app = wx.PySimpleApp()
- rospy.ready(NAME, anonymous=True)
+ rospy.init_node(NAME, anonymous=True)
frame = MainWindow(None, -1, "PR2 Power Board")
frame.Show()
Modified: pkg/trunk/drivers/robot/pr2/pr2_power_board/scripts/view_power
===================================================================
--- pkg/trunk/drivers/robot/pr2/pr2_power_board/scripts/view_power 2009-01-28 08:14:01 UTC (rev 10359)
+++ pkg/trunk/drivers/robot/pr2/pr2_power_board/scripts/view_power 2009-01-28 08:28:15 UTC (rev 10360)
@@ -73,7 +73,7 @@
def listener():
app = wx.PySimpleApp()
- rospy.ready(NAME, anonymous=True)
+ rospy.init_node(NAME, anonymous=True)
frame = MainWindow(None, -1, "PR2 Power Board")
frame.Show()
Modified: pkg/trunk/hardware_test/runtime_monitor/scripts/log_runtime_messages
===================================================================
--- pkg/trunk/hardware_test/runtime_monitor/scripts/log_runtime_messages 2009-01-28 08:14:01 UTC (rev 10359)
+++ pkg/trunk/hardware_test/runtime_monitor/scripts/log_runtime_messages 2009-01-28 08:28:15 UTC (rev 10360)
@@ -72,7 +72,7 @@
def listener():
rospy.TopicSub("/diagnostics", DiagnosticMessage, callback)
- rospy.ready(NAME, anonymous=True)
+ rospy.init_node(NAME, anonymous=True)
rospy.spin()
if __name__ == '__main__':
Modified: pkg/trunk/hardware_test/runtime_monitor/scripts/monitor
===================================================================
--- pkg/trunk/hardware_test/runtime_monitor/scripts/monitor 2009-01-28 08:14:01 UTC (rev 10359)
+++ pkg/trunk/hardware_test/runtime_monitor/scripts/monitor 2009-01-28 08:28:15 UTC (rev 10360)
@@ -55,7 +55,7 @@
def listener():
rospy.TopicSub("/diagnostics", DiagnosticMessage, callback)
- rospy.ready(NAME, anonymous=True)
+ rospy.init_node(NAME, anonymous=True)
rospy.spin()
if __name__ == '__main__':
Modified: pkg/trunk/hardware_test/runtime_monitor/scripts/runtime_test
===================================================================
--- pkg/trunk/hardware_test/runtime_monitor/scripts/runtime_test 2009-01-28 08:14:01 UTC (rev 10359)
+++ pkg/trunk/hardware_test/runtime_monitor/scripts/runtime_test 2009-01-28 08:28:15 UTC (rev 10360)
@@ -104,7 +104,7 @@
def listener():
rospy.TopicSub("/diagnostics", DiagnosticMessage, callback)
- rospy.ready(NAME, anonymous=True)
+ rospy.init_node(NAME, anonymous=True)
rospy.spin()
if __name__ == '__main__':
Modified: pkg/trunk/hardware_test/runtime_monitor/scripts/test_high_level
===================================================================
--- pkg/trunk/hardware_test/runtime_monitor/scripts/test_high_level 2009-01-28 08:14:01 UTC (rev 10359)
+++ pkg/trunk/hardware_test/runtime_monitor/scripts/test_high_level 2009-01-28 08:28:15 UTC (rev 10360)
@@ -79,7 +79,7 @@
def listener():
rospy.TopicSub("/diagnostics", DiagnosticMessage, callback)
- rospy.ready(NAME, anonymous=True)
+ rospy.init_node(NAME, anonymous=True)
rospy.spin()
if __name__ == '__main__':
Modified: pkg/trunk/hardware_test/runtime_monitor/scripts/wxmonitor.py
===================================================================
--- pkg/trunk/hardware_test/runtime_monitor/scripts/wxmonitor.py 2009-01-28 08:14:01 UTC (rev 10359)
+++ pkg/trunk/hardware_test/runtime_monitor/scripts/wxmonitor.py 2009-01-28 08:28:15 UTC (rev 10360)
@@ -73,7 +73,7 @@
def wxmonitor():
app = wx.PySimpleApp()
- rospy.ready(NAME, anonymous=True)
+ rospy.init_node(NAME, anonymous=True)
frame = MainWindow(None, -1, "Runtime Monitor")
frame.Show()
Modified: pkg/trunk/hardware_test/runtime_monitor/testmonitor.py
===================================================================
--- pkg/trunk/hardware_test/runtime_monitor/testmonitor.py 2009-01-28 08:14:01 UTC (rev 10359)
+++ pkg/trunk/hardware_test/runtime_monitor/testmonitor.py 2009-01-28 08:28:15 UTC (rev 10360)
@@ -82,7 +82,7 @@
def listener():
pub = rospy.TopicPub("/diagnostics", DiagnosticMessage)
- rospy.ready(NAME, anonymous=True)
+ rospy.init_node(NAME, anonymous=True)
while not rospy.is_shutdown():
loop(pub)
time.sleep(1)
Modified: pkg/trunk/mechanism/mechanism_control/scripts/detect.py
===================================================================
--- pkg/trunk/mechanism/mechanism_control/scripts/detect.py 2009-01-28 08:14:01 UTC (rev 10359)
+++ pkg/trunk/mechanism/mechanism_control/scripts/detect.py 2009-01-28 08:28:15 UTC (rev 10360)
@@ -39,7 +39,7 @@
def listener_with_user_data():
rospy.TopicSub("/mechanism_state", MechanismState, callback)
- rospy.ready(NAME, anonymous=True)
+ rospy.init_node(NAME, anonymous=True)
rospy.spin()
if __name__ == '__main__':
Modified: pkg/trunk/mechanism/mechanism_control/scripts/listen.py
===================================================================
--- pkg/trunk/mechanism/mechanism_control/scripts/listen.py 2009-01-28 08:14:01 UTC (rev 10359)
+++ pkg/trunk/mechanism/mechanism_control/scripts/listen.py 2009-01-28 08:28:15 UTC (rev 10360)
@@ -52,7 +52,7 @@
def listener_with_user_data():
rospy.TopicSub("/mechanism_state", MechanismState, callback)
- rospy.ready(NAME, anonymous=True)
+ rospy.init_node(NAME, anonymous=True)
rospy.spin()
if __name__ == '__main__':
Modified: pkg/trunk/mechanism/mechanism_control/scripts/writer.py
===================================================================
--- pkg/trunk/mechanism/mechanism_control/scripts/writer.py 2009-01-28 08:14:01 UTC (rev 10359)
+++ pkg/trunk/mechanism/mechanism_control/scripts/writer.py 2009-01-28 08:28:15 UTC (rev 10360)
@@ -24,7 +24,7 @@
def listener_with_user_data():
rospy.TopicSub("/mechanism_state", MechanismState, callback)
- rospy.ready(NAME, anonymous=True)
+ rospy.init_node(NAME, anonymous=True)
rospy.spin()
if __name__ == '__main__':
Modified: pkg/trunk/mechanism/mechanism_control/test/listenerpublisher_ms.py
===================================================================
--- pkg/trunk/mechanism/mechanism_control/test/listenerpublisher_ms.py 2009-01-28 08:14:01 UTC (rev 10359)
+++ pkg/trunk/mechanism/mechanism_control/test/listenerpublisher_ms.py 2009-01-28 08:28:15 UTC (rev 10360)
@@ -63,7 +63,7 @@
_pub.publish(data)
def listener_publisher():
- rospy.ready(NAME)
+ rospy.init_node(NAME)
rospy.TopicSub(IN, MSG, callback)
rospy.spin()
Modified: pkg/trunk/mechanism/mechanism_control/test/test_ms.py
===================================================================
--- pkg/trunk/mechanism/mechanism_control/test/test_ms.py 2009-01-28 08:14:01 UTC (rev 10359)
+++ pkg/trunk/mechanism/mechanism_control/test/test_ms.py 2009-01-28 08:28:15 UTC (rev 10360)
@@ -141,5 +141,5 @@
self.assertEquals(1, self.callback_data.actuator_states[1].num_encoder_errors)
if __name__ == '__main__':
- rospy.ready(NAME)
+ rospy.init_node(NAME)
rostest.run(PKG, NAME, TestMechanismState, sys.argv)
Modified: pkg/trunk/mechanism/mechanism_control/test/test_ms_cpp.py
===================================================================
--- pkg/trunk/mechanism/mechanism_control/test/test_ms_cpp.py 2009-01-28 08:14:01 UTC (rev 10359)
+++ pkg/trunk/mechanism/mechanism_control/test/test_ms_cpp.py 2009-01-28 08:28:15 UTC (rev 10360)
@@ -113,5 +113,5 @@
self.assertEquals(0, f.num_encoder_errors)
if __name__ == '__main__':
- rospy.ready(NAME)
+ rospy.init_node(NAME)
rostest.run(PKG, NAME, TestMechanismState, sys.argv)
Modified: pkg/trunk/nav/trajectory_rollout/scripts/listen.py
===================================================================
--- pkg/trunk/nav/trajectory_rollout/scripts/listen.py 2009-01-28 08:14:01 UTC (rev 10359)
+++ pkg/trunk/nav/trajectory_rollout/scripts/listen.py 2009-01-28 08:28:15 UTC (rev 10360)
@@ -13,7 +13,7 @@
def listener_with_user_data():
rospy.TopicSub("/goal", Planner2DGoal, callback)
- rospy.ready(NAME, anonymous=True)
+ rospy.init_node(NAME, anonymous=True)
rospy.spin()
if __name__ == '__main__':
Modified: pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_prototype1/motor_monitor.py
===================================================================
--- pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_prototype1/motor_monitor.py 2009-01-28 08:14:01 UTC (rev 10359)
+++ pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_prototype1/motor_monitor.py 2009-01-28 08:28:15 UTC (rev 10360)
@@ -21,7 +21,7 @@
def listener_with_user_data():
rospy.TopicSub("/diagnostics", DiagnosticMessage, callback)
- rospy.ready(NAME, anonymous=True)
+ rospy.init_node(NAME, anonymous=True)
rospy.spin()
if __name__ == '__main__':
Modified: pkg/trunk/simulators/simulator_integration_tests/world_3d_map_gazebo_tests/testcloud.py
===================================================================
--- pkg/trunk/simulators/simulator_integration_tests/world_3d_map_gazebo_tests/testcloud.py 2009-01-28 08:14:01 UTC (rev 10359)
+++ pkg/trunk/simulators/simulator_integration_tests/world_3d_map_gazebo_tests/testcloud.py 2009-01-28 08:28:15 UTC (rev 10360)
@@ -73,7 +73,7 @@
def test_cloud(self):
print "LNK\n"
rospy.TopicSub("world_3d_map", PointCloud, self.pointInput)
- rospy.ready(NAME, anonymous=True)
+ rospy.init_node(NAME, anonymous=True)
timeout_t = time.time() + 30.0 #30 seconds
while not rospy.is_shutdown() and not self.success and time.time() < timeout_t:
time.sleep(0.1)
Modified: pkg/trunk/util/ntp_monitor/ntp_monitor.py
===================================================================
--- pkg/trunk/util/ntp_monitor/ntp_monitor.py 2009-01-28 08:14:01 UTC (rev 10359)
+++ pkg/trunk/util/ntp_monitor/ntp_monitor.py 2009-01-28 08:28:15 UTC (rev 10360)
@@ -52,7 +52,7 @@
return
else:
pub = rospy.Publisher("/diagnostics", DiagnosticMessage)
- rospy.ready(NAME, anonymous=True)
+ rospy.init_node(NAME, anonymous=True)
hostname = socket.gethostbyaddr(socket.gethostname())[0]
Modified: pkg/trunk/vision/visual_odometry/nodes/camview_py.py
===================================================================
--- pkg/trunk/vision/visual_odometry/nodes/camview_py.py 2009-01-28 08:14:01 UTC (rev 10359)
+++ pkg/trunk/vision/visual_odometry/nodes/camview_py.py 2009-01-28 08:28:15 UTC (rev 10360)
@@ -247,7 +247,7 @@
vod = VODemo(mode, library)
- rospy.ready('camview_py')
+ rospy.init_node('camview_py')
rospy.spin()
vod.dump()
Modified: pkg/trunk/vision/visual_odometry/nodes/corrector.py
===================================================================
--- pkg/trunk/vision/visual_odometry/nodes/corrector.py 2009-01-28 08:14:01 UTC (rev 10359)
+++ pkg/trunk/vision/visual_odometry/nodes/corrector.py 2009-01-28 08:28:15 UTC (rev 10360)
@@ -177,7 +177,7 @@
corr = Corrector(vo, library)
- rospy.ready('corrector')
+ rospy.init_node('corrector')
try:
corr.workloop()
except KeyboardInterrupt:
Modified: pkg/trunk/vision/visual_odometry/nodes/lineperf.py
===================================================================
--- pkg/trunk/vision/visual_odometry/nodes/lineperf.py 2009-01-28 08:14:01 UTC (rev 10359)
+++ pkg/trunk/vision/visual_odometry/nodes/lineperf.py 2009-01-28 08:28:15 UTC (rev 10360)
@@ -118,7 +118,7 @@
vod = lineperftest(args[1])
- rospy.ready('lineperf_%s' % args[1])
+ rospy.init_node('lineperf_%s' % args[1])
rospy.spin()
if args[1] == 'send':
vod.report()
Modified: pkg/trunk/vision/visual_odometry/nodes/vo.py
===================================================================
--- pkg/trunk/vision/visual_odometry/nodes/vo.py 2009-01-28 08:14:01 UTC (rev 10359)
+++ pkg/trunk/vision/visual_odometry/nodes/vo.py 2009-01-28 08:28:15 UTC (rev 10360)
@@ -177,7 +177,7 @@
def main(args):
vod = VO()
- rospy.ready('vo')
+ rospy.init_node('vo')
rospy.spin()
vod.vo.summarize_timers()
vod.dump()
Modified: pkg/trunk/visualization/pr2_gui/src/pr2_gui/pr2_frame.py
===================================================================
--- pkg/trunk/visualization/pr2_gui/src/pr2_gui/pr2_frame.py 2009-01-28 08:14:01 UTC (rev 10359)
+++ pkg/trunk/visualization/pr2_gui/src/pr2_gui/pr2_frame.py 2009-01-28 08:28:15 UTC (rev 10360)
@@ -59,7 +59,7 @@
def __init__(self, parent, id=wx.ID_ANY, title='PR2 GUI', pos=wx.DefaultPosition, size=(1280, 1024), style=wx.DEFAULT_FRAME_STYLE):
wx.Frame.__init__(self, parent, id, title, pos, size, style)
- rospy.ready('pr2_gui', anonymous=True)
+ rospy.init_node('pr2_gui', anonymous=True)
self._config = wx.Config("pr2_gui")
self._aui_manager = wx.aui.AuiManager(self)
Modified: pkg/trunk/visualization/wxpy_ros/tests/test_try.py
===================================================================
--- pkg/trunk/visualization/wxpy_ros/tests/test_try.py 2009-01-28 08:14:01 UTC (rev 10359)
+++ pkg/trunk/visualization/wxpy_ros/tests/test_try.py 2009-01-28 08:28:15 UTC (rev 10360)
@@ -52,7 +52,7 @@
Thread.__init__(self)
def run(self):
- rospy.ready(NAME, anonymous=True)
+ rospy.init_node(NAME, anonymous=True)
rospy.spin()
channel = MyChannel()
Modified: pkg/trunk/world_models/static_map_server/nodes/map_server
===================================================================
--- pkg/trunk/world_models/static_map_server/nodes/map_server 2009-01-28 08:14:01 UTC (rev 10359)
+++ pkg/trunk/world_models/static_map_server/nodes/map_server 2009-01-28 08:28:15 UTC (rev 10360)
@@ -95,7 +95,7 @@
self.scale = yaml_defs['resolution']
self.origin = yaml_defs['origin']
- rospy.ready(NAME)
+ rospy.init_node(NAME)
s1 = rospy.Service("static_map", std_srvs.srv.StaticMap, self.map_handler)
rospy.spin()
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|