00001
00002
00003 """
00004 Copyright (c) 2015, Ubiquity Robotics
00005 All rights reserved.
00006 Redistribution and use in source and binary forms, with or without
00007 modification, are permitted provided that the following conditions are met:
00008 * Redistributions of source code must retain the above copyright notice, this
00009 list of conditions and the following disclaimer.
00010 * Redistributions in binary form must reproduce the above copyright notice,
00011 this list of conditions and the following disclaimer in the documentation
00012 and/or other materials provided with the distribution.
00013 * Neither the name of ubiquity_motor nor the names of its
00014 contributors may be used to endorse or promote products derived from
00015 this software without specific prior written permission.
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00017 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00018 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
00020 FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
00021 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
00022 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00023 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
00024 OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
00025 OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 """
00027
00028 """
00029 Simultaneous location and mapping based on fiducial poses.
00030 Receives FiducialTransform messages and builds a map and estimates the
00031 camera pose from them
00032 """
00033
00034
00035 import rospy
00036 from nav_msgs.msg import Odometry
00037 from tf2_msgs.msg import TFMessage
00038 from std_msgs.msg import String, ColorRGBA
00039 from geometry_msgs.msg import PoseWithCovarianceStamped, Pose, Point, Quaternion, \
00040 TransformStamped
00041 from visualization_msgs.msg import Marker, MarkerArray
00042
00043 from fiducial_pose.msg import Fiducial, FiducialTransform, FiducialTransformArray
00044
00045 from tf.transformations import euler_from_quaternion, quaternion_slerp, \
00046 translation_matrix, quaternion_matrix, \
00047 translation_from_matrix, quaternion_from_matrix, \
00048 quaternion_from_euler
00049 import tf
00050 import rosbag
00051
00052 from math import pi, sqrt
00053 import sys
00054 import os
00055 import traceback
00056 import math
00057 import numpy
00058 import time
00059 import threading
00060 import copy
00061
00062
00063
00064
00065 MIN_UPDATE_TRANSLATION = 1.0
00066 MIN_UPDATE_ROTATION = math.pi/4.0
00067
00068
00069 CEILING_HEIGHT = 2.77
00070
00071
00072 UNSEEN_TIME = 1.5
00073
00074
00075 def mkdirnotex(filename):
00076 dir=os.path.dirname(filename)
00077 print "Directory", dir
00078 if not os.path.exists(dir):
00079 os.makedirs(dir)
00080
00081 """
00082 Radians to degrees
00083 """
00084 def rad2deg(rad):
00085 return rad / math.pi * 180.0
00086
00087 """
00088 Degrees to radians
00089 """
00090 def deg2rad(deg):
00091 return float(deg) * math.pi / 180.0
00092
00093 """
00094 Distance from the nearest perpendicular
00095 """
00096
00097
00098 def angularError(r):
00099 r = r % 360
00100 rDiff = r % 90
00101 quadrant = r - rDiff
00102 err = abs(min(rDiff, 90 - rDiff))
00103 return err
00104
00105 def angularError3D(r, p, y):
00106 a = angularError(rad2deg(r))
00107 b = angularError(rad2deg(p))
00108 c = angularError(rad2deg(y))
00109 tilt = deg2rad(math.sqrt(a*a + b*b + c*c))
00110 error = CEILING_HEIGHT * math.tan(tilt)
00111 variance = error * error
00112 print "Variance", variance
00113 return variance
00114
00115
00116 """
00117 Weighted average of linear quantities
00118 """
00119 def updateLinear(mean1, var1, mean2, var2):
00120 newMean = (mean1 * var2 + mean2 * var1) / (var1 + var2)
00121 newVar = 1.0 / (1.0/var1 + 1.0/var2)
00122 return [newMean, newVar]
00123
00124
00125 """
00126 Weighted average of quaternions
00127 """
00128 def updateAngular(quat1, var1, quat2, var2):
00129 newMean = quaternion_slerp(quat1, quat2, var1/(var1+var2))
00130 newVar = 1.0 / (1.0/var1 + 1.0/var2)
00131 return [newMean, newVar]
00132
00133
00134 """
00135 Class to represent the pose and state of a single fiducial
00136 """
00137 class Fiducial:
00138 def __init__(self, id):
00139 self.id = id
00140 self.position = None
00141 self.orientation = None
00142 self.variance = None
00143 self.observations = 0
00144 self.links = []
00145 self.publishedMarker = False
00146 self.lastSeenTime = rospy.Time(0,0)
00147
00148 """
00149 Return pose as a 4x4 matrix
00150 """
00151 def pose44(self):
00152 return numpy.dot(translation_matrix(self.position),
00153 quaternion_matrix(self.orientation))
00154
00155 """
00156 Update pose with a new observation
00157 """
00158 def update(self, newPosition, newOrientation, newVariance):
00159 if self.observations == 0:
00160 self.position = newPosition
00161 self.orientation = numpy.array(newOrientation)
00162 self.variance = newVariance
00163 self.observations = 1
00164 return
00165 self.position, v1 = updateLinear(self.position, self.variance,
00166 newPosition, newVariance)
00167 self.orientation, v2 = updateAngular(self.orientation, self.variance,
00168 newOrientation, newVariance)
00169 self.variance = v1
00170 self.observations += 1
00171
00172
00173 class FiducialSlam:
00174 def __init__(self):
00175 rospy.init_node('fiducial_slam')
00176 self.odomFrame = rospy.get_param("~odom_frame", "")
00177 self.poseFrame = rospy.get_param("~pose_frame", "base_link")
00178 self.mapFrame = rospy.get_param("~map_frame", "map")
00179 self.cameraFrame = rospy.get_param("~camera_frame", "camera")
00180 self.sendTf = rospy.get_param("~publish_tf", True)
00181 self.mappingMode = rospy.get_param("~mapping_mode", True)
00182 self.useExternalPose = rospy.get_param("~use_external_pose", False)
00183 self.mapFileName = os.path.expanduser(rospy.get_param("~map_file", "map.txt"))
00184 self.obsFileName = os.path.expanduser(rospy.get_param("~obs_file", "obs.txt"))
00185 self.transFileName = os.path.expanduser(rospy.get_param("~trans_file", "trans.txt"))
00186 self.fiducialsAreLevel = rospy.get_param("~fiducials_are_level", True)
00187 mkdirnotex(self.mapFileName)
00188 mkdirnotex(self.obsFileName)
00189 mkdirnotex(self.transFileName)
00190
00191 self.future = rospy.get_param("~future", 0.0)
00192
00193 self.republishTf = rospy.get_param("~republish_tf", True)
00194 print "frames: odom", self.odomFrame, "map:", self.mapFrame, "pose", self.poseFrame
00195 self.obsFile = open(self.obsFileName, "a")
00196 self.transFile = open(self.transFileName, "a")
00197 self.tfs = {}
00198 self.currentSeq = None
00199 self.imageTime = None
00200 self.numFiducials = 0
00201 self.fiducials = {}
00202 self.mapPublished = False
00203 if self.sendTf:
00204 self.br = tf.TransformBroadcaster()
00205 self.lr = tf.TransformListener(True, rospy.Duration(10))
00206 self.markerPub = rospy.Publisher("fiducials", Marker, queue_size=20)
00207 self.publishLock = threading.Lock()
00208 self.visibleMarkers = {}
00209 self.pose = None
00210 self.robotQuat = None
00211 self.robotXyz = None
00212 self.robotYaw = 0.0
00213 self.lastUpdateXyz = None
00214 self.lastUpdateYaw = None
00215 self.loadMap()
00216 self.position = None
00217 rospy.Subscriber("/fiducial_transforms", FiducialTransformArray, self.newTf)
00218 self.posePub = rospy.Publisher("/fiducial_pose", PoseWithCovarianceStamped, queue_size=1)
00219
00220
00221 def close(self):
00222 self.saveMap()
00223 self.obsFile.close()
00224 self.transFile.close()
00225
00226
00227 """
00228 Save current map to file
00229 """
00230 def saveMap(self):
00231 print "** save map **"
00232 file = open(self.mapFileName, "w")
00233 fids = self.fiducials.keys()
00234 fids.sort()
00235 for fid in fids:
00236 f = self.fiducials[fid]
00237 pos = f.position
00238 (r, p, y) = euler_from_quaternion(f.orientation)
00239 file.write("%d %r %r %r %r %r %r %r %d %s\n" % \
00240 (f.id, pos[0], pos[1], pos[2],
00241 rad2deg(r), rad2deg(p), rad2deg(y),
00242 f.variance, f.observations,
00243 ' '.join(map(str, f.links))))
00244 file.close()
00245
00246 """
00247 Load map from file
00248 """
00249 def loadMap(self):
00250 file = open(self.mapFileName, "r")
00251 for line in file.readlines():
00252 words = line.split()
00253 fid = int(words[0])
00254 f = Fiducial(fid)
00255 f.position = numpy.array((float(words[1]), float(words[2]), float(words[3])))
00256 f.orientation = quaternion_from_euler(deg2rad(words[4]), deg2rad(words[5]), deg2rad(words[6]))
00257 f.variance = float(words[7])
00258 f.observations = int(words[8])
00259 f.links = map(int, words[9:])
00260 self.fiducials[fid] = f
00261 file.close()
00262
00263 """
00264 Print out fiducual vertices
00265 """
00266 def showVertices(self):
00267 fids = self.fiducials.keys()
00268 fids.sort()
00269 for fid in fids:
00270 f = self.fiducials[fid]
00271 pos = f.position
00272 off = numpy.dot(translation_matrix(numpy.array((-1.0, -1.0, 0.0))), f.pose44())
00273 off = numpy.dot(translation_matrix(numpy.array((1.0, -1.0, 0.0))), f.pose44())
00274 off = numpy.dot(translation_matrix(numpy.array((1.0, 1.0, 0.0))), f.pose44())
00275 off = numpy.dot(translation_matrix(numpy.array((-1.0, 1.0, 0.0))), f.pose44())
00276
00277 """
00278 Called when a FiducialTransformArray is received
00279 """
00280 def newTf(self, msg):
00281 self.currentSeq = msg.image_seq
00282 self.imageTime = msg.header.stamp
00283 self.tfs = {}
00284 rospy.loginfo("got tfs from image seq %d", self.currentSeq)
00285
00286 for m in msg.transforms:
00287 id = m.fiducial_id
00288 trans = m.transform.translation
00289 rot = m.transform.rotation
00290 mat = numpy.dot(translation_matrix((trans.x, trans.y, trans.z)),
00291 quaternion_matrix((rot.x, rot.y, rot.z, rot.w)))
00292 invMat = numpy.linalg.inv(mat)
00293 self.tfs[id] = (mat, invMat, m.object_error, m.image_error)
00294 self.transFile.write("%d %d %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf\n" % \
00295 (id, self.currentSeq, trans.x, trans.y, trans.z,
00296 rot.x, rot.y, rot.z, rot.w,
00297 m.object_error, m.image_error, m.fiducial_area))
00298 """
00299 if self.useExternalPose:
00300 # XXXX needs to be verified with respect to time
00301 fiducialKnown = False
00302 for f in self.tfs.keys():
00303 if self.fiducials.has_key(f):
00304 fiducialKnown = True
00305 if not fiducialKnown:
00306 for f in self.tfs.keys():
00307 self.updateMapFromExternal(f)
00308 """
00309 self.updatePose()
00310 if not self.pose is None:
00311 robotXyz = numpy.array(translation_from_matrix(self.pose))[:3]
00312 robotQuat = numpy.array(quaternion_from_matrix(self.pose))
00313 (r, p, robotYaw) = euler_from_quaternion(robotQuat)
00314
00315
00316 if self.lastUpdateXyz is None:
00317 self.updateMap()
00318 self.lastUpdateXyz = robotXyz
00319 self.lastUpdateYaw = robotYaw
00320 else:
00321 dist = numpy.linalg.norm(self.lastUpdateXyz - robotXyz)
00322 angle = self.lastUpdateYaw - self.robotYaw
00323 print "Distance moved", dist, angle
00324 if self.mappingMode or dist > MIN_UPDATE_TRANSLATION \
00325 or angle > MIN_UPDATE_ROTATION:
00326 self.updateMap()
00327 self.lastUpdateXyz = robotXyz
00328 self.lastUpdateYaw = robotYaw
00329
00330 """
00331 Update the map with fiducial pairs
00332 """
00333 def updateMap(self):
00334 for f1 in self.tfs.keys():
00335 for f2 in self.tfs.keys():
00336 if f1 == f2:
00337 continue
00338 if not self.fiducials.has_key(f1):
00339 continue
00340 self.updateMapPair(f1, f2)
00341
00342 """
00343 Update the map with the new transform between the fiducial pair
00344 f1 and f2
00345 """
00346 def updateMapPair(self, f1, f2):
00347 fid1 = self.fiducials[f1]
00348
00349
00350 if self.fiducials.has_key(f2):
00351 if self.fiducials[f2].variance == 0.0:
00352 return
00353
00354
00355 if len(fid1.links) == 1 and f1 in fid1.links:
00356 return
00357
00358 P_fid1 = fid1.pose44()
00359
00360 (T_camFid1, T_fid1Cam, oerr1, ierr1) = self.tfs[f1]
00361 (T_camFid2, T_fid2Cam, oerr2, ierr2) = self.tfs[f2]
00362
00363
00364 T_fid1Fid2 = numpy.dot(T_fid1Cam, T_camFid2)
00365
00366
00367 P_fid2 = numpy.dot(P_fid1, T_fid1Fid2)
00368
00369 xyz = numpy.array(translation_from_matrix(P_fid2))[:3]
00370 quat = numpy.array(quaternion_from_matrix(P_fid2))
00371 (r, p, yaw) = euler_from_quaternion(quat)
00372
00373 self.obsFile.write("%d %d %d %r %r %r %r %r %r %r %r %r %r\n" % \
00374 (self.currentSeq, f2, f1,
00375 xyz[0], xyz[1], xyz[2],
00376 rad2deg(r), rad2deg(p), rad2deg(yaw),
00377 oerr1, ierr1, oerr2, ierr2))
00378
00379 addedNew = False
00380 if not self.fiducials.has_key(f2):
00381 self.fiducials[f2] = Fiducial(f2)
00382 addedNew = True
00383
00384 fid2 = self.fiducials[f2]
00385
00386 variance = angularError3D(r, p , yaw)
00387
00388
00389 print "*** %f var %f %f" % (f1, self.fiducials[f1].variance, variance)
00390 variance = variance + self.fiducials[f1].variance
00391
00392 if self.fiducialsAreLevel:
00393 (r1, p1, y1) = euler_from_quaternion(fid1.orientation)
00394 (r, p, yaw) = euler_from_quaternion(quat)
00395 quat = quaternion_from_euler(r1, p1, yaw)
00396
00397 self.fiducials[f2].update(xyz, quat, variance)
00398
00399 print "%d updated to %.3f %.3f %.3f %.3f %.3f %.3f %.3f" % (f2, xyz[0], xyz[1], xyz[2],
00400 rad2deg(r), rad2deg(p), rad2deg(yaw), variance)
00401
00402 p = self.fiducials[f2].position
00403
00404 if self.mappingMode or addedNew:
00405 self.saveMap()
00406
00407 if not f1 in fid2.links:
00408 fid2.links.append(f1)
00409 if not f2 in fid1.links:
00410 fid1.links.append(f2)
00411
00412 """
00413 Update the map with a new fiducial based on an external robot pose
00414 """
00415 def updateMapFromExternal(self, f):
00416 rospy.logerr("update from external %d" % f)
00417 try:
00418 ct, cr = self.lr.lookupTransform(self.mapFrame,
00419 self.cameraFrame,
00420 self.imageTime)
00421 T_worldCam = numpy.dot(translation_matrix((ct[0], ct[1], ct[2])),
00422 quaternion_matrix((cr[0], cr[1], cr[2], cr[3])))
00423 except:
00424 rospy.logerr("Unable to lookup transfrom from map to camera (%s to %s)" % \
00425 (self.mapFrame, self.cameraFrame))
00426 return
00427
00428 (T_camFid, T_fidCam, oerr1, ierr1) = self.tfs[f]
00429
00430 P_fid = numpy.dot(T_worldCam, T_camFid)
00431
00432 self.fiducials[f] = Fiducial(f)
00433
00434 xyz = numpy.array(translation_from_matrix(P_fid))[:3]
00435 quat = numpy.array(quaternion_from_matrix(P_fid))
00436 (r, p, yaw) = euler_from_quaternion(quat)
00437
00438 variance = 0.3
00439 self.fiducials[f].update(xyz, quat, variance)
00440
00441 print "%d updated from external to %.3f %.3f %.3f %.3f %.3f %.3f %.3f" % (f, xyz[0], xyz[1], xyz[2],
00442 rad2deg(r), rad2deg(p), rad2deg(yaw), variance)
00443
00444 p = self.fiducials[f].position
00445 self.saveMap()
00446
00447
00448 """
00449 Estimate the pose of the camera from the fiducial to camera
00450 transforms in self.tfs
00451 """
00452 def updatePose(self):
00453 position = None
00454 orientation = None
00455 camera = None
00456 try:
00457 ct, cr = self.lr.lookupTransform(self.cameraFrame,
00458 self.poseFrame,
00459 self.imageTime)
00460 except:
00461 rospy.logerr("Unable to lookup transfrom from camera to robot (%s to %s)" % \
00462 (self.poseFrame, self.cameraFrame))
00463 return
00464
00465 T_camBase = numpy.dot(translation_matrix((ct[0], ct[1], ct[2])),
00466 quaternion_matrix((cr[0], cr[1], cr[2], cr[3])))
00467
00468 for t in self.tfs.keys():
00469 if not self.fiducials.has_key(t):
00470 rospy.logwarn("No path to %d" % t)
00471 continue
00472
00473 self.fiducials[t].lastSeenTime = self.imageTime
00474
00475 (T_camFid, T_fidCam, oerr, ierr) = self.tfs[t]
00476 T_worldFid = self.fiducials[t].pose44()
00477
00478 T_worldCam = numpy.dot(T_worldFid, T_fidCam)
00479 T_worldBase = numpy.dot(T_worldCam, T_camBase)
00480
00481 xyz = numpy.array(translation_from_matrix(T_worldBase))[:3]
00482 quat = numpy.array(quaternion_from_matrix(T_worldBase))
00483 (r, p, y) = euler_from_quaternion(quat)
00484
00485 if self.fiducialsAreLevel:
00486 quat = quaternion_from_euler(0, 0, y)
00487
00488 thisvar = angularError3D(r, p , 0.0)
00489 rospy.loginfo("pose %d %f %f %f %f %f %f %f" % \
00490 (t, xyz[0], xyz[1], xyz[2],
00491 rad2deg(r), rad2deg(p), rad2deg(y),
00492 thisvar))
00493
00494 if position is None:
00495 position = xyz
00496 orientation = quat
00497 variance = thisvar
00498 else:
00499 position, v1 = updateLinear(position, variance,
00500 xyz, thisvar)
00501 orientation, v2 = updateAngular(orientation, variance,
00502 quat, thisvar)
00503 variance = v1
00504 if not position is None:
00505 (r, p, y) = euler_from_quaternion(orientation)
00506 xyz = position
00507 rospy.loginfo("pose ALL %f %f %f %f %f %f %f %d" % \
00508 (xyz[0], xyz[1], xyz[2],
00509 rad2deg(r), rad2deg(p), rad2deg(y),
00510 variance, self.currentSeq))
00511 self.pose = numpy.dot(translation_matrix((position[0],
00512 position[1],
00513 0)),
00514 quaternion_matrix((orientation[0],
00515 orientation[1],
00516 orientation[2],
00517 orientation[3])))
00518 self.computeTransform()
00519
00520 def makeMarker(self, fiducialId, visible=False):
00521 fiducial = self.fiducials[fiducialId]
00522 marker = Marker()
00523 marker.type = Marker.CUBE
00524 marker.action = Marker.ADD
00525
00526 position = fiducial.position
00527 marker.pose = Pose(Point(position[0], position[1], position[2]),
00528 Quaternion(0, 0, 0, 1))
00529 marker.scale.x = 0.15
00530 marker.scale.y = 0.15
00531 marker.scale.z = 0.15
00532 if visible:
00533 marker.color = ColorRGBA(1, 0, 0, 1)
00534 else:
00535 marker.color = ColorRGBA(0, 1, 0, 1)
00536 marker.id = fiducialId
00537 marker.ns = "fiducial_namespace"
00538 marker.header.frame_id = "/map"
00539
00540 text = Marker()
00541 text.header.frame_id = "/map"
00542 text.color = ColorRGBA(1, 1, 1, 1)
00543 text.scale.x = text.scale.y = text.scale.z = 0.1
00544 text.pose.position.x = marker.pose.position.x
00545 text.pose.position.y = marker.pose.position.y
00546 text.pose.position.z = marker.pose.position.z
00547 text.pose.position.z += (marker.scale.z/2.0) + 0.1
00548 text.id = fiducialId + 10000
00549 text.ns = "fiducial_namespace_text"
00550 text.type = Marker.TEXT_VIEW_FACING
00551 text.text = str(fiducialId)
00552 text.action = Marker.ADD
00553
00554 links = Marker()
00555 links.ns = "fiducial_namespace"
00556 links.header.frame_id = "/map"
00557 links.action = Marker.ADD
00558 links.type = Marker.LINE_LIST
00559 links.pose.position.x = 0.0
00560 links.pose.position.y = 0.0
00561 links.pose.position.z = 0.0
00562 links.color = ColorRGBA(0, 0, 1, 1)
00563 links.scale.x = 0.05
00564 for fid2 in fiducial.links:
00565 if self.fiducials.has_key(fid2):
00566 position2 = self.fiducials[fid2].position
00567 links.points.append(Point(position[0], position[1], position[2]))
00568 links.points.append(Point(position2[0], position2[1], position2[2]))
00569 links.id = fiducialId + 20000
00570 links.ns = "fiducial_namespace_link"
00571
00572 return marker, text, links
00573
00574
00575 def publishMarker(self, fiducialId, visible=False):
00576 marker, text, links = self.makeMarker(fiducialId, visible)
00577 self.markerPub.publish(marker)
00578 self.markerPub.publish(text)
00579 self.markerPub.publish(links)
00580
00581
00582 """
00583 Publish the next unpublished marker in the map.
00584 This should be called repeatedly until all markers are published
00585 """
00586 def publishNextMarker(self):
00587 if self.mapPublished:
00588 return
00589 for fid in self.fiducials.keys():
00590 if not self.fiducials[fid].publishedMarker:
00591 self.publishMarker(fid)
00592 self.fiducials[fid].publishedMarker = True
00593 return
00594 self.mapPublished = True
00595 print "Map published"
00596
00597 """
00598 Update markers with visibility colors
00599 """
00600 def publishMarkers(self):
00601 self.publishNextMarker()
00602 t = self.imageTime
00603 for fid in self.tfs.keys():
00604 if self.fiducials.has_key(fid):
00605 self.visibleMarkers[fid] = True
00606 for fid in self.visibleMarkers.keys():
00607 if (t - self.fiducials[fid].lastSeenTime).to_sec() > UNSEEN_TIME:
00608 self.publishMarker(fid, False)
00609 del self.visibleMarkers[fid]
00610 else:
00611 self.publishMarker(fid, True)
00612
00613
00614 """
00615 Publish the transform in self.pose
00616 """
00617 def computeTransform(self):
00618 if self.pose is None:
00619 return
00620 robotXyz = numpy.array(translation_from_matrix(self.pose))[:3]
00621 robotQuat = numpy.array(quaternion_from_matrix(self.pose))
00622 (r, p, yaw) = euler_from_quaternion(robotQuat)
00623 robotQuat = quaternion_from_euler(0.0, 0.0, yaw)
00624 m = PoseWithCovarianceStamped()
00625 m.header.frame_id = self.mapFrame
00626 m.header.stamp = self.imageTime
00627 m.pose.pose.orientation.x = robotQuat[0]
00628 m.pose.pose.orientation.y = robotQuat[1]
00629 m.pose.pose.orientation.z = robotQuat[2]
00630 m.pose.pose.orientation.w = robotQuat[3]
00631 m.pose.pose.position.x = robotXyz[0]
00632 m.pose.pose.position.y = robotXyz[1]
00633 m.pose.pose.position.z = robotXyz[2]
00634 """
00635 These values are designed to work with robot_localization.
00636 See http://wiki.ros.org/robot_localization/Tutorials/Migration%20from%20robot_pose_ekf
00637 """
00638 m.pose.covariance = [0.01, 0, 0, 0, 0, 0,
00639 0, 0.01, 0, 0, 0, 0,
00640 0, 0, 0.01, 0, 0, 0,
00641 0, 0, 0, 0.01, 0, 0,
00642 0, 0, 0, 0, 0.01, 0,
00643 0, 0, 0, 0, 0, 0.01]
00644 self.posePub.publish(m)
00645 if self.odomFrame != "":
00646 try:
00647 if self.imageTime is None:
00648 rospy.logerr("imageTime is bogus!")
00649 odomt, odomr = self.lr.lookupTransform(self.poseFrame, self.odomFrame, self.imageTime)
00650 odom = numpy.dot(translation_matrix((odomt[0], odomt[1], odomt[2])),
00651 quaternion_matrix((odomr[0], odomr[1], odomr[2], odomr[3])))
00652 pose = numpy.dot(self.pose, odom)
00653 except:
00654 rospy.logerr("Unable to lookup transfrom from odom to robot (%s to %s)" % \
00655 (self.poseFrame, self.odomFrame))
00656 return
00657 else:
00658 pose = self.pose
00659 self.publishLock.acquire()
00660 self.robotXyz = numpy.array(translation_from_matrix(pose))[:3]
00661 robotQuat = numpy.array(quaternion_from_matrix(pose))
00662 (r, p, yaw) = euler_from_quaternion(robotQuat)
00663 self.robotQuat = quaternion_from_euler(0.0, 0.0, yaw)
00664 self.robotYaw = yaw
00665 self.publishLock.release()
00666 self.publishTransform()
00667
00668 def publishTransform(self):
00669 if self.sendTf and not self.robotXyz is None:
00670 self.publishLock.acquire()
00671 if self.odomFrame != "":
00672 toFrame = self.odomFrame
00673 fromFrame = self.mapFrame
00674 else:
00675 toFrame = self.poseFrame
00676 fromFrame = self.mapFrame
00677 self.br.sendTransform(self.robotXyz,
00678 self.robotQuat,
00679 rospy.Time.now() + rospy.Duration(self.future),
00680 toFrame,
00681 fromFrame)
00682 self.publishLock.release()
00683
00684 def run(self):
00685 hz = 10.0
00686 rospy.loginfo("Fiducial Slam started")
00687 rate = rospy.Rate(hz)
00688 while not rospy.is_shutdown():
00689 if self.republishTf:
00690 self.publishTransform()
00691 self.publishMarkers()
00692 rate.sleep()
00693 self.close()
00694 rospy.loginfo("Fiducial Slam ended")
00695
00696 if __name__ == "__main__":
00697 node = FiducialSlam()
00698 node.run()