test_publisher_twist_series.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
4 #
5 # Licensed under the Apache License, Version 2.0 (the "License");
6 # you may not use this file except in compliance with the License.
7 # You may obtain a copy of the License at
8 #
9 # http://www.apache.org/licenses/LICENSE-2.0
10 #
11 # Unless required by applicable law or agreed to in writing, software
12 # distributed under the License is distributed on an "AS IS" BASIS,
13 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 # See the License for the specific language governing permissions and
15 # limitations under the License.
16 
17 
18 import rospy
19 from geometry_msgs.msg import TwistStamped
20 
21 def twistPub():
22  rospy.init_node("test_publisher_twist_series", anonymous=True)
23 
24  pub = rospy.Publisher("twist_controller/command_twist_stamped", TwistStamped, queue_size=1)
25 
26  rospy.sleep(1.0)
27 
28  twist_msg = TwistStamped()
29  twist_msg.header.stamp = rospy.Time.now()
30  twist_msg.header.frame_id = "arm_left_base_link"
31  twist_msg.twist.linear.x = 0
32  twist_msg.twist.linear.y = 0
33  twist_msg.twist.linear.z = 0
34  twist_msg.twist.angular.x = 0
35  twist_msg.twist.angular.y = 0
36  twist_msg.twist.angular.z = 0
37 
38  rate = 50
39  r = rospy.Rate(rate)
40 
41  for i in range(0, 5*rate, 1):
42  twist_msg.header.stamp = rospy.Time.now()
43  twist_msg.header.frame_id = "arm_left_base_link"
44  twist_msg.twist.linear.x = 0
45  twist_msg.twist.linear.y = 0
46  twist_msg.twist.linear.z = -0.02
47  twist_msg.twist.angular.x = 0
48  twist_msg.twist.angular.y = 0
49  twist_msg.twist.angular.z = 0
50  pub.publish(twist_msg)
51  r.sleep()
52 
53  #pause
54  for i in range(0, 1*rate, 1):
55  twist_msg.header.stamp = rospy.Time.now()
56  twist_msg.header.frame_id = "arm_left_base_link"
57  twist_msg.twist.linear.x = 0
58  twist_msg.twist.linear.y = 0
59  twist_msg.twist.linear.z = 0
60  twist_msg.twist.angular.x = 0
61  twist_msg.twist.angular.y = 0
62  twist_msg.twist.angular.z = 0
63  pub.publish(twist_msg)
64  r.sleep()
65 
66  for i in range(0, 5*rate, 1):
67  twist_msg.header.stamp = rospy.Time.now()
68  twist_msg.header.frame_id = "arm_left_base_link"
69  twist_msg.twist.linear.x = 0
70  twist_msg.twist.linear.y = 0
71  twist_msg.twist.linear.z = 0.02
72  twist_msg.twist.angular.x = 0
73  twist_msg.twist.angular.y = 0
74  twist_msg.twist.angular.z = 0
75  pub.publish(twist_msg)
76  r.sleep()
77 
78  #pause
79  for i in range(0, 1*rate, 1):
80  twist_msg.header.stamp = rospy.Time.now()
81  twist_msg.header.frame_id = "arm_left_base_link"
82  twist_msg.twist.linear.x = 0
83  twist_msg.twist.linear.y = 0
84  twist_msg.twist.linear.z = 0
85  twist_msg.twist.angular.x = 0
86  twist_msg.twist.angular.y = 0
87  twist_msg.twist.angular.z = 0
88  pub.publish(twist_msg)
89  r.sleep()
90 
91  print("done")
92 
93 if __name__ == '__main__':
94  try:
95  twistPub()
96  except rospy.ROSInterruptException: pass
97 


cob_twist_controller
Author(s): Felix Messmer , Marco Bezzon , Christoph Mark , Francisco Moreno
autogenerated on Thu Apr 8 2021 02:40:01