test_publisher_vel.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 import math
20 from std_msgs.msg import Float64MultiArray
21 
22 def velPub():
23  rospy.init_node("test_publisher_vel", anonymous=True)
24 
25  pub_vel = rospy.Publisher("joint_group_velocity_controller/command", Float64MultiArray, queue_size=1)
26  rospy.sleep(1.0)
27 
28  freq = 100.0
29  r = rospy.Rate(freq)
30 
31  joint_idx = 2
32 
33  a = 0.1#2.0
34  b = 0.1 * (2.0*math.pi/freq)
35  c = 0.0 #math.pi
36  d = 0.0
37  i = 0.0
38 
39  vel_msg = Float64MultiArray()
40  vel_msg.data = [0.0] * 7
41 
42  while not rospy.is_shutdown():
43  vel = a*math.sin(b*i+c) + d
44  #print("vel: ", vel)
45  vel_msg.data[joint_idx] = vel
46  pub_vel.publish(vel_msg)
47  i += 1.0
48  r.sleep()
49 
50 if __name__ == '__main__':
51  try:
52  velPub()
53  except rospy.ROSInterruptException: pass


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