shadowhand_subscriber.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 
00019 """
00020 This is a simple subscriber example, subscribing to the joint_states topic and printing out the data in a per-joint basis
00021 To see how the joint_states topic looks like you can type the following in a terminal:
00022 > rostopic echo /joint_states
00023 
00024 """
00025 
00026 import roslib; roslib.load_manifest('sr_example')
00027 import rospy
00028 import math
00029 from sensor_msgs.msg import JointState
00030 
00031 def callback(joint_state):
00032     """
00033     The callback function for the topic /joint_states
00034 
00035     It just displays the received information on the console.
00036 
00037     @param joint_state: the message containing the joints data.
00038     """
00039     for joint_name, position, velocity, effort in zip(joint_state.name, joint_state.position, joint_state.velocity, joint_state.effort):
00040         rospy.loginfo("[%s] : Pos = %f | Pos_deg = %f | Vel = %f | Effort = %f",
00041                       joint_name, position, math.degrees(position), velocity, effort)
00042 
00043 def listener():
00044     """
00045     Initialize the ROS node and the topic to which it subscribes.
00046     """
00047     rospy.init_node('shadowhand_joint_states_subscriber_python', anonymous=True)
00048 
00049     rospy.Subscriber("joint_states", JointState, callback)
00050 
00051     rospy.spin()
00052 
00053 if __name__ == '__main__':
00054     listener()


sr_example
Author(s): Ugo Cupcic
autogenerated on Fri Aug 21 2015 12:25:43