Main Page
Namespaces
Classes
Files
File List
File Members
scripts
joint_state_pruner.py
Go to the documentation of this file.
1
#!/usr/bin/env python
2
# -*- coding: utf-8 -*-
3
4
import
rospy
5
from
sensor_msgs.msg
import
JointState
6
7
class
JointStatePruner
():
8
def
__init__
(self):
9
rospy.init_node(
'joint_state_pruner'
, anonymous=
True
)
10
self.
pruned_pub
= rospy.Publisher(
"/joint_states_pruned"
, JointState)
11
rospy.Subscriber(
"/joint_states"
, JointState, self.
joint_state_callback
)
12
rospy.spin()
13
14
15
def
joint_state_callback
(self,js):
16
js.effort = []
17
js.velocity = []
18
self.pruned_pub.publish(js)
19
20
if
__name__ ==
'__main__'
:
21
jsp =
JointStatePruner
()
joint_state_pruner.JointStatePruner
Definition:
joint_state_pruner.py:7
joint_state_pruner.JointStatePruner.__init__
def __init__(self)
Definition:
joint_state_pruner.py:8
joint_state_pruner.JointStatePruner.joint_state_callback
def joint_state_callback(self, js)
Definition:
joint_state_pruner.py:15
joint_state_pruner.JointStatePruner.pruned_pub
pruned_pub
Definition:
joint_state_pruner.py:10
jsk_topic_tools
Author(s): Kei Okada
, Yusuke Furuta
autogenerated on Tue Feb 6 2018 03:45:19