test_publisher_vel.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00004 #
00005 # Licensed under the Apache License, Version 2.0 (the "License");
00006 # you may not use this file except in compliance with the License.
00007 # You may obtain a copy of the License at
00008 #
00009 #   http://www.apache.org/licenses/LICENSE-2.0
00010 #
00011 # Unless required by applicable law or agreed to in writing, software
00012 # distributed under the License is distributed on an "AS IS" BASIS,
00013 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00014 # See the License for the specific language governing permissions and
00015 # limitations under the License.
00016 
00017 
00018 import rospy
00019 import math
00020 from std_msgs.msg import Float64MultiArray
00021 
00022 def velPub():
00023   rospy.init_node("test_publisher_vel", anonymous=True)
00024 
00025   pub_vel = rospy.Publisher("joint_group_velocity_controller/command", Float64MultiArray, queue_size=1)
00026   rospy.sleep(1.0)
00027 
00028   freq = 100.0
00029   r = rospy.Rate(freq)
00030   
00031   joint_idx = 2
00032 
00033   a = 0.1#2.0
00034   b = 0.1 * (2.0*math.pi/freq)
00035   c = 0.0 #math.pi
00036   d = 0.0
00037   i = 0.0
00038   
00039   vel_msg = Float64MultiArray()
00040   vel_msg.data = [0.0] * 7
00041 
00042   while not rospy.is_shutdown():
00043     vel = a*math.sin(b*i+c) + d
00044     #print("vel: ", vel)
00045     vel_msg.data[joint_idx] = vel
00046     pub_vel.publish(vel_msg)
00047     i += 1.0
00048     r.sleep()
00049 
00050 if __name__ == '__main__':
00051   try:
00052       velPub()
00053   except rospy.ROSInterruptException: pass


cob_twist_controller
Author(s): Felix Messmer , Marco Bezzon , Christoph Mark , Francisco Moreno
autogenerated on Thu Jun 6 2019 21:19:26