39 PKG =
'gazebo_plugins'
40 NAME =
'test_link_pose'
44 roslib.load_manifest(PKG)
47 import os, os.path, threading, time
50 from geometry_msgs.msg
import Pose
51 from geometry_msgs.msg
import Twist
52 from tf
import transformations
56 super(LinkPoseTest, self).
__init__(*args)
95 print(
"P3D pose translan: " +
"x: " + str(p3d.pose.pose.position.x))
96 print(
" " +
"y: " + str(p3d.pose.pose.position.y))
97 print(
" " +
"z: " + str(p3d.pose.pose.position.z))
98 print(
"P3D pose rotation: " +
"x: " + str(p3d.pose.pose.orientation.x))
99 print(
" " +
"y: " + str(p3d.pose.pose.orientation.y))
100 print(
" " +
"z: " + str(p3d.pose.pose.orientation.z))
101 print(
" " +
"w: " + str(p3d.pose.pose.orientation.w))
102 print(
"P3D rate translan: " +
"x: " + str(p3d.twist.twist.linear.x))
103 print(
" " +
"y: " + str(p3d.twist.twist.linear.y))
104 print(
" " +
"z: " + str(p3d.twist.twist.linear.z))
105 print(
"P3D rate rotation: " +
"x: " + str(p3d.twist.twist.angular.x))
106 print(
" " +
"y: " + str(p3d.twist.twist.angular.y))
107 print(
" " +
"z: " + str(p3d.twist.twist.angular.z))
121 error = math.sqrt(tmpx*tmpx+tmpy*tmpy+tmpz*tmpz)
146 rospy.init_node(NAME, anonymous=
True)
157 rospy.stdinfo(
"Waiting for test to start at time [%s]"% self.
test_start_time)
164 start_t = time.time()
166 while not rospy.is_shutdown()
and not self.
success and time.time() < timeout_t:
171 if __name__ ==
'__main__':
172 print(
"Waiting for test to start at time")
173 rostest.run(PKG, sys.argv[0], LinkPoseTest, sys.argv)