|
From: <tf...@us...> - 2008-08-29 00:55:39
|
Revision: 3784
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=3784&view=rev
Author: tfoote
Date: 2008-08-29 00:55:48 +0000 (Fri, 29 Aug 2008)
Log Message:
-----------
converting Point3DFloat64 to identical message Position
Modified Paths:
--------------
pkg/trunk/robot_msgs/msg/KinematicSpaceParameters.msg
pkg/trunk/vision/laser_interface/nodes/follow_light_node.py
pkg/trunk/vision/laser_interface/nodes/laser_pointer_detector_node.py
pkg/trunk/vision/laser_interface/nodes/send_command.py
pkg/trunk/vision/laser_interface/src/laser_interface/cursor3d_listener.py
pkg/trunk/vision/laser_interface/src/laser_interface/dimreduce_display.py
pkg/trunk/vision/laser_interface/src/laser_interface/test.py
pkg/trunk/vision/laser_interface/src/laser_interface/test2.py
Modified: pkg/trunk/robot_msgs/msg/KinematicSpaceParameters.msg
===================================================================
--- pkg/trunk/robot_msgs/msg/KinematicSpaceParameters.msg 2008-08-29 00:51:23 UTC (rev 3783)
+++ pkg/trunk/robot_msgs/msg/KinematicSpaceParameters.msg 2008-08-29 00:55:48 UTC (rev 3784)
@@ -17,8 +17,8 @@
# Lower coordinate for a box defining the volume in the workspace the
# motion planner is active in. If planning in 2D, only first 2 values
# (x, y) of the points are used.
-std_msgs/Point3DFloat64 volumeMin
+std_msgs/Position volumeMin
# Higher coordinate for the box described above
-std_msgs/Point3DFloat64 volumeMax
+std_msgs/Position volumeMax
Modified: pkg/trunk/vision/laser_interface/nodes/follow_light_node.py
===================================================================
--- pkg/trunk/vision/laser_interface/nodes/follow_light_node.py 2008-08-29 00:51:23 UTC (rev 3783)
+++ pkg/trunk/vision/laser_interface/nodes/follow_light_node.py 2008-08-29 00:55:48 UTC (rev 3784)
@@ -27,7 +27,7 @@
#
## @author Hai Nguyen/ha...@ga...
from pkg import *
-from std_msgs.msg import Point3DFloat64
+from std_msgs.msg import Position
from std_msgs.msg import BaseVel
from std_msgs.msg import RobotBase2DOdom
import sys
@@ -119,7 +119,7 @@
pub = rospy.TopicPub('cmd_vel', BaseVel)
follow_behavior = FollowBehavior(pub)
rospy.TopicSub('odom', RobotBase2DOdom, follow_behavior.robot_moved)
- rospy.TopicSub(CURSOR_TOPIC, Point3DFloat64, follow_behavior.cursor_moved)
+ rospy.TopicSub(CURSOR_TOPIC, Position, follow_behavior.cursor_moved)
rospy.ready(sys.argv[0])
#follow_behavior.cursor_moved(FakePoint(0.0,0.0,1.0))
while not rospy.isShutdown():
Modified: pkg/trunk/vision/laser_interface/nodes/laser_pointer_detector_node.py
===================================================================
--- pkg/trunk/vision/laser_interface/nodes/laser_pointer_detector_node.py 2008-08-29 00:51:23 UTC (rev 3783)
+++ pkg/trunk/vision/laser_interface/nodes/laser_pointer_detector_node.py 2008-08-29 00:55:48 UTC (rev 3784)
@@ -72,7 +72,7 @@
#- @b "laser_mode"/String : sets the mode to either 'debug' 'display' 'verbose' 'rebuild' 'positive' or 'clear'.
#
#Publishes to (name / type):
-#- @b "cursor3d"/Point3DFloat64:
+#- @b "cursor3d"/Position:
#
#<hr>
#
@@ -80,7 +80,7 @@
#
from pkg import *
-from std_msgs.msg import Point3DFloat64
+from std_msgs.msg import Position
from std_msgs.msg import String
import sys, time
import opencv as cv
@@ -294,7 +294,7 @@
rospy.TopicSub(LASER_MODE_TOPIC, String, self._mode_handler)
#Publish
- self.topic = rospy.TopicPub(CURSOR_TOPIC, Point3DFloat64)
+ self.topic = rospy.TopicPub(CURSOR_TOPIC, Position)
#Ready
rospy.ready(sys.argv[0])
@@ -368,7 +368,7 @@
if result != None:
p = result['point']
- self.topic.publish(Point3DFloat64(p[0,0], p[1,0], p[2,0]))
+ self.topic.publish(Position(p[0,0], p[1,0], p[2,0]))
if self.debug:
print '>> undistort %.2f' % (undistort_time - start_time)
@@ -576,7 +576,7 @@
# rospy.TopicSub(LASER_MODE_TOPIC, String, self._mode_handler)
#
# #Publish
-# self.topic = rospy.TopicPub(CURSOR_TOPIC, Point3DFloat64)
+# self.topic = rospy.TopicPub(CURSOR_TOPIC, Position)
#
# #Ready
# rospy.ready(sys.argv[0])
@@ -613,7 +613,7 @@
# self.video_lock.release()
# if result != None:
# p = result['point']
-# self.topic.publish(Point3DFloat64(p[0,0], p[1,0], p[2,0]))
+# self.topic.publish(Position(p[0,0], p[1,0], p[2,0]))
#
# if self.debug:
# print '>> undistort %.2f' % (undistort_time - start_time)
Modified: pkg/trunk/vision/laser_interface/nodes/send_command.py
===================================================================
--- pkg/trunk/vision/laser_interface/nodes/send_command.py 2008-08-29 00:51:23 UTC (rev 3783)
+++ pkg/trunk/vision/laser_interface/nodes/send_command.py 2008-08-29 00:55:48 UTC (rev 3784)
@@ -27,7 +27,7 @@
#
## @author Hai Nguyen/ha...@ga...
from pkg import *
-from std_msgs.msg import Point3DFloat64
+from std_msgs.msg import Position
import sys, time
import opencv as cv
import opencv.highgui as hg
@@ -38,11 +38,11 @@
from laser_detector import *
from threading import RLock
-topic = rospy.TopicPub(CURSOR_TOPIC, Point3DFloat64)
+topic = rospy.TopicPub(CURSOR_TOPIC, Position)
rospy.ready(sys.argv[0])
if not rospy.isShutdown():
time.sleep(1)
- topic.publish(Point3DFloat64(float(sys.argv[1]), float(sys.argv[2]), float(sys.argv[3])))
+ topic.publish(Position(float(sys.argv[1]), float(sys.argv[2]), float(sys.argv[3])))
print 'sent message'
Modified: pkg/trunk/vision/laser_interface/src/laser_interface/cursor3d_listener.py
===================================================================
--- pkg/trunk/vision/laser_interface/src/laser_interface/cursor3d_listener.py 2008-08-29 00:51:23 UTC (rev 3783)
+++ pkg/trunk/vision/laser_interface/src/laser_interface/cursor3d_listener.py 2008-08-29 00:55:48 UTC (rev 3784)
@@ -1,12 +1,12 @@
from pkg import *
-from std_msgs.msg import Point3DFloat64
+from std_msgs.msg import Position
import sys
class Echo:
def echo(self, point):
print 'x y z', point.x, point.y, point.z
-rospy.TopicSub(CURSOR_TOPIC, Point3DFloat64, Echo().echo)
+rospy.TopicSub(CURSOR_TOPIC, Position, Echo().echo)
rospy.ready(sys.argv[0])
rospy.spin()
Modified: pkg/trunk/vision/laser_interface/src/laser_interface/dimreduce_display.py
===================================================================
--- pkg/trunk/vision/laser_interface/src/laser_interface/dimreduce_display.py 2008-08-29 00:51:23 UTC (rev 3783)
+++ pkg/trunk/vision/laser_interface/src/laser_interface/dimreduce_display.py 2008-08-29 00:55:48 UTC (rev 3784)
@@ -281,7 +281,7 @@
#
##from pkg import *
#import rospy
-#from std_msgs.msg import Point3DFloat64
+#from std_msgs.msg import Position
#from std_msgs.msg import RobotBase2DOdom
#import sys
#
Modified: pkg/trunk/vision/laser_interface/src/laser_interface/test.py
===================================================================
--- pkg/trunk/vision/laser_interface/src/laser_interface/test.py 2008-08-29 00:51:23 UTC (rev 3783)
+++ pkg/trunk/vision/laser_interface/src/laser_interface/test.py 2008-08-29 00:55:48 UTC (rev 3784)
@@ -102,7 +102,7 @@
#
##from pkg import *
#import rospy
-#from std_msgs.msg import Point3DFloat64
+#from std_msgs.msg import Position
#from std_msgs.msg import RobotBase2DOdom
#import sys
#
Modified: pkg/trunk/vision/laser_interface/src/laser_interface/test2.py
===================================================================
--- pkg/trunk/vision/laser_interface/src/laser_interface/test2.py 2008-08-29 00:51:23 UTC (rev 3783)
+++ pkg/trunk/vision/laser_interface/src/laser_interface/test2.py 2008-08-29 00:55:48 UTC (rev 3784)
@@ -39,7 +39,7 @@
#from pkg import *
import rospy
-from std_msgs.msg import Point3DFloat64
+from std_msgs.msg import Position
from std_msgs.msg import RobotBase2DOdom
from std_msgs.msg import Pose2DFloat32
import sys
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|