CameraModelFilter.cpp
Go to the documentation of this file.
1 
21 
22 namespace next_best_view {
23  CameraModelFilter::CameraModelFilter() : GeneralFilter(), mParametersChanged(true), mFOVX(0.0), mFOVY(0.0), mNcp(0.0), mFcp(0.0) {
24  }
25 
27 
28  void CameraModelFilter::setRecognizerCosts(float recognizerCosts, std::string objectType)
29  {
30  this->recognizerCosts = recognizerCosts;
31  }
32 
33 
34  float CameraModelFilter::getRecognizerCosts(std::string objectType) {
35  return recognizerCosts;
36  }
37 
38  void CameraModelFilter::setPivotPointPose(const SimpleVector3 &position, const SimpleQuaternion &orientation) {
39  this->setPivotPointPosition(position);
40  this->setOrientation(orientation);
41  }
42 
44  mPivotPointPosition = position;
45  this->setParametersChanged(true);
46  }
47 
49  return mPivotPointPosition;
50  }
51 
53  mPivotPointOrientation = orientation;
54  this->setParametersChanged(true);
55  }
56 
59  }
60 
62  SimpleMatrix4 cameraPoseMatrix = SimpleMatrix4::Identity();
63  cameraPoseMatrix.block<3, 3>(0, 0) = orientation.toRotationMatrix();
64  cameraPoseMatrix.block<3, 1>(0, 3) = position;
65  return cameraPoseMatrix;
66  }
67 
68  void CameraModelFilter::setHorizontalFOV(double fovDegrees) {
69  mFOVX = fovDegrees;
70  this->setParametersChanged(true);
71  }
72 
74  return mFOVX;
75  }
76 
77  void CameraModelFilter::setVerticalFOV(double fovDegrees) {
78  mFOVY = fovDegrees;
79  this->setParametersChanged(true);
80  }
81 
83  return mFOVY;
84  }
85 
87  mNcp = ncp;
88  this->setParametersChanged(true);
89  }
90 
92  return mNcp;
93  }
94 
96  mFcp = fcp;
97  this->setParametersChanged(true);
98  }
99 
101  return mFcp;
102  }
103 }
104 
void setOrientation(const SimpleQuaternion &orientation)
sets the orientation of the pivot point
void setPivotPointPosition(const SimpleVector3 &position)
sets the position of the pivot point.
void setFarClippingPlane(double fcp)
sets the far clipping plane. fcp the far clipping distance
double mFOVX
the horizontal field of view.
Eigen::Matrix< Precision, 3, 1 > SimpleVector3
Definition: typedef.hpp:53
void setNearClippingPlane(double ncp)
sets the near clipping plane.
static SimpleMatrix4 getCameraPoseMatrix(const SimpleVector3 &position, const SimpleQuaternion &orientation)
convenience function to get a camera pose matrix.
SimpleQuaternion mPivotPointOrientation
the orientation of the pivot point.
SimpleVector3 mPivotPointPosition
the position of the pivot point.
double mNcp
the near clipping distance.
this namespace contains all generally usable classes.
void setPivotPointPose(const SimpleVector3 &position, const SimpleQuaternion &orientation)
sets the pose of the pivot point.
CameraModelFilter()
constructs a new camera model filter.
double mFcp
the far clipping distance.
virtual ~CameraModelFilter()=0
destructs the camera model filter.
Eigen::Matrix< Precision, 4, 4 > SimpleMatrix4
Definition: typedef.hpp:41
double mFOVY
the vertical field of view.
Eigen::Quaternion< Precision > SimpleQuaternion
Definition: typedef.hpp:67
virtual void setRecognizerCosts(float recognizerCosts, std::string objectType)
void setVerticalFOV(double fovDegrees)
sets the vertical field of view.
virtual float getRecognizerCosts(std::string objectType)
void setHorizontalFOV(double fovDegrees)
sets the horizontal field of view.
float recognizerCosts
The time it takes to recognize an object (in seconds)


asr_next_best_view
Author(s): Aumann Florian, Borella Jocelyn, Heller Florian, Meißner Pascal, Schleicher Ralf, Stöckle Patrick, Stroh Daniel, Trautmann Jeremias, Walter Milena, Wittenbeck Valerij
autogenerated on Thu Jan 9 2020 07:20:18