44 roslib.load_manifest(
'pr2_gazebo')
47 from pr2_msgs.msg
import PressureState
48 from geometry_msgs.msg
import PointStamped, Vector3Stamped
57 from fingertip_pressure
import fingertip_geometry
63 return math.sqrt(numpy.dot(vect, vect))
68 return [
vectnorm(x)
for x
in vectarray]
78 return ' '.join([
'%2.3f'%x
for x
in list])
82 return '\n'.join([
pplist(x)
for x
in list])
86 return numpy.matrix([[vector.x, vector.y, vector.z, 1]]).transpose()
96 l_msg = fingertip_geometry.pressureInformation(
'', 1)
98 (l_msg.force_per_unit, l_msg.center, l_msg.halfside1, l_msg.halfside2)
100 r_msg = fingertip_geometry.pressureInformation(
'', -1)
102 (r_msg.force_per_unit, r_msg.center, r_msg.halfside1, r_msg.halfside2)
137 'l':gripper+
'_gripper_l_finger_tip_link'}
140 rospy.Subscriber(gripper +
"_gripper_l_finger_tip_bumper/state", ContactsState, self.
l_contact_callback)
141 rospy.Subscriber(gripper +
"_gripper_r_finger_tip_bumper/state", ContactsState, self.
r_contact_callback)
144 self.
pub = rospy.Publisher(
"pressure/"+gripper+
"_gripper_motor", PressureState)
166 for contactstate
in bumperstate.states:
169 for i
in range(len(contactstate.depths)):
174 array_pos = numpy.array([contact_pos[0,0], contact_pos[1,0], contact_pos[2,0]])
175 array_normal = numpy.array([contact_normal[0,0], contact_normal[1,0], contact_normal[2,0]])
195 finger_tip_readings = {
'l':[0]*sensor_element_count,
'r':[0]*sensor_element_count} 196 for tip
in [
'l',
'r']: 200 nearest_array_element =
'not found' 201 nearest_array_weighted_dist = 1e6;
207 for arrayelem
in range(sensor_element_count):
221 dist_from_plane = math.fabs(numpy.dot(posdiff, sensednormal)/
vectnorm(sensednormal))
224 halfside1proj = numpy.dot(posdiff, halfside1)/
vectnorm(halfside1)
225 halfside2proj = numpy.dot(posdiff, halfside2)/
vectnorm(halfside2)
226 halfside1dist = math.fabs(halfside1proj) -
vectnorm(halfside1)
227 halfside2dist = math.fabs(halfside2proj) -
vectnorm(halfside2)
230 if halfside1dist < 0:
232 if halfside2dist < 0:
234 dist = math.sqrt(halfside1dist**2+halfside2dist**2+dist_from_plane**2)
239 if dist > .01
and not DEBUG:
243 normal_angle_diff =
anglediff(sensednormal, normal)
244 anglediffs.append(normal_angle_diff)
249 weighted_dist = normal_angle_diff + dist / .01
250 weighteddists.append(weighted_dist)
252 if weighted_dist < nearest_array_weighted_dist:
253 nearest_array_weighted_dist = weighted_dist
254 nearest_array_element = arrayelem
258 print "dists:",
pplist(dists)
259 print "anglediffs:",
pplist(anglediffs)
260 print "weighteddists:",
pplist(weighteddists)
264 if nearest_array_element !=
'not found':
266 print "nearest_array_element:", nearest_array_element
267 print "nearest_array_weighted_dist: %0.3f"%nearest_array_weighted_dist
270 if newreading > 10000:
273 if newreading > finger_tip_readings[tip][nearest_array_element]:
274 finger_tip_readings[tip][nearest_array_element] = newreading
283 print "left tip readings:",
pplist(finger_tip_readings[
'l'])
284 print "right tip readings:",
pplist(finger_tip_readings[
'r']) 288 ps.header.stamp = rospy.get_rostime();
291 for i
in range(sensor_element_count):
292 ps.l_finger_tip.append(finger_tip_readings[
'l'][i])
293 ps.r_finger_tip.append(finger_tip_readings[
'r'][i]) 299 if __name__ ==
'__main__':
301 rospy.init_node(
'sim_contact_translator', anonymous=
True)
306 print "done initializing, starting to publish" 308 while not rospy.is_shutdown():