init_amcl.py
Go to the documentation of this file.
00001 #!/usr/bin/python
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 Initialize amcl from fiducial pose
00030 """
00031 
00032 
00033 import rospy
00034 from geometry_msgs.msg import PoseWithCovarianceStamped
00035 
00036 from math import pi, sqrt
00037 import sys
00038 import os
00039 import traceback
00040 import math
00041 import numpy
00042 import time
00043 import copy
00044 
00045 class InitAMCL:
00046     def __init__(self):
00047        rospy.init_node('init_amcl')
00048        self.lastAmclPose = None
00049        self.isInitialized = False
00050        self.cov_thresh = rospy.get_param("~cov_thresh", 0.2)
00051        self.initPub = rospy.Publisher("/initialpose", 
00052                                         PoseWithCovarianceStamped, 
00053                                         queue_size=1)
00054        rospy.Subscriber("/amcl_pose",
00055                         PoseWithCovarianceStamped,
00056                         self.amclPose)
00057        rospy.Subscriber("/fiducial_pose",
00058                         PoseWithCovarianceStamped,
00059                         self.fiducialPose)
00060 
00061     def amclPose(self, m):
00062         print "amcl_pose", m.pose.covariance[0]
00063         self.lastAmclPose = m
00064 
00065     def fiducialPose(self, m):
00066         #print "fiducial_pose", m
00067         if self.lastAmclPose.pose.covariance[0] > self.cov_thresh \
00068         or not self.isInitialized:
00069             self.initPub.publish(m)
00070             self.isInitialized = True
00071 
00072 if __name__ == "__main__":
00073     node = InitAMCL()
00074     rospy.spin()


fiducial_slam
Author(s): Jim Vaughan
autogenerated on Thu Jun 6 2019 18:08:14