Public Member Functions | Public Attributes | Private Member Functions | Private Attributes
calibration_estimation.sensors.camera_chain_sensor.CameraChainSensor Class Reference

List of all members.

Public Member Functions

def __init__
def build_sparsity_dict
def compute_cov
def compute_expected
def compute_expected_J
def compute_marginal_gamma_sqrt
def compute_residual
def compute_residual_scaled
def get_chain_cov
def get_measurement
def get_residual_length
def update_config

Public Attributes

 sensor_id
 sensor_type
 terms_per_sample

Private Member Functions

def _compute_expected

Private Attributes

 _camera
 _config_dict
 _full_chain
 _M_cam
 _M_chain

Detailed Description

Definition at line 89 of file camera_chain_sensor.py.


Constructor & Destructor Documentation

def calibration_estimation.sensors.camera_chain_sensor.CameraChainSensor.__init__ (   self,
  config_dict,
  M_cam,
  M_chain 
)
Generates a single sensor block for a single configuration
Inputs:
- config_dict: The configuration for this specific sensor. This looks exactly like
       a single element from the valid_configs list passed into CameraChainBundler.__init__
- M_cam: The camera measurement of type calibration_msgs/CameraMeasurement
- M_chain: The chain measurement of type calibration_msgs/ChainMeasurement

Definition at line 90 of file camera_chain_sensor.py.


Member Function Documentation

def calibration_estimation.sensors.camera_chain_sensor.CameraChainSensor._compute_expected (   self,
  chain_state,
  target_pts 
) [private]
Compute what measurement we would expect to see, based on the current system parameters
and the specified target point locations.

Inputs:
- chain_state: The joint angles of this sensor's chain of type sensor_msgs/JointState.
- target_pts: 4XN matrix, storing features point locations in world cartesian homogenous coordinates.

Returns: target points projected into pixel coordinates, in a Nx2 matrix

Definition at line 188 of file camera_chain_sensor.py.

Build a dictionary that defines which parameters will in fact affect this measurement.

Returned dictionary should be of the following form:
  transforms:
    my_transformA: [1, 1, 1, 1, 1, 1]
    my_transformB: [1, 1, 1, 1, 1, 1]
  chains:
    my_chain:
      gearing: [1, 1, ---, 1]
  rectified_cams:
    my_cam:
      baseline_shift: 1
      f_shift: 1
      cx_shift: 1
      cy_shift: 1

Definition at line 272 of file camera_chain_sensor.py.

Computes the measurement covariance in pixel coordinates for the given
set of target points (target_pts)
Input:
 - target_pts: 4xN matrix, storing N feature points of the target, in homogeneous coords

Definition at line 229 of file camera_chain_sensor.py.

Compute the expected pixel coordinates for a set of target points.
target_pts: 4xN matrix, storing feature points of the target, in homogeneous coords
Returns: target points projected into pixel coordinates, in a Nx2 matrix

Definition at line 178 of file camera_chain_sensor.py.

The output Jacobian J shows how moving target_pts in cartesian space affects
the expected measurement in (u,v) camera coordinates.
For n points in target_pts, J is a 2nx3n matrix
Note: This doesn't seem to be used anywhere, except maybe in some drawing code

Definition at line 206 of file camera_chain_sensor.py.

Calculates the square root of the information matrix for the measurement of the
current set of system parameters at the passed in set of target points.

Definition at line 146 of file camera_chain_sensor.py.

Computes the measurement residual for the current set of system parameters and target points
Input:
- target_pts: 4XN matrix, storing features point locations in world cartesian homogenous coordinates.
Output:
- r: terms_per_sample*N long vector, storing pixel residuals for the target points in the form of
     [u1, v1, u2, v2, ..., uN, vN] or [u1, v1, u'1, u2....]

Definition at line 122 of file camera_chain_sensor.py.

Computes the residual, and then scales it by sqrt(Gamma), where Gamma
is the information matrix for this measurement (Cov^-1).

Definition at line 136 of file camera_chain_sensor.py.

Definition at line 253 of file camera_chain_sensor.py.

Get the target's pixel coordinates as measured by the actual sensor

Definition at line 169 of file camera_chain_sensor.py.

Definition at line 166 of file camera_chain_sensor.py.

On each optimization cycle the set of system parameters that we're optimizing over will change. Thus,
after each change in parameters we must call update_config to ensure that our calculated residual reflects
the newest set of system parameters.

Definition at line 112 of file camera_chain_sensor.py.


Member Data Documentation

Definition at line 116 of file camera_chain_sensor.py.

Definition at line 97 of file camera_chain_sensor.py.

Definition at line 97 of file camera_chain_sensor.py.

Definition at line 97 of file camera_chain_sensor.py.

Definition at line 97 of file camera_chain_sensor.py.

Definition at line 97 of file camera_chain_sensor.py.

Definition at line 97 of file camera_chain_sensor.py.

Definition at line 97 of file camera_chain_sensor.py.


The documentation for this class was generated from the following file:


calibration_estimation
Author(s): Vijay Pradeep, Michael Ferguson
autogenerated on Sat Jun 8 2019 19:41:45