shadowhand_publisher.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # Copyright 2011 Shadow Robot Company Ltd.
00004 #
00005 # This program is free software: you can redistribute it and/or modify it
00006 # under the terms of the GNU General Public License as published by the Free
00007 # Software Foundation, either version 2 of the License, or (at your option)
00008 # any later version.
00009 #
00010 # This program is distributed in the hope that it will be useful, but WITHOUT
00011 # ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
00012 # FITNESS FOR A PARTICULAR PURPOSE.  See the GNU General Public License for
00013 # more details.
00014 #
00015 # You should have received a copy of the GNU General Public License along
00016 # with this program.  If not, see <http://www.gnu.org/licenses/>.
00017 #
00018 # -*- coding: utf-8 -*-
00019 """
00020 This is an example showing how to publish command messages to the hand.
00021 """
00022 
00023 
00024 import roslib; roslib.load_manifest('sr_example')
00025 import rospy
00026 import time
00027 import math
00028 
00029 from std_msgs.msg import Float64
00030 
00031 # type of controller that is running 
00032 # If you use the simulated hand (in gazebo) use the mixed controllers
00033 controller_type = "_mixed_position_velocity_controller"
00034 # If you use the real hand, generally use the position controller (comment the previous line and uncomment the following)
00035 #controller_type = "_position_controller"
00036     
00037 def talker():
00038     """
00039     The Publisher publishes two commands to move joint FFJ0 and RFJ0
00040 
00041     """
00042     joint1 = 'ffj0'
00043     joint2 = 'rfj0'
00044     
00045     #Initalize the ROS node
00046     rospy.init_node('shadowhand_command_publisher_python')
00047 
00048     pub1 = rospy.Publisher('sh_'+ joint1 + controller_type + '/command', Float64, latch=True)
00049     pub2 = rospy.Publisher('sh_'+ joint2 + controller_type + '/command', Float64, latch=True)
00050     
00051 
00052     # define a new target value for the joint position.
00053     # The position controllers expect their commands in radians
00054     new_target_1 = math.radians(0.0)
00055     new_target_2 = math.radians(0.0)
00056 
00057     time.sleep(1)
00058     print "publishing"
00059     
00060     #This will move the joint ffj0 to the defined target (0 degrees)
00061     pub1.publish(new_target_1)
00062     
00063     #This will move the joint rfj0 to the defined target (0 degrees)
00064     pub2.publish(new_target_2)
00065 
00066 
00067 if __name__ == '__main__':
00068     try:
00069         talker()
00070     except rospy.ROSInterruptException: pass


sr_example
Author(s): Ugo Cupcic
autogenerated on Mon Oct 6 2014 07:49:30