Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025 import sys
00026 import unittest
00027 import time
00028 import rostest
00029 import rospy
00030 import geometry_msgs.msg
00031 import sensor_msgs.msg
00032
00033
00034 class TestJoyTwist(unittest.TestCase):
00035
00036 def setUp(self):
00037 rospy.init_node('test_joy_twist_node', anonymous=True)
00038 self.pub = rospy.Publisher('joy', sensor_msgs.msg.Joy)
00039 rospy.Subscriber('cmd_vel', geometry_msgs.msg.Twist, callback=self.callback)
00040
00041 while (not rospy.has_param("~publish_joy")) and (not rospy.get_param("~expect_cmd_vel")):
00042 time.sleep(0.1)
00043
00044 self.expect_cmd_vel = rospy.get_param("~expect_cmd_vel")
00045 self.joy_msg = rospy.get_param("~publish_joy")
00046 self.received_cmd_vel = None
00047
00048 def test_expected(self):
00049 pub_joy = sensor_msgs.msg.Joy()
00050 pub_joy.axes.extend(self.joy_msg['axes'])
00051 pub_joy.buttons.extend(self.joy_msg['buttons'])
00052 while self.received_cmd_vel is None:
00053 self.pub.publish(pub_joy)
00054 time.sleep(0.1)
00055
00056 self.assertAlmostEqual(self.received_cmd_vel.linear.x, self.expect_cmd_vel['linear']['x'])
00057 self.assertAlmostEqual(self.received_cmd_vel.linear.y, self.expect_cmd_vel['linear']['y'])
00058 self.assertAlmostEqual(self.received_cmd_vel.linear.z, self.expect_cmd_vel['linear']['z'])
00059 self.assertAlmostEqual(self.received_cmd_vel.angular.x, self.expect_cmd_vel['angular']['x'])
00060 self.assertAlmostEqual(self.received_cmd_vel.angular.y, self.expect_cmd_vel['angular']['y'])
00061 self.assertAlmostEqual(self.received_cmd_vel.angular.z, self.expect_cmd_vel['angular']['z'])
00062
00063 def callback(self, msg):
00064 self.received_cmd_vel = geometry_msgs.msg.Twist()
00065 self.received_cmd_vel = msg
00066
00067
00068 if __name__ == '__main__':
00069 rostest.rosrun('teleop_twist_joy', 'test_joy_twist', TestJoyTwist)