|
From: <sf...@us...> - 2009-04-10 21:52:18
|
Revision: 13749
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=13749&view=rev
Author: sfkwc
Date: 2009-04-10 21:52:13 +0000 (Fri, 10 Apr 2009)
Log Message:
-----------
cleanup of rospy API usage
Modified Paths:
--------------
pkg/trunk/demos/2dnav_pr2/pose_listen.py
pkg/trunk/demos/plug_in/fake_vision.py
pkg/trunk/demos/plug_in/outlet_pose_filter.py
pkg/trunk/demos/plug_in/plug_in.py
pkg/trunk/demos/tabletop_manipulation/scripts/executive.py
pkg/trunk/demos/tabletop_manipulation/scripts/tiltscan.py
pkg/trunk/drivers/robot/pr2/ocean_battery_driver/scripts/monitor
pkg/trunk/hardware_test/runtime_monitor/scripts/runtime_test
pkg/trunk/mechanism/mechanism_control/scripts/spawner.py
pkg/trunk/prcore/pytf/test_pytf.py
pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_prototype1/motor_monitor.py
pkg/trunk/util/twitterros/nodes/rostwitter.py
pkg/trunk/vision/cv_mech_turk/src/snapper.py
pkg/trunk/vision/people/src/stereo_face_feature_tracker.py
pkg/trunk/vision/visual_odometry/nodes/camview_py.py
pkg/trunk/vision/visual_odometry/nodes/corrector.py
pkg/trunk/vision/visual_odometry/nodes/diff.py
pkg/trunk/vision/visual_odometry/nodes/vo.py
pkg/trunk/vision/vslam/nodes/roadmap.py
pkg/trunk/vision/vslam/nodes/watchmap.py
pkg/trunk/visualization/pr2_dashboard/src/pr2_dashboard/reset.py
Modified: pkg/trunk/demos/2dnav_pr2/pose_listen.py
===================================================================
--- pkg/trunk/demos/2dnav_pr2/pose_listen.py 2009-04-10 21:45:46 UTC (rev 13748)
+++ pkg/trunk/demos/2dnav_pr2/pose_listen.py 2009-04-10 21:52:13 UTC (rev 13749)
@@ -14,8 +14,8 @@
print "localized: %d.%d %.2f, %.2f, %.2f" % (data.header.stamp.secs, data.header.stamp.nsecs, data.pos.x, data.pos.y, data.pos.th)
def pose_listen():
- rospy.TopicSub("/odom", RobotBase2DOdom, odom_callback)
- rospy.TopicSub("/localizedpose", RobotBase2DOdom, localized_callback)
+ rospy.Subscriber("/odom", RobotBase2DOdom, odom_callback)
+ rospy.Subscriber("/localizedpose", RobotBase2DOdom, localized_callback)
rospy.init_node(NAME, anonymous=True)
rospy.spin()
Modified: pkg/trunk/demos/plug_in/fake_vision.py
===================================================================
--- pkg/trunk/demos/plug_in/fake_vision.py 2009-04-10 21:45:46 UTC (rev 13748)
+++ pkg/trunk/demos/plug_in/fake_vision.py 2009-04-10 21:52:13 UTC (rev 13749)
@@ -59,7 +59,7 @@
mechanism_state = Tracker('/mechanism_state', MechanismState)
def last_time():
- return rospy.rostime.get_rostime()
+ return rospy.get_rostime()
global mechanism_state
if mechanism_state.msg:
return mechanism_state.msg.header.stamp
Modified: pkg/trunk/demos/plug_in/outlet_pose_filter.py
===================================================================
--- pkg/trunk/demos/plug_in/outlet_pose_filter.py 2009-04-10 21:45:46 UTC (rev 13748)
+++ pkg/trunk/demos/plug_in/outlet_pose_filter.py 2009-04-10 21:52:13 UTC (rev 13749)
@@ -76,7 +76,7 @@
tf_msg.transforms = [pose_to_transform_stamped(outlet_msg)]
tf_msg.transforms[0].header.seq = seq
tf_msg.transforms[0].header.frame_id = 'outlet_pose'
- tf_msg.transforms[0].header.stamp = rospy.rostime.get_rostime()
+ tf_msg.transforms[0].header.stamp = rospy.get_rostime()
tf_pub.publish(tf_msg)
seq += 1
outlet_msg = track_outlet_pose.msg
Modified: pkg/trunk/demos/plug_in/plug_in.py
===================================================================
--- pkg/trunk/demos/plug_in/plug_in.py 2009-04-10 21:45:46 UTC (rev 13748)
+++ pkg/trunk/demos/plug_in/plug_in.py 2009-04-10 21:52:13 UTC (rev 13749)
@@ -105,7 +105,7 @@
if cnt % 3 == 0:
try:
set_tool_frame(track_plug_pose.msg)
- except rospy.service.ServiceException, ex:
+ except rospy.ServiceException, ex:
print "set_tool frame service went down. Reconnecting..."
rospy.wait_for_service("/%s/set_tool_frame" % CONTROLLER)
if rospy.is_shutdown(): return
Modified: pkg/trunk/demos/tabletop_manipulation/scripts/executive.py
===================================================================
--- pkg/trunk/demos/tabletop_manipulation/scripts/executive.py 2009-04-10 21:45:46 UTC (rev 13748)
+++ pkg/trunk/demos/tabletop_manipulation/scripts/executive.py 2009-04-10 21:52:13 UTC (rev 13749)
@@ -207,10 +207,10 @@
# Set the collision_map_buffer's window size accordingly, to remember a
# fixed time window scans.
- rospy.client.set_param('collision_map_buffer/window_size',
- int(self.laser_buffer_time / (period / 2.0)))
+ rospy.set_param('collision_map_buffer/window_size',
+ int(self.laser_buffer_time / (period / 2.0)))
return resp
-
+
def getTable(self):
print 'Calling FindTable'
s = rospy.ServiceProxy('table_object_detector', FindTable)
@@ -418,7 +418,7 @@
sys.exit(0)
def doCycle(self):
- curr_time = rospy.rostime.get_time()
+ curr_time = rospy.get_time()
#make sure that all adapters have legal states
if self.legalStates():
if self.state == 'idle':
Modified: pkg/trunk/demos/tabletop_manipulation/scripts/tiltscan.py
===================================================================
--- pkg/trunk/demos/tabletop_manipulation/scripts/tiltscan.py 2009-04-10 21:45:46 UTC (rev 13748)
+++ pkg/trunk/demos/tabletop_manipulation/scripts/tiltscan.py 2009-04-10 21:52:13 UTC (rev 13749)
@@ -60,8 +60,8 @@
if resp:
# Set the collision_map_buffer's window size accordingly, to remember a
# fixed time window scans.
- rospy.client.set_param('collision_map_buffer/window_size',
- int(self.laser_buffer_time / (period / 2.0)))
+ rospy.set_param('collision_map_buffer/window_size',
+ int(self.laser_buffer_time / (period / 2.0)))
print '[TiltScan] Waiting for a full sweep at the new speed...'
# Wait until the laser's swept through most of its period at the new
Modified: pkg/trunk/drivers/robot/pr2/ocean_battery_driver/scripts/monitor
===================================================================
--- pkg/trunk/drivers/robot/pr2/ocean_battery_driver/scripts/monitor 2009-04-10 21:45:46 UTC (rev 13748)
+++ pkg/trunk/drivers/robot/pr2/ocean_battery_driver/scripts/monitor 2009-04-10 21:52:13 UTC (rev 13749)
@@ -305,9 +305,9 @@
rospy.logfatal("Batteries have %.2f minutes estimated remaining"%average_time_remaining)
elif average_time_remaining < 5.0:
rospy.logerr("Batteries have %.2f minutes estimated remaining"%average_time_remaining)
- elif average_time_remaining < 30.0 and self.last_battery_warn + 6 < rospy.rostime.get_time():
+ elif average_time_remaining < 30.0 and self.last_battery_warn + 6 < rospy.get_time():
rospy.logwarn("Batteries have %.2f minutes estimated remaining"%average_time_remaining)
- self.last_battery_warn = rospy.rostime.get_time()
+ self.last_battery_warn = rospy.get_time()
#print "Sent Energy: %.0f (J) of %.0f (J) Power: %.2f (W)\n"%(energy, full_energy, power)
self.battery_state_pub.publish(BatteryState(None, energy, full_energy, power))
Modified: pkg/trunk/hardware_test/runtime_monitor/scripts/runtime_test
===================================================================
--- pkg/trunk/hardware_test/runtime_monitor/scripts/runtime_test 2009-04-10 21:45:46 UTC (rev 13748)
+++ pkg/trunk/hardware_test/runtime_monitor/scripts/runtime_test 2009-04-10 21:52:13 UTC (rev 13749)
@@ -45,7 +45,7 @@
latest_messages = {}
test_name = 'uninitialized'
package = 'uninitialized'
-last_runtime = rospy.rostime.get_time()
+last_runtime = rospy.get_time()
def status_to_map(status):
str_map = {}
@@ -76,11 +76,11 @@
def execute_test(args):
global last_runtime
- time_step = rospy.rostime.get_time() - last_runtime
+ time_step = rospy.get_time() - last_runtime
if 1.0 /time_step > options.max_freq:
return
else:
- last_runtime = rospy.rostime.get_time()
+ last_runtime = rospy.get_time()
test_impl, params = args
results = analyze(package, test_impl, params)
@@ -116,7 +116,7 @@
rospy.Subscriber("/diagnostics", DiagnosticMessage, callback, (test_impl, params))
while not rospy.is_shutdown():
- if rospy.rostime.get_time() - last_runtime > 1/options.min_freq:
+ if rospy.get_time() - last_runtime > 1/options.min_freq:
execute_test((test_impl, params))
time.sleep(0.5/options.min_freq)
Modified: pkg/trunk/mechanism/mechanism_control/scripts/spawner.py
===================================================================
--- pkg/trunk/mechanism/mechanism_control/scripts/spawner.py 2009-04-10 21:45:46 UTC (rev 13748)
+++ pkg/trunk/mechanism/mechanism_control/scripts/spawner.py 2009-04-10 21:52:13 UTC (rev 13749)
@@ -59,7 +59,7 @@
kill_controller(name)
rospy.logout("Succeeded in killing %s" % name)
break
- except rospy.service.ServiceException:
+ except rospy.ServiceException:
raise
rospy.logerr("ServiceException while killing %s" % name)
# We're shutdown. Now invoke rospy's handler for full cleanup.
Modified: pkg/trunk/prcore/pytf/test_pytf.py
===================================================================
--- pkg/trunk/prcore/pytf/test_pytf.py 2009-04-10 21:45:46 UTC (rev 13748)
+++ pkg/trunk/prcore/pytf/test_pytf.py 2009-04-10 21:52:13 UTC (rev 13749)
@@ -15,7 +15,7 @@
time.sleep(0.5)
for i in xrange(1,10):
print "Looping"
- current_time = rospy.rostime.get_rostime()
+ current_time = rospy.get_rostime()
if not t.can_transform("frame", "parent", current_time):
print "waiting to try again"
time.sleep(0.1)
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-04-10 21:45:46 UTC (rev 13748)
+++ pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_prototype1/motor_monitor.py 2009-04-10 21:52:13 UTC (rev 13749)
@@ -20,7 +20,7 @@
print "Resetting motors"
def listener_with_user_data():
- rospy.TopicSub("/diagnostics", DiagnosticMessage, callback)
+ rospy.Subscriber("/diagnostics", DiagnosticMessage, callback)
rospy.init_node(NAME, anonymous=True)
rospy.spin()
Modified: pkg/trunk/util/twitterros/nodes/rostwitter.py
===================================================================
--- pkg/trunk/util/twitterros/nodes/rostwitter.py 2009-04-10 21:45:46 UTC (rev 13748)
+++ pkg/trunk/util/twitterros/nodes/rostwitter.py 2009-04-10 21:52:13 UTC (rev 13749)
@@ -57,7 +57,7 @@
if twitPass == None:
twitPass = passes[twitId]
self.api = twitter.Api(username=twitId, password=twitPass)
- rospy.TopicSub('/twitter', std_msgs.msg.String, self.handle_message)
+ rospy.Subscriber('/twitter', std_msgs.msg.String, self.handle_message)
def handle_message(self, msg):
status = self.api.PostUpdate(msg.data[:140])
Modified: pkg/trunk/vision/cv_mech_turk/src/snapper.py
===================================================================
--- pkg/trunk/vision/cv_mech_turk/src/snapper.py 2009-04-10 21:45:46 UTC (rev 13748)
+++ pkg/trunk/vision/cv_mech_turk/src/snapper.py 2009-04-10 21:52:13 UTC (rev 13749)
@@ -65,7 +65,7 @@
def main(args):
s = Snapper()
rospy.init_node('snapper')
- rospy.TopicSub('/stereo/left/image_rect_color', image_msgs.msg.Image, s.handle_raw_stereo, queue_size=2, buff_size=7000000)
+ rospy.Subscriber('/stereo/left/image_rect_color', image_msgs.msg.Image, s.handle_raw_stereo, queue_size=2, buff_size=7000000)
rospy.spin()
if __name__ == '__main__':
Modified: pkg/trunk/vision/people/src/stereo_face_feature_tracker.py
===================================================================
--- pkg/trunk/vision/people/src/stereo_face_feature_tracker.py 2009-04-10 21:45:46 UTC (rev 13748)
+++ pkg/trunk/vision/people/src/stereo_face_feature_tracker.py 2009-04-10 21:52:13 UTC (rev 13749)
@@ -727,9 +727,9 @@
#people_tracker.pub = rospy.Publisher('head_controller/track_point',PointStamped)
people_tracker.pub = rospy.Publisher('/stereo_face_feature_tracker/position_measurement',PositionMeasurement)
rospy.init_node('stereo_face_feature_tracker', anonymous=True)
- #rospy.TopicSub('/head_controller/track_point',PointStamped,people_tracker.point_stamped)
- rospy.TopicSub('/videre/images',ImageArray,people_tracker.frame)
- rospy.TopicSub('/videre/cal_params',String,people_tracker.params)
+ #rospy.Subscriber('/head_controller/track_point',PointStamped,people_tracker.point_stamped)
+ rospy.Subscriber('/videre/images',ImageArray,people_tracker.frame)
+ rospy.Subscriber('/videre/cal_params',String,people_tracker.params)
rospy.spin()
Modified: pkg/trunk/vision/visual_odometry/nodes/camview_py.py
===================================================================
--- pkg/trunk/vision/visual_odometry/nodes/camview_py.py 2009-04-10 21:45:46 UTC (rev 13748)
+++ pkg/trunk/vision/visual_odometry/nodes/camview_py.py 2009-04-10 21:52:13 UTC (rev 13749)
@@ -74,9 +74,9 @@
self.mode = mode
self.library = library
- rospy.TopicSub('/videre/images', ImageArray, self.display_array)
- rospy.TopicSub('/videre/cal_params', String, self.display_params)
- rospy.TopicSub('/vo/tmo', Pose44, self.handle_corrections)
+ rospy.Subscriber('/videre/images', ImageArray, self.display_array)
+ rospy.Subscriber('/videre/cal_params', String, self.display_params)
+ rospy.Subscriber('/vo/tmo', Pose44, self.handle_corrections)
self.viz_pub = rospy.Publisher("/overlay", Lines)
self.vo_key_pub = rospy.Publisher("/vo/key", Frame)
Modified: pkg/trunk/vision/visual_odometry/nodes/corrector.py
===================================================================
--- pkg/trunk/vision/visual_odometry/nodes/corrector.py 2009-04-10 21:45:46 UTC (rev 13748)
+++ pkg/trunk/vision/visual_odometry/nodes/corrector.py 2009-04-10 21:52:13 UTC (rev 13749)
@@ -72,7 +72,7 @@
self.vo = vo
self.library = library
- rospy.TopicSub('/vo/key', Frame, self.incoming_frame)
+ rospy.Subscriber('/vo/key', Frame, self.incoming_frame)
self.pub_tmo = rospy.Publisher("/vo/tmo", Pose44)
self.frameq = Queue()
Modified: pkg/trunk/vision/visual_odometry/nodes/diff.py
===================================================================
--- pkg/trunk/vision/visual_odometry/nodes/diff.py 2009-04-10 21:45:46 UTC (rev 13748)
+++ pkg/trunk/vision/visual_odometry/nodes/diff.py 2009-04-10 21:52:13 UTC (rev 13749)
@@ -49,8 +49,8 @@
def __init__(self):
self.prev_a = 0
self.prev_b = 0
- rospy.TopicSub('/stereo/raw_stereo', image_msgs.msg.RawStereo, self.handle_a, queue_size=2, buff_size=7000000)
- rospy.TopicSub('/vo', robot_msgs.msg.VOPose, self.handle_b, queue_size=2, buff_size=7000000)
+ rospy.Subscriber('/stereo/raw_stereo', image_msgs.msg.RawStereo, self.handle_a, queue_size=2, buff_size=7000000)
+ rospy.Subscriber('/vo', robot_msgs.msg.VOPose, self.handle_b, queue_size=2, buff_size=7000000)
def handle_a(self, msg):
self.prev_a = msg.header.stamp.to_seconds()
Modified: pkg/trunk/vision/visual_odometry/nodes/vo.py
===================================================================
--- pkg/trunk/vision/visual_odometry/nodes/vo.py 2009-04-10 21:45:46 UTC (rev 13748)
+++ pkg/trunk/vision/visual_odometry/nodes/vo.py 2009-04-10 21:52:13 UTC (rev 13749)
@@ -73,7 +73,7 @@
class VO:
def __init__(self):
- rospy.TopicSub('/stereo/raw_stereo', image_msgs.msg.RawStereo, self.handle_raw_stereo, queue_size=2, buff_size=7000000)
+ rospy.Subscriber('/stereo/raw_stereo', image_msgs.msg.RawStereo, self.handle_raw_stereo, queue_size=2, buff_size=7000000)
self.pub_vo = rospy.Publisher("/vo", robot_msgs.msg.VOPose)
Modified: pkg/trunk/vision/vslam/nodes/roadmap.py
===================================================================
--- pkg/trunk/vision/vslam/nodes/roadmap.py 2009-04-10 21:45:46 UTC (rev 13748)
+++ pkg/trunk/vision/vslam/nodes/roadmap.py 2009-04-10 21:52:13 UTC (rev 13749)
@@ -74,7 +74,7 @@
time.sleep(1)
self.send_map()
- rospy.TopicSub('/stereo/raw_stereo', image_msgs.msg.RawStereo, self.handle_raw_stereo, queue_size=2, buff_size=7000000)
+ rospy.Subscriber('/stereo/raw_stereo', image_msgs.msg.RawStereo, self.handle_raw_stereo, queue_size=2, buff_size=7000000)
def send_map(self):
p = vslam.msg.Roadmap()
@@ -112,7 +112,7 @@
def __init__(self, args):
rospy.init_node('roadmap_server')
self.pub = rospy.Publisher("/roadmap", vslam.msg.Roadmap)
- rospy.TopicSub('/localizedpose', deprecated_msgs.msg.RobotBase2DOdom, self.handle_localizedpose)
+ rospy.Subscriber('/localizedpose', deprecated_msgs.msg.RobotBase2DOdom, self.handle_localizedpose)
self.nodes = []
def handle_localizedpose(self, msg):
Modified: pkg/trunk/vision/vslam/nodes/watchmap.py
===================================================================
--- pkg/trunk/vision/vslam/nodes/watchmap.py 2009-04-10 21:45:46 UTC (rev 13748)
+++ pkg/trunk/vision/vslam/nodes/watchmap.py 2009-04-10 21:52:13 UTC (rev 13749)
@@ -69,7 +69,7 @@
def main(args):
rospy.init_node('watchmap')
- rospy.TopicSub('/roadmap', vslam.msg.Roadmap, handle_roadmap)
+ rospy.Subscriber('/roadmap', vslam.msg.Roadmap, handle_roadmap)
rospy.spin()
if __name__ == '__main__':
Modified: pkg/trunk/visualization/pr2_dashboard/src/pr2_dashboard/reset.py
===================================================================
--- pkg/trunk/visualization/pr2_dashboard/src/pr2_dashboard/reset.py 2009-04-10 21:45:46 UTC (rev 13748)
+++ pkg/trunk/visualization/pr2_dashboard/src/pr2_dashboard/reset.py 2009-04-10 21:52:13 UTC (rev 13749)
@@ -36,7 +36,6 @@
import wx
from wx import xrc
import rospy
-import rospy.service
import std_srvs.srv
PKG='pr2_dashboard'
@@ -62,6 +61,6 @@
try:
reset()
- except rospy.service.ServiceException:
+ except rospy.ServiceException:
rospy.logerr('Failed to reset the motors: service call failed')
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|