43 roslib.load_manifest(
'fingertip_pressure')
47 from fingertip_pressure.msg
import PressureInfo, PressureInfoElement
48 from pr2_msgs.msg
import PressureState
49 from visualization_msgs.msg
import Marker
51 from geometry_msgs.msg
import Vector3
54 ( 0.026, 0.007, 0.000, 0.010, 0.010, 0.015),
55 ( 0.010, 0.010,-0.008, 0.030, 0.010, 0.010),
56 ( 0.025, 0.010,-0.008, 0.010, 0.010, 0.010),
57 ( 0.030, 0.010,-0.004, 0.010, 0.010, 0.010),
58 ( 0.030, 0.010, 0.004, 0.010, 0.010, 0.010),
59 ( 0.025, 0.010, 0.008, 0.010, 0.010, 0.010),
60 ( 0.010, 0.010, 0.008, 0.030, 0.010, 0.010),
61 ( 0.025, 0.012,-0.006, 0.010, 0.010, 0.010),
62 ( 0.025, 0.012, 0.000, 0.010, 0.010, 0.010),
63 ( 0.025, 0.012, 0.006, 0.010, 0.010, 0.010),
64 ( 0.019, 0.012,-0.006, 0.010, 0.010, 0.010),
65 ( 0.019, 0.012, 0.000, 0.010, 0.010, 0.010),
66 ( 0.019, 0.012, 0.006, 0.010, 0.010, 0.010),
67 ( 0.013, 0.012,-0.006, 0.010, 0.010, 0.010),
68 ( 0.013, 0.012, 0.000, 0.010, 0.010, 0.010),
69 ( 0.013, 0.012, 0.006, 0.010, 0.010, 0.010),
70 ( 0.007, 0.012,-0.006, 0.010, 0.010, 0.010),
71 ( 0.007, 0.012, 0.000, 0.010, 0.010, 0.010),
72 ( 0.007, 0.012, 0.006, 0.010, 0.010, 0.010),
73 ( 0.001, 0.012,-0.006, 0.010, 0.010, 0.010),
74 ( 0.001, 0.012, 0.000, 0.010, 0.010, 0.010),
75 ( 0.001, 0.012, 0.006, 0.010, 0.010, 0.010),
77 numsensors = len(positions);
87 self.frame.append(info.sensor[i].frame_id)
88 self.center.append(info.sensor[i].center)
89 self.hside1.append(info.sensor[i].halfside1)
90 self.hside2.append(info.sensor[i].halfside2)
115 mk.header.frame_id = self.
frame[tipnum]
117 mk.ns = mk.header.frame_id +
"/sphere" 118 mk.type = Marker.SPHERE
119 mk.action = Marker.ADD
123 for i
in range(0,numsensors):
125 (mk.pose.position.x, mk.pose.position.y, mk.pose.position.z, mk.scale.x, mk.scale.y, mk.scale.z) = positions[i]
126 mk.pose.position.y = mk.pose.position.y * ydir
127 mk.pose.position.z = mk.pose.position.z * ydir
132 mk.pose.orientation.w = 1.0
134 (mk.color.r, mk.color.g, mk.color.b) =
color(data[i] / 6000.)
136 self.vis_pub.publish(mk)
143 self.
vis_pub = rospy.Publisher(
'visualization_marker', Marker)
144 rospy.Subscriber(source, PressureState, self.
callback)
145 rospy.Subscriber(source +
"_info", PressureInfo, self.
info_callback)
149 if __name__ ==
'__main__':
151 rospy.init_node(
'pressure_rectangle_viz')
157 while not rospy.is_shutdown():
def makeVisualization(self, data, tipnum, ydir)
def __init__(self, source)
def info_callback(self, info)
def callback(self, pressurestate)