|
Camera Class ReferenceBasic camera sensor.
More...
#include <Camera.hh>
Inheritance diagram for Camera:
List of all members.
|
Public Member Functions |
| Camera (World *world) |
virtual | ~Camera () |
int | Init (int width, int height, double hfov, double minDepth, double maxDepth, const char *method, int zBufferDepth) |
| Initialize the sensor.
|
void | InitContext (GLContext &context) |
int | Fini () |
| Finalize the sensor.
|
void | Update () |
| Update the sensor information.
|
void | SetPose (GzPose pose) |
| Set the pose of the camera (global cs).
|
GzPose | GetPose () |
| Get the camera pose (global cs).
|
void | SetFOV (double fov) |
| Set the camera FOV (horizontal).
|
double | GetFOV () const |
| Get the camera FOV (horizontal).
|
void | SetRenderOptions (const RenderOptions *opt) |
| Set the rendering options.
|
void | GetRenderOptions (RenderOptions *opt) const |
| Get the rendering options.
|
void | GetImageSize (int *w, int *h) |
| Get the image dimensions.
|
const unsigned char * | GetImageData () const |
| Get a pointer to the image data.
|
double | GetZValue (int x, int y) |
| Get the Z-buffer value at the given image coordinate.
|
GzPose | CalcCameraDelta (int mode, GzVector a, GzVector b) |
| Compute the change in pose based on two image points.
|
void | SetSavePath (const char *pathname) |
| Set the path for saved frames.
|
void | EnableSaveFrame (bool enable) |
| Enable or disable saving.
|
Detailed Description
Basic camera sensor.
This sensor is used for simulating standard monocular cameras; is is used by both camera models (e.g., SonyVID30) and user interface models (e.g., ObserverCam).
Constructor & Destructor Documentation
Camera::Camera |
( |
World * |
world |
) |
|
|
Camera::~Camera |
( |
|
) |
[virtual] |
|
Member Function Documentation
int Camera::Init |
( |
int |
width, |
|
|
int |
height, |
|
|
double |
hfov, |
|
|
double |
minDepth, |
|
|
double |
maxDepth, |
|
|
const char * |
method, |
|
|
int |
zBufferDepth |
|
) |
|
|
|
Initialize the sensor.
- Parameters:
-
| width,height | image width and height (pixels) |
| hfov | horizontal field of view (radians) |
| minDepth,maxDepth | near and far depth clipping planes (m); minDepth must be greater than zero; maxDepth must be greater than minDepth. |
| method | Prefered rendering method: SGIX, GLX or XLIB. |
| zBufferDepth | Z buffer depth (in bits) used for rendering (useful for some nvidia cards that do not support other depths than 24 bits) |
- Returns:
- Zero on success.
|
void Camera::InitContext |
( |
GLContext & |
context |
) |
|
|
|
Update the sensor information.
|
void Camera::SetPose |
( |
GzPose |
pose |
) |
|
|
|
Set the pose of the camera (global cs).
|
|
Get the camera pose (global cs).
|
void Camera::SetFOV |
( |
double |
fov |
) |
|
|
|
Set the camera FOV (horizontal).
|
double Camera::GetFOV |
( |
|
) |
const |
|
|
Get the camera FOV (horizontal).
|
|
Set the rendering options.
|
|
Get the rendering options.
|
void Camera::GetImageSize |
( |
int * |
w, |
|
|
int * |
h |
|
) |
|
|
|
Get the image dimensions.
|
const unsigned char* Camera::GetImageData |
( |
|
) |
const [inline] |
|
|
Get a pointer to the image data.
|
double Camera::GetZValue |
( |
int |
x, |
|
|
int |
y |
|
) |
|
|
|
Get the Z-buffer value at the given image coordinate.
- Parameters:
-
| x,y | Image coordinate; (0, 0) specifies the top-left corner. |
- Returns:
- Image z value; note that this is abitrarily scaled and is not the same as the depth value.
|
|
Compute the change in pose based on two image points.
This function provides natural feedback when using a mouse to control the camera pose. The function computes a change in camera pose, such that the initial image coordinate a and final coordinate b map both to the same global coordinate. Thus, it is possible to "grab" a piece of the terrain and "drag" it to a new location.
Naturally, with only two image coordinates the solution is under-determined (4 constraints and 6 DOF). We therefore provide a mode argument specify what kind of transformation should be affected; the supported modes are translating, zooming and rotating.
- Parameters:
-
| mode | Solution method: 0 = translate; 1 = zoom; 2 = rotate. |
| a,b | Initial and final image points; the z value on a must be specified (use GetZValue() for this). |
- Returns:
- Change in pose (camera frame; post-multiply with current global pose).
|
void Camera::SetSavePath |
( |
const char * |
pathname |
) |
|
|
|
Set the path for saved frames.
|
void Camera::EnableSaveFrame |
( |
bool |
enable |
) |
|
|
|
Enable or disable saving.
|
The documentation for this class was generated from the following files:
|