|
From: <hsu...@us...> - 2009-08-07 22:25:48
|
Revision: 21070
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21070&view=rev
Author: hsujohnhsu
Date: 2009-08-07 22:25:37 +0000 (Fri, 07 Aug 2009)
Log Message:
-----------
ticket #1316: PoseDot --> Twist for python scripts.
fix from xxx import * convention.
Modified Paths:
--------------
pkg/trunk/audio/backup_safetysound/backingup.py
pkg/trunk/audio/backup_safetysound/manifest.xml
pkg/trunk/demos/door_demos_gazebo/scripts/initialize_nav.py
pkg/trunk/demos/handhold/manifest.xml
pkg/trunk/demos/handhold/src/handhold.py
pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/manifest.xml
pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomw_gt.py
pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomx_gt.py
pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomxy_gt.py
pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomxyw_gt.py
pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomy_gt.py
pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_vw_gt.py
pkg/trunk/highlevel/executive_python/manifest.xml
pkg/trunk/highlevel/executive_python/src/stuck_adapter.py
pkg/trunk/pr2/hot_box_test/base_shuffle.py
pkg/trunk/pr2/hot_box_test/base_swivvel.py
pkg/trunk/pr2/hot_box_test/manifest.xml
pkg/trunk/sandbox/annotated_map_builder/manifest.xml
pkg/trunk/sandbox/annotated_map_builder/src/annotated_map_builder/move_head_action.py
pkg/trunk/sandbox/annotated_map_builder/src/annotated_map_builder/move_head_action2.py
pkg/trunk/sandbox/annotated_map_builder/src/annotated_map_builder/wait_for_k_messages_adapter.py
pkg/trunk/sandbox/annotated_map_builder/src/annotated_map_builder/wait_for_k_messages_adapter2.py
pkg/trunk/sandbox/annotated_map_builder/src/annotated_map_builder/wait_for_multiple_head_configs.py
pkg/trunk/sandbox/annotated_map_builder/test/test_head.py
pkg/trunk/sandbox/annotated_map_builder/test/test_head2.py
pkg/trunk/sandbox/person_follower/src/move_head_action.py
pkg/trunk/sandbox/person_follower/src/wait_for_k_messages_adapter.py
pkg/trunk/sandbox/person_follower/src/wait_for_k_messages_adapter2.py
pkg/trunk/sandbox/person_follower/src/wait_for_multiple_head_configs.py
Modified: pkg/trunk/audio/backup_safetysound/backingup.py
===================================================================
--- pkg/trunk/audio/backup_safetysound/backingup.py 2009-08-07 22:25:37 UTC (rev 21069)
+++ pkg/trunk/audio/backup_safetysound/backingup.py 2009-08-07 22:25:37 UTC (rev 21070)
@@ -3,7 +3,7 @@
import rospy
import threading
-from robot_msgs.msg import PoseDot
+from geometry_msgs.msg import Twist
from sound_play.msg import SoundRequest
import os
@@ -11,7 +11,7 @@
# if robot base receives a command to move backwards in the x-axis,
# then play sound file (TruckBackUp.wav) from Logitech USB speaker (hw:1,0).
-# data is an instance of a PoseDot extracted from the cmd_vel topic.
+# data is an instance of a Twist extracted from the cmd_vel topic.
class backingup:
def start(self):
msg = SoundRequest()
@@ -27,16 +27,16 @@
self.pub.publish(msg)
self.state = self.STOPPED
- def callback(self,data):
+ def callback(self,twist):
self.mutex.acquire()
try:
- if data.vel.vx < 0:
+ if twist.linear.x < 0:
if self.state == self.STOPPED:
self.start()
self.state = self.PLAYING
- if data.vel.vx >= 0 and self.state == self.PLAYING:
+ if twist.linear.x >= 0 and self.state == self.PLAYING:
self.state = self.STOPPING
self.targettime = rospy.get_time() + 0.5
@@ -57,7 +57,7 @@
self.state = self.STOPPED
self.targettime = 0
self.pub = rospy.Publisher('robotsound', SoundRequest)
- rospy.Subscriber("cmd_vel", PoseDot, self.callback)
+ rospy.Subscriber("cmd_vel", Twist, self.callback)
while not rospy.is_shutdown():
self.mutex.acquire()
Modified: pkg/trunk/audio/backup_safetysound/manifest.xml
===================================================================
--- pkg/trunk/audio/backup_safetysound/manifest.xml 2009-08-07 22:25:37 UTC (rev 21069)
+++ pkg/trunk/audio/backup_safetysound/manifest.xml 2009-08-07 22:25:37 UTC (rev 21070)
@@ -5,7 +5,7 @@
<author>Leila Takayama</author>
<license>BSD</license>
<depend package="rospy" />
-<depend package="robot_msgs" />
+<depend package="geometry_msgs" />
<depend package="sound_play" />
</package>
Modified: pkg/trunk/demos/door_demos_gazebo/scripts/initialize_nav.py
===================================================================
--- pkg/trunk/demos/door_demos_gazebo/scripts/initialize_nav.py 2009-08-07 22:25:37 UTC (rev 21069)
+++ pkg/trunk/demos/door_demos_gazebo/scripts/initialize_nav.py 2009-08-07 22:25:37 UTC (rev 21070)
@@ -46,14 +46,15 @@
import sys, unittest
import os, os.path, threading, time
import rospy, rostest
-from std_msgs.msg import *
-from robot_actions.msg import *
-from nav_robot_actions.msg import *
-from robot_msgs.msg import *
-from nav_msgs.msg import *
-from tf.transformations import *
-from numpy import *
+from std_msgs.msg import String
+from nav_robot_actions.msg import MoveBaseState
+from geometry_msgs.msg import Pose,Quaternion,Point, PoseWithRatesStamped, PoseStamped, PoseWithCovariance
+from geometry_msgs.msg import Twist
+from nav_msgs.msg import Odometry
+import tf.transformations as tft
+from numpy import float64
+
FLOAT_TOL = 0.0001
AMCL_TOL = 0.5
COV = [float64(0.5*0.5 ),float64(0),float64(0),float64(0),float64(0),float64(0), \
@@ -188,7 +189,7 @@
def stateInput(self, state):
if self.publish_goal:
- state_eul = euler_from_quaternion([state.goal.pose.orientation.x,state.goal.pose.orientation.y,state.goal.pose.orientation.z,state.goal.pose.orientation.w])
+ state_eul = tft.euler_from_quaternion([state.goal.pose.orientation.x,state.goal.pose.orientation.y,state.goal.pose.orientation.z,state.goal.pose.orientation.w])
print "target: ", self.target_x, ",", self.target_y, ",", self.target_t
print "state.goal: (", state.goal.pose.position.x, ",", state.goal.pose.position.y, ",", state.goal.pose.position.z \
,",", state_eul[0], ",", state_eul[1], ",", state_eul[2] \
@@ -203,7 +204,7 @@
def amclInput(self, amcl_pose):
if self.publish_initialpose:
print "/amcl_pose received, ",amcl_pose
- amcl_eul = euler_from_quaternion([amcl_pose.pose.orientation.x,amcl_pose.pose.orientation.y,amcl_pose.pose.orientation.z,amcl_pose.pose.orientation.w])
+ amcl_eul = tft.euler_from_quaternion([amcl_pose.pose.orientation.x,amcl_pose.pose.orientation.y,amcl_pose.pose.orientation.z,amcl_pose.pose.orientation.w])
if abs(amcl_pose.pose.position.x - self.initialpose[0]) < AMCL_TOL and \
abs(amcl_pose.pose.position.y - self.initialpose[1]) < AMCL_TOL and \
abs(amcl_eul[2] - self.initialpose[2]) < AMCL_TOL:
@@ -212,9 +213,9 @@
else:
print "initial_pose mismatch, continue setPose."
- def cmd_velInput(self, cmd_vel):
- print "cmd_vel: ", cmd_vel.vel.vx, ",", cmd_vel.vel.vy, ",", cmd_vel.vel.vz \
- , cmd_vel.ang_vel.vx, ",", cmd_vel.ang_vel.vy, ",", cmd_vel.ang_vel.vz
+ def cmd_velInput(self, cmd_vel_twist):
+ print "cmd_vel: ", cmd_vel_twist.linear.x, ",", cmd_vel_twist.linear.y, ",", cmd_vel_twist.linear.z \
+ , cmd_vel_twist.angular.x, ",", cmd_vel_twist.angular.y, ",", cmd_vel_twist.angular.z
def init_nav(self):
print "LNK\n"
@@ -230,7 +231,7 @@
rospy.Subscriber("/amcl_pose" , PoseWithCovariance , self.amclInput)
# below only for debugging build 303, base not moving
- rospy.Subscriber("cmd_vel" , PoseDot , self.cmd_velInput)
+ rospy.Subscriber("cmd_vel" , Twist , self.cmd_velInput)
rospy.init_node(NAME, anonymous=True)
@@ -249,7 +250,7 @@
if self.args[i] == '-t':
if len(self.args) > i+1:
self.target_t = float(self.args[i+1])
- self.target_q = quaternion_from_euler(0,0,self.target_t,'rxyz')
+ self.target_q = tft.quaternion_from_euler(0,0,self.target_t,'rxyz')
print "target t set to:",self.target_t
if self.args[i] == '-nav_t_tol':
if len(self.args) > i+1:
@@ -307,7 +308,7 @@
# publish initial pose until /amcl_pose is same as intialpose
if self.publish_initialpose:
p = Point(self.initialpose[0], self.initialpose[1], 0)
- tmpq = quaternion_from_euler(0,0,self.initialpose[2],'rxyz')
+ tmpq = tft.quaternion_from_euler(0,0,self.initialpose[2],'rxyz')
q = Quaternion(tmpq[0],tmpq[1],tmpq[2],tmpq[3])
pose = Pose(p,q)
print "publishing initialpose",h,p,COV[0]
@@ -315,7 +316,7 @@
else:
# send goal until state /move_base/feedback indicates goal is received
p = Point(self.target_x, self.target_y, 0)
- tmpq = quaternion_from_euler(0,0,self.target_t,'rxyz')
+ tmpq = tft.quaternion_from_euler(0,0,self.target_t,'rxyz')
q = Quaternion(tmpq[0],tmpq[1],tmpq[2],tmpq[3])
pose = Pose(p,q)
print "publishing goal",self.publish_goal
@@ -327,27 +328,27 @@
# compute angular error between deltas in odom and p3d
# compute delta in odom from initial pose
print "========================"
- tmpoqi = quaternion_inverse(self.odom_qi)
- odom_q_delta = quaternion_multiply(tmpoqi,self.odom_q)
+ tmpoqi = tft.quaternion_inverse(self.odom_qi)
+ odom_q_delta = tft.quaternion_multiply(tmpoqi,self.odom_q)
print "debug odom_qi:" , self.odom_qi
print "debug tmpoqi:" , tmpoqi
print "debug odom_q_delta:" , odom_q_delta
- print "odom delta:" , euler_from_quaternion(odom_q_delta)
+ print "odom delta:" , tft.euler_from_quaternion(odom_q_delta)
# compute delta in p3d from initial pose
- tmppqi = quaternion_inverse(self.p3d_qi)
- p3d_q_delta = quaternion_multiply(tmppqi,self.p3d_q)
- print "p3d delta:" , euler_from_quaternion(p3d_q_delta)
+ tmppqi = tft.quaternion_inverse(self.p3d_qi)
+ p3d_q_delta = tft.quaternion_multiply(tmppqi,self.p3d_q)
+ print "p3d delta:" , tft.euler_from_quaternion(p3d_q_delta)
# compute delta between odom and p3d
- tmpdqi = quaternion_inverse(p3d_q_delta)
- delta = quaternion_multiply(tmpdqi,odom_q_delta)
- delta_euler = euler_from_quaternion(delta)
+ tmpdqi = tft.quaternion_inverse(p3d_q_delta)
+ delta = tft.quaternion_multiply(tmpdqi,odom_q_delta)
+ delta_euler = tft.euler_from_quaternion(delta)
odom_drift_dyaw = delta_euler[2]
- print "odom drift from p3d:" , euler_from_quaternion(delta)
+ print "odom drift from p3d:" , tft.euler_from_quaternion(delta)
# compute delta between target and p3d
- tmptqi = quaternion_inverse(self.target_q)
- navdq = quaternion_multiply(tmptqi,self.p3d_q)
- navde = euler_from_quaternion(navdq)
+ tmptqi = tft.quaternion_inverse(self.target_q)
+ navdq = tft.quaternion_multiply(tmptqi,self.p3d_q)
+ navde = tft.euler_from_quaternion(navdq)
nav_dyaw = navde[2]
print "nav euler off target:" , navde
Modified: pkg/trunk/demos/handhold/manifest.xml
===================================================================
--- pkg/trunk/demos/handhold/manifest.xml 2009-08-07 22:25:37 UTC (rev 21069)
+++ pkg/trunk/demos/handhold/manifest.xml 2009-08-07 22:25:37 UTC (rev 21070)
@@ -7,6 +7,7 @@
<depend package="roscpp" />
<depend package="tf" />
<depend package="pr2_default_controllers" />
+ <depend package="geometry_msgs" />
<url>http://pr.willowgarage.com</url>
<export>
</export>
Modified: pkg/trunk/demos/handhold/src/handhold.py
===================================================================
--- pkg/trunk/demos/handhold/src/handhold.py 2009-08-07 22:25:37 UTC (rev 21069)
+++ pkg/trunk/demos/handhold/src/handhold.py 2009-08-07 22:25:37 UTC (rev 21070)
@@ -4,7 +4,7 @@
import rospy
from tf import TransformListener
from robot_msgs.msg import PoseStamped
-from robot_msgs.msg import PoseDot
+from geometry_msgs.msg import Twist
#import numpy
rospy.init_node("handhold")
@@ -14,9 +14,9 @@
q_target = None
-base_pub = rospy.Publisher('/cmd_vel', PoseDot);
+base_pub = rospy.Publisher('/cmd_vel', Twist);
-cmd_vel = PoseDot()
+cmd_vel = Twist()
error_x = 0
error_y = 0
@@ -34,9 +34,9 @@
error_rotation = q_target.pose.orientation.z - q.pose.orientation.z
print (error_rotation)
- cmd_vel.vel.vx = -10.0 * error_x
- cmd_vel.ang_vel.vz = -10.0 * error_y + error_rotation * -5.0
- cmd_vel.vel.vy = error_rotation * 2.0
+ cmd_vel.linear.x = -10.0 * error_x
+ cmd_vel.angular.z = -10.0 * error_y + error_rotation * -5.0
+ cmd_vel.linear.y = error_rotation * 2.0
base_pub.publish(cmd_vel)
rate.sleep();
Modified: pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/manifest.xml
===================================================================
--- pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/manifest.xml 2009-08-07 22:25:37 UTC (rev 21069)
+++ pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/manifest.xml 2009-08-07 22:25:37 UTC (rev 21070)
@@ -13,7 +13,7 @@
<depend package="pr2_ogre" />
<depend package="gazebo_worlds" />
<depend package="nav_msgs" />
- <depend package="robot_msgs" />
+ <depend package="geometry_msgs" />
<depend package="std_msgs" />
<depend package="tf" />
</package>
Modified: pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomw_gt.py
===================================================================
--- pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomw_gt.py 2009-08-07 22:25:37 UTC (rev 21069)
+++ pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomw_gt.py 2009-08-07 22:25:37 UTC (rev 21070)
@@ -45,8 +45,8 @@
import sys, unittest
import os, time
import rospy, rostest
-from robot_msgs.msg import *
-from nav_msgs.msg import *
+from geometry_msgs.msg import Twist,Vector3
+from nav_msgs.msg import Odometry
TEST_DURATION = 10.0
@@ -218,13 +218,13 @@
def test_base(self):
print "LNK\n"
- pub = rospy.Publisher("/cmd_vel", PoseDot)
+ pub = rospy.Publisher("/cmd_vel", Twist)
rospy.Subscriber("/base_pose_ground_truth", PoseWithRatesStamped, self.p3dInput)
rospy.Subscriber("/odom", Odometry, self.odomInput)
rospy.init_node(NAME, anonymous=True)
timeout_t = time.time() + TEST_DURATION
while not rospy.is_shutdown() and not self.success and time.time() < timeout_t:
- pub.publish(PoseDot(Velocity(TARGET_VX,TARGET_VY, 0), AngularVelocity(0,0,TARGET_VW)))
+ pub.publish(Twist(Vector3(TARGET_VX,TARGET_VY, 0), Vector3(0,0,TARGET_VW)))
time.sleep(0.1)
# display what odom thinks
#print " odom " + " x: " + str(self.odom_e.x) + " y: " + str(self.odom_e.y) + " t: " + str(self.odom_e.t)
Modified: pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomx_gt.py
===================================================================
--- pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomx_gt.py 2009-08-07 22:25:37 UTC (rev 21069)
+++ pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomx_gt.py 2009-08-07 22:25:37 UTC (rev 21070)
@@ -45,9 +45,10 @@
import sys, unittest
import os, time
import rospy, rostest
-from robot_msgs.msg import *
-from nav_msgs.msg import *
+from geometry_msgs.msg import Twist,Vector3
+from nav_msgs.msg import Odometry
+
TEST_DURATION = 10.0
TARGET_VX = 0.5
@@ -179,13 +180,13 @@
def test_base(self):
print "LNK\n"
- pub = rospy.Publisher("/cmd_vel", PoseDot)
+ pub = rospy.Publisher("/cmd_vel", Twist)
rospy.Subscriber("/base_pose_ground_truth", PoseWithRatesStamped, self.p3dInput)
rospy.Subscriber("/odom", Odometry, self.odomInput)
rospy.init_node(NAME, anonymous=True)
timeout_t = time.time() + TEST_DURATION
while not rospy.is_shutdown() and not self.success and time.time() < timeout_t:
- pub.publish(PoseDot(Velocity(TARGET_VX,TARGET_VY, 0), AngularVelocity(0,0,TARGET_VW)))
+ pub.publish(Twist(Vector3(TARGET_VX,TARGET_VY, 0), Vector3(0,0,TARGET_VW)))
time.sleep(0.1)
# display what odom thinks
#print " odom " + " x: " + str(self.odom_x) + " y: " + str(self.odom_y) + " t: " + str(self.odom_t)
Modified: pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomxy_gt.py
===================================================================
--- pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomxy_gt.py 2009-08-07 22:25:37 UTC (rev 21069)
+++ pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomxy_gt.py 2009-08-07 22:25:37 UTC (rev 21070)
@@ -45,8 +45,8 @@
import sys, unittest
import os, os.path, threading, time
import rospy, rostest
-from robot_msgs.msg import *
-from nav_msgs.msg import *
+from geometry_msgs.msg import Twist,Vector3
+from nav_msgs.msg import Odometry
TEST_DURATION = 10.0
@@ -179,13 +179,13 @@
def test_base(self):
print "LNK\n"
- pub = rospy.Publisher("/cmd_vel", PoseDot)
+ pub = rospy.Publisher("/cmd_vel", Twist)
rospy.Subscriber("/base_pose_ground_truth", PoseWithRatesStamped, self.p3dInput)
rospy.Subscriber("/odom", Odometry, self.odomInput)
rospy.init_node(NAME, anonymous=True)
timeout_t = time.time() + TEST_DURATION
while not rospy.is_shutdown() and not self.success and time.time() < timeout_t:
- pub.publish(PoseDot(Velocity(TARGET_VX,TARGET_VY, 0), AngularVelocity(0,0,TARGET_VW)))
+ pub.publish(Twist(Vector3(TARGET_VX,TARGET_VY, 0), Vector3(0,0,TARGET_VW)))
time.sleep(0.1)
# display what odom thinks
#print " odom " + " x: " + str(self.odom_x) + " y: " + str(self.odom_y) + " t: " + str(self.odom_t)
Modified: pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomxyw_gt.py
===================================================================
--- pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomxyw_gt.py 2009-08-07 22:25:37 UTC (rev 21069)
+++ pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomxyw_gt.py 2009-08-07 22:25:37 UTC (rev 21070)
@@ -45,8 +45,8 @@
import sys, unittest
import os, time
import rospy, rostest
-from robot_msgs.msg import *
-from nav_msgs.msg import *
+from geometry_msgs.msg import Twist,Vector3
+from nav_msgs.msg import Odometry
TEST_DURATION = 10.0
@@ -215,13 +215,13 @@
def test_base(self):
print "LNK\n"
- pub = rospy.Publisher("/cmd_vel", PoseDot)
+ pub = rospy.Publisher("/cmd_vel", Twist)
rospy.Subscriber("/base_pose_ground_truth", PoseWithRatesStamped, self.p3dInput)
rospy.Subscriber("/odom", Odometry, self.odomInput)
rospy.init_node(NAME, anonymous=True)
timeout_t = time.time() + TEST_DURATION
while not rospy.is_shutdown() and not self.success and time.time() < timeout_t:
- pub.publish(PoseDot(Velocity(TARGET_VX,TARGET_VY, 0), AngularVelocity(0,0,TARGET_VW)))
+ pub.publish(Twist(Vector3(TARGET_VX,TARGET_VY, 0), Vector3(0,0,TARGET_VW)))
time.sleep(0.1)
# display what odom thinks
#print " odom " + " x: " + str(self.odom_e.x) + " y: " + str(self.odom_e.y) + " t: " + str(self.odom_e.t)
Modified: pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomy_gt.py
===================================================================
--- pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomy_gt.py 2009-08-07 22:25:37 UTC (rev 21069)
+++ pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomy_gt.py 2009-08-07 22:25:37 UTC (rev 21070)
@@ -45,8 +45,8 @@
import sys, unittest
import os, time
import rospy, rostest
-from robot_msgs.msg import *
-from nav_msgs.msg import *
+from geometry_msgs.msg import Twist,Vector3
+from nav_msgs.msg import Odometry
TEST_DURATION = 10.0
@@ -179,13 +179,13 @@
def test_base(self):
print "LNK\n"
- pub = rospy.Publisher("/cmd_vel", PoseDot)
+ pub = rospy.Publisher("/cmd_vel", Twist)
rospy.Subscriber("/base_pose_ground_truth", PoseWithRatesStamped, self.p3dInput)
rospy.Subscriber("/odom", Odometry, self.odomInput)
rospy.init_node(NAME, anonymous=True)
timeout_t = time.time() + TEST_DURATION
while not rospy.is_shutdown() and not self.success and time.time() < timeout_t:
- pub.publish(PoseDot(Velocity(TARGET_VX,TARGET_VY, 0), AngularVelocity(0,0,TARGET_VW)))
+ pub.publish(Twist(Vector3(TARGET_VX,TARGET_VY, 0), Vector3(0,0,TARGET_VW)))
time.sleep(0.1)
# display what odom thinks
#print " odom " + " x: " + str(self.odom_x) + " y: " + str(self.odom_y) + " t: " + str(self.odom_t)
Modified: pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_vw_gt.py
===================================================================
--- pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_vw_gt.py 2009-08-07 22:25:37 UTC (rev 21069)
+++ pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_vw_gt.py 2009-08-07 22:25:37 UTC (rev 21070)
@@ -48,8 +48,8 @@
import sys, unittest
import os, time
import rospy, rostest
-from robot_msgs.msg import *
-from nav_msgs.msg import *
+from geometry_msgs.msg import Twist,Vector3
+from nav_msgs.msg import Odometry
TEST_DURATION = 60.0
@@ -121,13 +121,13 @@
def test_base(self):
print "LNK\n"
- pub = rospy.Publisher("/cmd_vel", PoseDot)
+ pub = rospy.Publisher("/cmd_vel", Twist)
rospy.Subscriber("/base_pose_ground_truth", PoseWithRatesStamped, self.p3dInput)
rospy.Subscriber("/odom", Odometry, self.odomInput)
rospy.init_node(NAME, anonymous=True)
timeout_t = time.time() + TEST_DURATION
while not rospy.is_shutdown() and not self.success and time.time() < timeout_t:
- pub.publish(PoseDot(Velocity(0.0,0.0,0),AngularVelocity(0,0,TARGET_VW)))
+ pub.publish(Twist(Vector3(0.0,0.0,0), Vector3(0,0,TARGET_VW)))
time.sleep(0.1)
self.assert_(self.success)
Modified: pkg/trunk/highlevel/executive_python/manifest.xml
===================================================================
--- pkg/trunk/highlevel/executive_python/manifest.xml 2009-08-07 22:25:37 UTC (rev 21069)
+++ pkg/trunk/highlevel/executive_python/manifest.xml 2009-08-07 22:25:37 UTC (rev 21070)
@@ -6,6 +6,6 @@
<depend package="rospy" />
<depend package="nav_robot_actions" />
<depend package="std_msgs" />
- <depend package="robot_msgs" />
+ <depend package="geometry_msgs" />
<depend package="pr2_robot_actions" />
</package>
Modified: pkg/trunk/highlevel/executive_python/src/stuck_adapter.py
===================================================================
--- pkg/trunk/highlevel/executive_python/src/stuck_adapter.py 2009-08-07 22:25:37 UTC (rev 21069)
+++ pkg/trunk/highlevel/executive_python/src/stuck_adapter.py 2009-08-07 22:25:37 UTC (rev 21070)
@@ -39,12 +39,12 @@
import rospy
import random
from pr2_msgs.msg import BaseControllerState
-from robot_msgs.msg import PoseDot
+from geometry_msgs.msg import Twist,Vector3
class StuckAdapter:
def __init__(self, state_topic, vel_topic, timeout):
rospy.Subscriber(state_topic, BaseControllerState, self.update)
- self.pub = rospy.Publisher(vel_topic, PoseDot)
+ self.pub = rospy.Publisher(vel_topic, Twist)
self.state = None
self.state_topic = state_topic
self.goal_topic = vel_topic
@@ -67,10 +67,10 @@
#to get unstuck... we're going to try to go at max speed forward until we are unstuck
while self.stuck() and (begin + self.timeout) < rospy.get_time():
start = rospy.get_time()
- vel = PoseDot()
- vel.vel.vx = 1.0
- vel.vel.vy = 0.0
- vel.ang_vel.vz = 0.0
+ vel = Twist()
+ vel.linear.x = 1.0
+ vel.linear.y = 0.0
+ vel.angular.z = 0.0
#publish the command to the base... hope we don't hit anything
self.pub.publish(vel)
end = rospy.get_time()
@@ -79,9 +79,9 @@
rospy.sleep(sleep_time)
#make sure to publish zeros when we're done
- vel = PoseDot()
- vel.vel.vx = 0.0
- vel.vel.vy = 0.0
- vel.ang_vel.vz = 0.0
+ vel = Twist()
+ vel.linear.x = 0.0
+ vel.linear.y = 0.0
+ vel.angular.z = 0.0
#publish the command to the base... hope we don't hit anything
self.pub.publish(vel)
Modified: pkg/trunk/pr2/hot_box_test/base_shuffle.py
===================================================================
--- pkg/trunk/pr2/hot_box_test/base_shuffle.py 2009-08-07 22:25:37 UTC (rev 21069)
+++ pkg/trunk/pr2/hot_box_test/base_shuffle.py 2009-08-07 22:25:37 UTC (rev 21070)
@@ -46,7 +46,7 @@
# Loads interface with the robot.
import rospy
-from robot_msgs.msg import PoseDot
+from geometry_msgs.msg import Twist,Vector3
from mechanism_msgs.srv import SpawnController, KillController
spawn_controller = rospy.ServiceProxy('spawn_controller', SpawnController)
@@ -70,21 +70,21 @@
# Publishes velocity every 0.05s, calculates number of publishes
num_publishes = int(distance * 20 * 2)
- cmd_vel = PoseDot()
+ cmd_vel = Twist()
# Change to 0 for a controller with no bkwd bias
- cmd_vel.vel.vx = float(-0.01)
- cmd_vel.vel.vy = float(0)
- cmd_vel.vel.vz = float(0)
- cmd_vel.ang_vel.vx = float(0)
- cmd_vel.ang_vel.vy = float(0)
- cmd_vel.ang_vel.vz = float(0)
+ cmd_vel.linear.x = float(-0.01)
+ cmd_vel.linear.y = float(0)
+ cmd_vel.linear.z = float(0)
+ cmd_vel.angular.x = float(0)
+ cmd_vel.angular.y = float(0)
+ cmd_vel.angular.z = float(0)
- base_vel = rospy.Publisher('cmd_vel', PoseDot)
+ base_vel = rospy.Publisher('cmd_vel', Twist)
try:
while not rospy.is_shutdown():
# Set velocity
- cmd_vel.vel.vy = float(0.4)
+ cmd_vel.linear.y = float(0.4)
# Extra iteration adds a negative bias in controller
for i in range(0, num_publishes - 1):
base_vel.publish(cmd_vel)
@@ -95,7 +95,7 @@
if rospy.is_shutdown():
break
- cmd_vel.vel.vy = float(-0.4)
+ cmd_vel.linear.y = float(-0.4)
for i in range(0, num_publishes):
base_vel.publish(cmd_vel)
if rospy.is_shutdown():
@@ -106,7 +106,7 @@
traceback.print_exc()
finally:
# Set velocity = 0
- cmd_vel.vel.vy = float(0)
+ cmd_vel.linear.y = float(0)
base_vel.publish(cmd_vel)
kill_controller('base_controller')
Modified: pkg/trunk/pr2/hot_box_test/base_swivvel.py
===================================================================
--- pkg/trunk/pr2/hot_box_test/base_swivvel.py 2009-08-07 22:25:37 UTC (rev 21069)
+++ pkg/trunk/pr2/hot_box_test/base_swivvel.py 2009-08-07 22:25:37 UTC (rev 21070)
@@ -45,7 +45,7 @@
# Loads interface with the robot.
import rospy
-from robot_msgs.msg import PoseDot
+from geometry_msgs.msg import Twist,Vector3
from mechanism_control import mechanism
@@ -68,15 +68,15 @@
# Publishes velocity every 0.05s, calculates number of publishes
num_publishes = int(distance * 20 * 2)
- cmd_vel = PoseDot()
- cmd_vel.vel.vx = float(0)
- cmd_vel.vel.vy = float(0)
- cmd_vel.vel.vz = float(0)
- cmd_vel.ang_vel.vx = float(0)
- cmd_vel.ang_vel.vy = float(0)
- cmd_vel.ang_vel.vz = float(0)
+ cmd_vel = Twist()
+ cmd_vel.linear.x = float(0)
+ cmd_vel.linear.y = float(0)
+ cmd_vel.linear.z = float(0)
+ cmd_vel.angular.x = float(0)
+ cmd_vel.angular.y = float(0)
+ cmd_vel.angular.z = float(0)
- base_vel = rospy.Publisher('cmd_vel', PoseDot)
+ base_vel = rospy.Publisher('cmd_vel', Twist)
try:
while not rospy.is_shutdown():
Modified: pkg/trunk/pr2/hot_box_test/manifest.xml
===================================================================
--- pkg/trunk/pr2/hot_box_test/manifest.xml 2009-08-07 22:25:37 UTC (rev 21069)
+++ pkg/trunk/pr2/hot_box_test/manifest.xml 2009-08-07 22:25:37 UTC (rev 21070)
@@ -18,7 +18,7 @@
<depend package="pr2_default_controllers" />
<depend package="life_test" />
<depend package="ocean_battery_driver" />
- <depend package="robot_msgs" />
+ <depend package="geometry_msgs" />
<depend package="mechanism_msgs" />
</package>
Modified: pkg/trunk/sandbox/annotated_map_builder/manifest.xml
===================================================================
--- pkg/trunk/sandbox/annotated_map_builder/manifest.xml 2009-08-07 22:25:37 UTC (rev 21069)
+++ pkg/trunk/sandbox/annotated_map_builder/manifest.xml 2009-08-07 22:25:37 UTC (rev 21070)
@@ -6,7 +6,7 @@
<depend package="rospy" />
<depend package="nav_robot_actions" />
<depend package="std_msgs" />
- <depend package="robot_msgs" />
+ <depend package="geometry_msgs" />
<depend package="pr2_robot_actions" />
<depend package="robot_actions" />
<depend package="milestone2_actions" />
Modified: pkg/trunk/sandbox/annotated_map_builder/src/annotated_map_builder/move_head_action.py
===================================================================
--- pkg/trunk/sandbox/annotated_map_builder/src/annotated_map_builder/move_head_action.py 2009-08-07 22:25:37 UTC (rev 21069)
+++ pkg/trunk/sandbox/annotated_map_builder/src/annotated_map_builder/move_head_action.py 2009-08-07 22:25:37 UTC (rev 21070)
@@ -50,7 +50,7 @@
from annotated_map_builder.wait_for_k_messages_adapter import WaitForKMessagesAdapter
from pr2_msgs.msg import BaseControllerState
-from robot_msgs.msg import PoseDot
+from geometry_msgs.msg import Twist
from mechanism_msgs.msg import JointStates, JointState
Modified: pkg/trunk/sandbox/annotated_map_builder/src/annotated_map_builder/move_head_action2.py
===================================================================
--- pkg/trunk/sandbox/annotated_map_builder/src/annotated_map_builder/move_head_action2.py 2009-08-07 22:25:37 UTC (rev 21069)
+++ pkg/trunk/sandbox/annotated_map_builder/src/annotated_map_builder/move_head_action2.py 2009-08-07 22:25:37 UTC (rev 21070)
@@ -50,7 +50,7 @@
from annotated_map_builder.wait_for_k_messages_adapter import WaitForKMessagesAdapter
from pr2_msgs.msg import BaseControllerState
-from robot_msgs.msg import PoseDot
+from geometry_msgs.msg import Twist
from mechanism_msgs.msg import JointStates, JointState
Modified: pkg/trunk/sandbox/annotated_map_builder/src/annotated_map_builder/wait_for_k_messages_adapter.py
===================================================================
--- pkg/trunk/sandbox/annotated_map_builder/src/annotated_map_builder/wait_for_k_messages_adapter.py 2009-08-07 22:25:37 UTC (rev 21069)
+++ pkg/trunk/sandbox/annotated_map_builder/src/annotated_map_builder/wait_for_k_messages_adapter.py 2009-08-07 22:25:37 UTC (rev 21070)
@@ -39,8 +39,7 @@
import rospy
import random
from pr2_msgs.msg import BaseControllerState
-from robot_msgs.msg import PoseDot
-from robot_msgs.msg import PoseDot
+from geometry_msgs.msg import Twist
from annotated_map_builder.msg import *
Modified: pkg/trunk/sandbox/annotated_map_builder/src/annotated_map_builder/wait_for_k_messages_adapter2.py
===================================================================
--- pkg/trunk/sandbox/annotated_map_builder/src/annotated_map_builder/wait_for_k_messages_adapter2.py 2009-08-07 22:25:37 UTC (rev 21069)
+++ pkg/trunk/sandbox/annotated_map_builder/src/annotated_map_builder/wait_for_k_messages_adapter2.py 2009-08-07 22:25:37 UTC (rev 21070)
@@ -39,8 +39,7 @@
import rospy
import random
from pr2_msgs.msg import BaseControllerState
-from robot_msgs.msg import PoseDot
-from robot_msgs.msg import PoseDot
+from geometry_msgs.msg import Twist
class WaitForKMessagesAdapter:
def __init__(self, message_topic,msgType, count, timeout):
Modified: pkg/trunk/sandbox/annotated_map_builder/src/annotated_map_builder/wait_for_multiple_head_configs.py
===================================================================
--- pkg/trunk/sandbox/annotated_map_builder/src/annotated_map_builder/wait_for_multiple_head_configs.py 2009-08-07 22:25:37 UTC (rev 21069)
+++ pkg/trunk/sandbox/annotated_map_builder/src/annotated_map_builder/wait_for_multiple_head_configs.py 2009-08-07 22:25:37 UTC (rev 21070)
@@ -39,7 +39,7 @@
import rospy
import random
from pr2_msgs.msg import BaseControllerState
-from robot_msgs.msg import PoseDot
+from geometry_msgs.msg import Twist
from mechanism_msgs.msg import JointStates, JointState
Modified: pkg/trunk/sandbox/annotated_map_builder/test/test_head.py
===================================================================
--- pkg/trunk/sandbox/annotated_map_builder/test/test_head.py 2009-08-07 22:25:37 UTC (rev 21069)
+++ pkg/trunk/sandbox/annotated_map_builder/test/test_head.py 2009-08-07 22:25:37 UTC (rev 21070)
@@ -50,7 +50,7 @@
from annotated_map_builder.move_head_adapter import *
from pr2_msgs.msg import BaseControllerState
-from robot_msgs.msg import PoseDot
+from geometry_msgs.msg import Twist
from robot_msgs.msg import JointCmd
from python_actions import *
Modified: pkg/trunk/sandbox/annotated_map_builder/test/test_head2.py
===================================================================
--- pkg/trunk/sandbox/annotated_map_builder/test/test_head2.py 2009-08-07 22:25:37 UTC (rev 21069)
+++ pkg/trunk/sandbox/annotated_map_builder/test/test_head2.py 2009-08-07 22:25:37 UTC (rev 21070)
@@ -50,7 +50,7 @@
from annotated_map_builder.wait_for_k_messages_adapter import WaitForKMessagesAdapter
from pr2_msgs.msg import BaseControllerState
-from robot_msgs.msg import PoseDot
+from geometry_msgs.msg import Twist
from robot_msgs.msg import JointCmd
from python_actions import *
Modified: pkg/trunk/sandbox/person_follower/src/move_head_action.py
===================================================================
--- pkg/trunk/sandbox/person_follower/src/move_head_action.py 2009-08-07 22:25:37 UTC (rev 21069)
+++ pkg/trunk/sandbox/person_follower/src/move_head_action.py 2009-08-07 22:25:37 UTC (rev 21070)
@@ -50,7 +50,7 @@
from annotated_map_builder.wait_for_k_messages_adapter import WaitForKMessagesAdapter
from pr2_msgs.msg import BaseControllerState
-from robot_msgs.msg import PoseDot
+from geometry_msgs.msg import Twist
from mechanism_msgs.msg import JointStates, JointState
Modified: pkg/trunk/sandbox/person_follower/src/wait_for_k_messages_adapter.py
===================================================================
--- pkg/trunk/sandbox/person_follower/src/wait_for_k_messages_adapter.py 2009-08-07 22:25:37 UTC (rev 21069)
+++ pkg/trunk/sandbox/person_follower/src/wait_for_k_messages_adapter.py 2009-08-07 22:25:37 UTC (rev 21070)
@@ -39,8 +39,7 @@
import rospy
import random
from pr2_msgs.msg import BaseControllerState
-from robot_msgs.msg import PoseDot
-from robot_msgs.msg import PoseDot
+from geometry_msgs.msg import Twist,Vector3
from annotated_map_builder.msg import *
Modified: pkg/trunk/sandbox/person_follower/src/wait_for_k_messages_adapter2.py
===================================================================
--- pkg/trunk/sandbox/person_follower/src/wait_for_k_messages_adapter2.py 2009-08-07 22:25:37 UTC (rev 21069)
+++ pkg/trunk/sandbox/person_follower/src/wait_for_k_messages_adapter2.py 2009-08-07 22:25:37 UTC (rev 21070)
@@ -39,8 +39,7 @@
import rospy
import random
from pr2_msgs.msg import BaseControllerState
-from robot_msgs.msg import PoseDot
-from robot_msgs.msg import PoseDot
+from geometry_msgs.msg import Twist
class WaitForKMessagesAdapter:
def __init__(self, message_topic,msgType, count, timeout):
Modified: pkg/trunk/sandbox/person_follower/src/wait_for_multiple_head_configs.py
===================================================================
--- pkg/trunk/sandbox/person_follower/src/wait_for_multiple_head_configs.py 2009-08-07 22:25:37 UTC (rev 21069)
+++ pkg/trunk/sandbox/person_follower/src/wait_for_multiple_head_configs.py 2009-08-07 22:25:37 UTC (rev 21070)
@@ -39,7 +39,7 @@
import rospy
import random
from pr2_msgs.msg import BaseControllerState
-from robot_msgs.msg import PoseDot
+from geometry_msgs.msg import Twist
from mechanism_msgs.msg import JointStates, JointState
class WaitForMultipleHeadConfigsAdapter:
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|