Public Member Functions | Static Public Member Functions | Private Types | Private Member Functions | Private Attributes
labust::blueview::CConverter Class Reference

#include <CConverter.hpp>

List of all members.

Public Member Functions

 CConverter ()
void llz2xy (const SonarHead &head, const TrackedFeaturePtr tracklet)
void xy2llz (const SonarHead &head, const TrackedFeaturePtr tracklet)
 ~CConverter ()

Static Public Member Functions

static std::pair< double, double > deg2meter (double difflat, double difflon, double lat)
static std::pair< double, double > meter2deg (double x, double y, double lat)
static void meter2pixel (const TrackerROI &roi, const TrackedFeaturePtr tracklet)
static void pixel2meter (const TrackerROI &roi, const TrackedFeaturePtr tracklet)

Private Types

typedef
labust::math::rotation_matrix::matrix 
matrix
typedef
boost::numeric::ublas::vector
< double > 
vector

Private Member Functions

void update (const SonarHead &head)

Private Attributes

matrix R

Detailed Description

The class contains conversions between frames needed for BlueView image processing.

Todo:
Drop the conversion stuff into hpp for inline.

Definition at line 50 of file CConverter.hpp.


Member Typedef Documentation

typedef labust::math::rotation_matrix::matrix labust::blueview::CConverter::matrix [private]

Definition at line 53 of file CConverter.hpp.

typedef boost::numeric::ublas::vector<double> labust::blueview::CConverter::vector [private]

Definition at line 52 of file CConverter.hpp.


Constructor & Destructor Documentation

Generic constructor.

Definition at line 40 of file CConverter.cpp.

Generic destructor.

Definition at line 42 of file CConverter.cpp.


Member Function Documentation

std::pair< double, double > CConverter::deg2meter ( double  difflat,
double  difflon,
double  lat 
) [static]

Degree to meter conversion.

Parameters:
difflatNorth distance in degree
difflonEast distance in degree
latLatitude position in decimal degrees
Returns:
Returns pair of lat,lon degrees

These conversion where taken of Wikipedia :) http://en.wikipedia.org/wiki/Geographic_coordinate_system#Cartesian_coordinates

Definition at line 143 of file CConverter.cpp.

void CConverter::llz2xy ( const SonarHead head,
const TrackedFeaturePtr  tracklet 
)

This method converts the estimated world lat-lon-z feature coordinates to the in x-y coordianates in the sonar head.

Parameters:
headThe sonar head information.
trackletThe tracked feature information.

Definition at line 44 of file CConverter.cpp.

std::pair< double, double > CConverter::meter2deg ( double  x,
double  y,
double  lat 
) [static]

Meters to degree conversion.

Parameters:
xNorth distance in meters
yEast distance in meters
latLatitude position in decimal degrees
Returns:
Returns pair of lat,lon degrees

These conversion where taken of Wikipedia :) http://en.wikipedia.org/wiki/Geographic_coordinate_system#Cartesian_coordinates

Definition at line 129 of file CConverter.cpp.

void CConverter::meter2pixel ( const TrackerROI roi,
const TrackedFeaturePtr  tracklet 
) [static]

Calculate the pixel position based on ROI information and sonar head X-Y position.

Parameters:
roiThe region of interest.
trackletThe tracked object.

Definition at line 94 of file CConverter.cpp.

void CConverter::pixel2meter ( const TrackerROI roi,
const TrackedFeaturePtr  tracklet 
) [static]

Calculate the pixel position back to sonar head X-Y position.

Parameters:
roiThe region of interest.
trackletThe tracked object.

Definition at line 108 of file CConverter.cpp.

void CConverter::update ( const SonarHead head) [private]

This method updates the rotation matrix NED->XYZ conversion

Definition at line 121 of file CConverter.cpp.

void CConverter::xy2llz ( const SonarHead head,
const TrackedFeaturePtr  tracklet 
)

This method converts the features x-y coordinates in the sonar head to the world lat-lon-z.

Parameters:
headThe sonar head information
trackletThe tracked feature information

Definition at line 73 of file CConverter.cpp.


Member Data Documentation

Rotation matrix NED->XYZ.

Definition at line 126 of file CConverter.hpp.


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


target_detector
Author(s): Gyula Nagy
autogenerated on Fri Feb 7 2014 11:36:05