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
50 from geometry_msgs.msg
import Vector3
64 self.frame.append(info.sensor[i].frame_id)
65 self.center.append(info.sensor[i].center)
66 self.hside1.append(info.sensor[i].halfside1)
67 self.hside2.append(info.sensor[i].halfside2)
92 mk.header.frame_id = self.
frame[tipnum]
94 mk.ns = mk.header.frame_id +
"/line" 95 mk.type = Marker.LINE_STRIP
96 mk.action = Marker.ADD
100 mk.points.append(Vector3())
102 for i
in range(0,22):
104 mk.pose.position = self.
center[tipnum][i]
105 mk.pose.orientation.w = 1.0
107 h1 = self.
hside1[tipnum][i]
108 h2 = self.
hside2[tipnum][i]
109 mk.points[0].x = h1.x + h2.x
110 mk.points[1].x = h1.x - h2.x
111 mk.points[2].x = -h1.x - h2.x
112 mk.points[3].x = -h1.x + h2.x
113 mk.points[0].y = h1.y + h2.y
114 mk.points[1].y = h1.y - h2.y
115 mk.points[2].y = -h1.y - h2.y
116 mk.points[3].y = -h1.y + h2.y
117 mk.points[0].z = h1.z + h2.z
118 mk.points[1].z = h1.z - h2.z
119 mk.points[2].z = -h1.z - h2.z
120 mk.points[3].z = -h1.z + h2.z
121 mk.points[4] = mk.points[0]
123 (mk.color.r, mk.color.g, mk.color.b) =
color(data[i] / 6000.)
125 self.vis_pub.publish(mk)
132 self.
vis_pub = rospy.Publisher(
'visualization_marker', Marker)
133 rospy.Subscriber(source, PressureState, self.
callback)
134 rospy.Subscriber(source +
"_info", PressureInfo, self.
info_callback)
138 if __name__ ==
'__main__':
140 rospy.init_node(
'pressure_sphere_viz')
146 while not rospy.is_shutdown():
def __init__(self, source)
def info_callback(self, info)
def callback(self, pressurestate)
def makeVisualization(self, data, tipnum)