checkerboard.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 import numpy
34 from numpy import matrix, vsplit, sin, cos, reshape
35 import rospy
36 
37 param_names = ['spacing_x', 'spacing_y']
38 
40  '''
41  Primitive for generating 3D points of a checkerboard.
42  '''
43 
44  # Dictionary with four elems
45  # num_x: number of internal corners along x axis (Not configurable)
46  # num_y: number of internal corners along y axis (Not configurable)
47  # width_x: spacing between corners along x direction
48  # width_y: spacing between corners along y direction
49  def __init__(self, config = {'corners_x': 2,
50  'corners_y': 2,
51  'spacing_x': .10,
52  'spacing_y': .10} ):
53  rospy.logdebug('Initializing Checkerboard')
54  self._corners_x = config['corners_x']
55  self._corners_y = config['corners_y']
56 
57  param_vec = reshape( matrix([ config['spacing_x'], config['spacing_y'] ], float), (-1,1))
58  self.inflate(param_vec)
59 
60  def calc_free(self, free_config):
61  return [free_config[x] == 1 for x in param_names]
62 
63  def params_to_config(self, param_vec):
64  return { 'corners_x' : self._corners_x,
65  'corners_y' : self._corners_y,
66  'spacing_x' : float(param_vec[0,0]),
67  'spacing_y' : float(param_vec[1,0]) }
68 
69  # Convert column vector of params into config
70  def inflate(self, param_vec):
71  self._spacing_x = param_vec[0,0]
72  self._spacing_y = param_vec[1,0]
73 
74  # Return column vector of config
75  def deflate(self):
76  param_vec = reshape(matrix( [self._spacing_x, self._spacing_y], float ), (-1,1))
77  return param_vec
78 
79  # Returns # of params needed for inflation & deflation
80  def get_length(self):
81  return len(param_names)
82 
83  # Generate the 3D points associated with all the corners of the checkerboard
84  # returns - 4xN numpy matrix with all the points (in homogenous coords)
85  def generate_points(self):
86  N = self._corners_x * self._corners_y
87  pts = matrix(numpy.zeros((4,N), float))
88  for y in range(0,self._corners_y):
89  for x in range(0,self._corners_x):
90  n = y*self._corners_x + x
91  pts[:,n] = numpy.matrix([ [(x-float(self._corners_x-1)/2) * self._spacing_x],
92  [-1*(y-float(self._corners_y-1)/2) * self._spacing_y],
93  [0],
94  [1] ])
95  return pts
96 


calibration_estimation
Author(s): Vijay Pradeep, Michael Ferguson
autogenerated on Thu Jun 6 2019 19:17:16