$search
00001 #!/usr/bin/python 00002 00003 import roslib 00004 roslib.load_manifest('ipa_canopen_tutorials') 00005 import rospy 00006 from cob_srvs.srv import Trigger 00007 from brics_actuator.msg import JointVelocities 00008 from brics_actuator.msg import JointValue 00009 00010 rospy.init_node("ipa_canopen_test") 00011 00012 00013 rospy.wait_for_service('/mockarm_controller/init') 00014 initService = rospy.ServiceProxy('/mockarm_controller/init', Trigger) 00015 resp = initService() 00016 print resp 00017 00018 velPublisher = rospy.Publisher('/mockarm_controller/command_vel', JointVelocities) 00019 rospy.sleep(2.0) 00020 v = JointVelocities() 00021 vv = JointValue() 00022 vv.timeStamp = rospy.Time.now() 00023 vv.joint_uri = "mockarm_1_joint" 00024 v.velocities = [vv] 00025 00026 while not rospy.is_shutdown(): 00027 v.velocities[0].value = 0.2 00028 velPublisher.publish(v) 00029 00030 rospy.sleep(1.0) 00031 00032 v.velocities[0].value = 0 00033 velPublisher.publish(v) 00034 00035 rospy.sleep(1.0) 00036 00037 v.velocities[0].value = - 0.2 00038 velPublisher.publish(v) 00039 00040 rospy.sleep(1.0) 00041 00042 v.velocities[0].value = 0 00043 velPublisher.publish(v) 00044 00045 rospy.sleep(1.0)