sr_subscriber_example.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # Copyright 2011 Shadow Robot Company Ltd.
4 #
5 # This program is free software: you can redistribute it and/or modify it
6 # under the terms of the GNU General Public License as published by the Free
7 # Software Foundation version 2 of the License.
8 #
9 # This program is distributed in the hope that it will be useful, but WITHOUT
10 # ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
11 # FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
12 # more details.
13 #
14 # You should have received a copy of the GNU General Public License along
15 # with this program. If not, see <http://www.gnu.org/licenses/>.
16 
17 """
18 This is a simple subscriber example, subscribing to the joint_states topic and printing
19 out the data in a per-joint basis.
20 To view the joint_states, type the following in a terminal:
21 > rostopic echo /joint_states
22 
23 """
24 
25 import roslib
26 import rospy
27 import math
28 from sensor_msgs.msg import JointState
29 
30 roslib.load_manifest('sr_example')
31 
32 
33 def callback(joint_state):
34  """
35  The callback function for the topic /joint_states
36 
37  It displays the received information in the console.
38 
39  @param joint_state: the message containing the joints data.
40  """
41  for joint_name, position, velocity, effort in zip(joint_state.name, joint_state.position,
42  joint_state.velocity, joint_state.effort):
43  rospy.loginfo(
44  "[%s] : Pos = %f | Pos_deg = %f | Vel = %f | Effort = %f",
45  joint_name, position, math.degrees(position), velocity, effort)
46 
47 
48 def listener():
49  """
50  Initialize the ROS node and the topic to which it subscribes.
51  """
52  rospy.init_node(
53  'subscriber_example', anonymous=True)
54 
55  # Subscribes to topic 'joint_states'
56  rospy.Subscriber("joint_states", JointState, callback)
57 
58  rospy.spin()
59 
60 if __name__ == '__main__':
61  listener()


sr_example
Author(s): Ugo Cupcic
autogenerated on Wed Oct 14 2020 04:05:12