tilting_laser_sensor.py
Go to the documentation of this file.
1 # Software License Agreement (BSD License)
2 #
3 # Copyright (c) 2008, Willow Garage, Inc.
4 # All rights reserved.
5 #
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions
8 # are met:
9 #
10 # * Redistributions of source code must retain the above copyright
11 # notice, this list of conditions and the following disclaimer.
12 # * Redistributions in binary form must reproduce the above
13 # copyright notice, this list of conditions and the following
14 # disclaimer in the documentation and/or other materials provided
15 # with the distribution.
16 # * Neither the name of Willow Garage, Inc. nor the names of its
17 # contributors may be used to endorse or promote products derived
18 # from this software without specific prior written permission.
19 #
20 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 # POSSIBILITY OF SUCH DAMAGE.
32 
33 # author: Vijay Pradeep
34 
35 # Error block for a monocular camera plus tilting laser. The
36 # camera is attached to a chain, but also has a 6 dof transform
37 # in between the tilting laser is attached to the
38 #
39 # checkerboard
40 # /
41 # root
42 # \
43 # tilting_laser
44 
45 from numpy import reshape, array, zeros, matrix, diag, real
46 
47 import roslib; roslib.load_manifest('calibration_estimation')
48 import rospy
49 import numpy
50 import math
51 
53  def __init__(self, valid_configs):
54  self._valid_configs = valid_configs
55 
56  # Construct a tilitng laser for each laser pair that matches one of the configs
57  def build_blocks(self, M_robot):
58  sensors = []
59  for cur_config in self._valid_configs:
60  if cur_config["sensor_id"] in [ x.laser_id for x in M_robot.M_laser ] :
61  M_laser = [x for x in M_robot.M_laser if cur_config["sensor_id"] == x.laser_id][0]
62  cur_sensor = TiltingLaserSensor(cur_config, M_laser)
63  sensors.append(cur_sensor)
64  else:
65  rospy.logdebug(" Didn't find block")
66  return sensors
67 
69  def __init__(self, config_dict, M_laser):
70  self.sensor_type = "laser"
71  self.sensor_id = config_dict["sensor_id"]
72 
73  self._config_dict = config_dict
74  self._M_laser = M_laser
76 
77  def update_config(self, robot_params):
78  self._tilting_laser = robot_params.tilting_lasers[ self.sensor_id ]
79  self._tilting_laser.update_config(robot_params)
80 
81  def compute_residual(self, target_pts):
82  z_mat = self.get_measurement()
83  h_mat = self.compute_expected(target_pts)
84  assert(z_mat.shape[0] == 4)
85  assert(h_mat.shape[0] == 4)
86  assert(z_mat.shape[1] == z_mat.shape[1])
87  r = array(reshape(h_mat[0:3,:].T - z_mat[0:3,:].T, [-1,1]))[:,0]
88  return r
89 
90  def compute_residual_scaled(self, target_pts):
91  r = self.compute_residual(target_pts)
92  gamma_sqrt = self.compute_marginal_gamma_sqrt(target_pts)
93  r_scaled = gamma_sqrt * matrix(r).T
94  return array(r_scaled.T)[0]
95 
96  def compute_marginal_gamma_sqrt(self, target_pts):
97  import scipy.linalg
98  # ----- Populate Here -----
99  cov = self.compute_cov(target_pts)
100  gamma = matrix(zeros(cov.shape))
101  num_pts = math.floor(self.get_residual_length()/3)
102 
103  for k in range(num_pts):
104  first = 3*k
105  last = 3*k+3
106  sub_cov = matrix(cov[first:last, first:last])
107  sub_gamma_sqrt_full = matrix(scipy.linalg.sqrtm(sub_cov.I))
108  sub_gamma_sqrt = real(sub_gamma_sqrt_full)
109  assert(scipy.linalg.norm(sub_gamma_sqrt_full - sub_gamma_sqrt) < 1e-6)
110  gamma[first:last, first:last] = sub_gamma_sqrt
111  return gamma
112 
114  N = len(self._M_laser.joint_points)
115  return N*3
116 
117  # Get the laser measurement.
118  # Returns a 3xN matrix of points in cartesian space
119  def get_measurement(self):
120  # Get the laser points in a 4xN homogenous matrix
121  laser_pts_root = self._tilting_laser.project_to_3D([x.position for x in self._M_laser.joint_points])
122  return laser_pts_root
123 
124  def compute_cov(self, target_pts):
125  epsilon = 1e-8
126 
127  # Ok, this is coded kind of weird. Jt should be [3*N, len(r)]. Currently, it is
128  # [3, len(r)], which means we are assuming that laser noise is correlated across
129  # multiple points. This is wrong. However, we accidentally fix this when computing
130  # Gamma, so it doesn't show up in the final solution.
131  Jt = zeros([3, self.get_residual_length()])
132 
133  import copy
134  x = [copy.copy(x.position) for x in self._M_laser.joint_points]
135 
136  f0 = reshape(array(self._tilting_laser.project_to_3D(x)[0:3,:].T), [-1])
137  for i in range(3):
138  x = [ [y for y in x.position] for x in self._M_laser.joint_points]
139  for cur_pt in x:
140  cur_pt[i] += epsilon
141  fTest = reshape(array(self._tilting_laser.project_to_3D(x)[0:3,:].T), [-1])
142  Jt[i] = (fTest - f0)/epsilon
143 
144  num_pts = len(x)
145  std_dev_sensor = [self._tilting_laser._cov_dict['tilt'],
146  self._tilting_laser._cov_dict['bearing'],
147  self._tilting_laser._cov_dict['range']]
148  cov_sensor = [x*x for x in std_dev_sensor]
149 
150  cov = matrix(Jt).T * matrix(diag(cov_sensor)) * matrix(Jt)
151  return cov
152 
153  # Returns the pixel coordinates of the laser points after being projected into the camera
154  # Returns a 4xN matrix of the target points
155  def compute_expected(self, target_pts):
156  return target_pts
157 
158  # Build a dictionary that defines which parameters will in fact affect this measurement
160  sparsity = dict()
161 
162  sparsity['tilting_lasers'] = {}
163  sparsity['tilting_lasers'][self.sensor_id] = {'gearing':1}
164  sparsity['transforms'] = {}
165  for cur_transform in ( self._tilting_laser._before_chain_Ts + \
166  self._tilting_laser._after_chain_Ts ):
167  sparsity['transforms'][cur_transform._name] = [1, 1, 1, 1, 1, 1]
168  sparsity['transforms'][self._tilting_laser._config['joint']] = [1, 1, 1, 1, 1, 1]
169 
170  return sparsity
171 
calibration_estimation.sensors.tilting_laser_sensor.TiltingLaserSensor._config_dict
_config_dict
Definition: tilting_laser_sensor.py:73
calibration_estimation.sensors.tilting_laser_sensor.TiltingLaserSensor.compute_marginal_gamma_sqrt
def compute_marginal_gamma_sqrt(self, target_pts)
Definition: tilting_laser_sensor.py:96
calibration_estimation.sensors.tilting_laser_sensor.TiltingLaserBundler._valid_configs
_valid_configs
Definition: tilting_laser_sensor.py:54
calibration_estimation.sensors.tilting_laser_sensor.TiltingLaserSensor.compute_residual_scaled
def compute_residual_scaled(self, target_pts)
Definition: tilting_laser_sensor.py:90
calibration_estimation.sensors.tilting_laser_sensor.TiltingLaserSensor.compute_cov
def compute_cov(self, target_pts)
Definition: tilting_laser_sensor.py:124
calibration_estimation.sensors.tilting_laser_sensor.TiltingLaserSensor.terms_per_sample
terms_per_sample
Definition: tilting_laser_sensor.py:75
calibration_estimation.sensors.tilting_laser_sensor.TiltingLaserSensor.build_sparsity_dict
def build_sparsity_dict(self)
Definition: tilting_laser_sensor.py:159
calibration_estimation.sensors.tilting_laser_sensor.TiltingLaserSensor.get_residual_length
def get_residual_length(self)
Definition: tilting_laser_sensor.py:113
calibration_estimation.sensors.tilting_laser_sensor.TiltingLaserSensor._tilting_laser
_tilting_laser
Definition: tilting_laser_sensor.py:78
calibration_estimation.sensors.tilting_laser_sensor.TiltingLaserSensor.compute_residual
def compute_residual(self, target_pts)
Definition: tilting_laser_sensor.py:81
calibration_estimation.sensors.tilting_laser_sensor.TiltingLaserSensor.sensor_id
sensor_id
Definition: tilting_laser_sensor.py:71
calibration_estimation.sensors.tilting_laser_sensor.TiltingLaserBundler.__init__
def __init__(self, valid_configs)
Definition: tilting_laser_sensor.py:53
calibration_estimation.sensors.tilting_laser_sensor.TiltingLaserSensor
Definition: tilting_laser_sensor.py:68
calibration_estimation.sensors.tilting_laser_sensor.TiltingLaserBundler.build_blocks
def build_blocks(self, M_robot)
Definition: tilting_laser_sensor.py:57
calibration_estimation.sensors.tilting_laser_sensor.TiltingLaserSensor._M_laser
_M_laser
Definition: tilting_laser_sensor.py:74
calibration_estimation.sensors.tilting_laser_sensor.TiltingLaserSensor.__init__
def __init__(self, config_dict, M_laser)
Definition: tilting_laser_sensor.py:69
calibration_estimation.sensors.tilting_laser_sensor.TiltingLaserSensor.get_measurement
def get_measurement(self)
Definition: tilting_laser_sensor.py:119
calibration_estimation.sensors.tilting_laser_sensor.TiltingLaserSensor.sensor_type
sensor_type
Definition: tilting_laser_sensor.py:70
calibration_estimation.sensors.tilting_laser_sensor.TiltingLaserSensor.update_config
def update_config(self, robot_params)
Definition: tilting_laser_sensor.py:77
calibration_estimation.sensors.tilting_laser_sensor.TiltingLaserSensor.compute_expected
def compute_expected(self, target_pts)
Definition: tilting_laser_sensor.py:155
calibration_estimation.sensors.tilting_laser_sensor.TiltingLaserBundler
Definition: tilting_laser_sensor.py:52


calibration_estimation
Author(s): Vijay Pradeep, Michael Ferguson
autogenerated on Tue Mar 1 2022 23:58:46