compute_joint_0_target.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # Copyright 2019 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 import roslib
18 import rospy
19 
20 from sensor_msgs.msg import JointState
21 from std_msgs.msg import Float64
22 
23 
24 class Merger(object):
25 
26  def __init__(self):
27  self.subscriber = rospy.Subscriber(
28  "/joint_states", JointState, self.callback)
29  self.publisher = rospy.Publisher("/lfj0_target", Float64)
30 
31  def callback(self, data):
32  msg_to_send = Float64()
33 
34  msg_to_send.data = data.position[17] + data.position[18]
35 
36  self.publisher.publish(msg_to_send)
37 
38 if __name__ == '__main__':
39  rospy.init_node("merger", anonymous=True)
40  merger = Merger()
41  rospy.spin()


sr_robot_lib
Author(s): Ugo Cupcic, Toni Oliver
autogenerated on Tue Oct 13 2020 04:01:57