30 import geometry_msgs.msg
    31 import sensor_msgs.msg
    37         rospy.init_node(
'test_joy_twist_node', anonymous=
True)
    38         self.
pub = rospy.Publisher(
'joy', sensor_msgs.msg.Joy)
    39         rospy.Subscriber(
'cmd_vel', geometry_msgs.msg.Twist, callback=self.
callback)
    41         while (
not rospy.has_param(
"~publish_joy")) 
and (
not rospy.get_param(
"~expect_cmd_vel")):
    45         self.
joy_msg = rospy.get_param(
"~publish_joy")
    49         pub_joy = sensor_msgs.msg.Joy()
    50         pub_joy.axes.extend(self.
joy_msg[
'axes'])
    51         pub_joy.buttons.extend(self.
joy_msg[
'buttons'])
    53             self.
pub.publish(pub_joy)
    68 if __name__ == 
'__main__':
    69     rostest.rosrun(
'teleop_twist_joy', 
'test_joy_twist', TestJoyTwist)