Revision: 6670 http://playerstage.svn.sourceforge.net/playerstage/?rev=6670&view=rev Author: natepak Date: 2008-06-23 15:51:30 -0700 (Mon, 23 Jun 2008)
Log Message: ----------- Added Vertical and Horizontal field of view attributes to the cameras Modified Paths: -------------- code/gazebo/trunk/libgazebo/gazebo.h code/gazebo/trunk/server/controllers/camera/generic/Generic_Camera.cc code/gazebo/trunk/server/controllers/camera/stereo/Stereo_Camera.cc code/gazebo/trunk/server/rendering/OgreCamera.cc code/gazebo/trunk/server/rendering/OgreCamera.hh code/gazebo/trunk/server/rendering/UserCamera.cc Modified: code/gazebo/trunk/libgazebo/gazebo.h =================================================================== --- code/gazebo/trunk/libgazebo/gazebo.h 2008-06-23 22:19:19 UTC (rev 6669) +++ code/gazebo/trunk/libgazebo/gazebo.h 2008-06-23 22:51:30 UTC (rev 6670) @@ -572,6 +572,9 @@ /// Horizontal field of view of the camera in radians public: double hfov; + /// Vertical field of view of the camera in radians + public: double vfov; + /// Pose of the camera public: Pose camera_pose; @@ -1351,7 +1354,10 @@ /// Horizontal field of view of the camera in radians public: double hfov; - /// Left image size + /// Vertical field of view of the camera in radians + public: double vfov; + + // Left image size public: unsigned int left_rgb_size; /// left image (R8G8B8) Modified: code/gazebo/trunk/server/controllers/camera/generic/Generic_Camera.cc =================================================================== --- code/gazebo/trunk/server/controllers/camera/generic/Generic_Camera.cc 2008-06-23 22:19:19 UTC (rev 6669) +++ code/gazebo/trunk/server/controllers/camera/generic/Generic_Camera.cc 2008-06-23 22:51:30 UTC (rev 6670) @@ -107,7 +107,8 @@ data->image_size = data->width * data->height * 3; // GetFOV() returns radians - data->hfov = this->myParent->GetFOV(); + data->hfov = this->myParent->GetHFOV(); + data->vfov = this->myParent->GetVFOV(); // Set the pose of the camera cameraPose = this->myParent->GetWorldPose(); Modified: code/gazebo/trunk/server/controllers/camera/stereo/Stereo_Camera.cc =================================================================== --- code/gazebo/trunk/server/controllers/camera/stereo/Stereo_Camera.cc 2008-06-23 22:19:19 UTC (rev 6669) +++ code/gazebo/trunk/server/controllers/camera/stereo/Stereo_Camera.cc 2008-06-23 22:51:30 UTC (rev 6670) @@ -136,7 +136,8 @@ stereo_data->farClip = this->myParent->GetFarClip(); stereo_data->nearClip = this->myParent->GetNearClip(); - stereo_data->hfov = this->myParent->GetFOV(); + stereo_data->hfov = this->myParent->GetHFOV(); + stereo_data->vfov = this->myParent->GetVFOV(); //stereo_data->right_rgb_size = stereo_data->width * stereo_data->height * 3; //stereo_data->left_rgb_size = stereo_data->width * stereo_data->height * 3; @@ -190,7 +191,9 @@ camera_data->image_size = camera_data->width * camera_data->height * 3; assert (camera_data->image_size <= sizeof(camera_data->image)); - camera_data->hfov = this->myParent->GetFOV(); + camera_data->hfov = this->myParent->GetHFOV(); + camera_data->vfov = this->myParent->GetVFOV(); + // Set the pose of the camera cameraPose = this->myParent->GetWorldPose(); camera_data->camera_pose.pos.x = cameraPose.pos.x; Modified: code/gazebo/trunk/server/rendering/OgreCamera.cc =================================================================== --- code/gazebo/trunk/server/rendering/OgreCamera.cc 2008-06-23 22:19:19 UTC (rev 6669) +++ code/gazebo/trunk/server/rendering/OgreCamera.cc 2008-06-23 22:51:30 UTC (rev 6670) @@ -237,12 +237,19 @@ ////////////////////////////////////////////////////////////////////////////// /// Get the horizontal field of view of the camera -double OgreCamera::GetFOV() const +double OgreCamera::GetHFOV() const { return this->hfov; } ////////////////////////////////////////////////////////////////////////////// +/// Get the vertical field of view of the camera +double OgreCamera::GetVFOV() const +{ + return this->camera->getFOVy().valueRadians(); +} + +////////////////////////////////////////////////////////////////////////////// /// Get the width of the image unsigned int OgreCamera::GetImageWidth() const { Modified: code/gazebo/trunk/server/rendering/OgreCamera.hh =================================================================== --- code/gazebo/trunk/server/rendering/OgreCamera.hh 2008-06-23 22:19:19 UTC (rev 6669) +++ code/gazebo/trunk/server/rendering/OgreCamera.hh 2008-06-23 22:51:30 UTC (rev 6670) @@ -100,7 +100,10 @@ public: void SetFOV( float radians ); /// \brief Get the camera FOV (horizontal) - public: double GetFOV() const; + public: double GetHFOV() const; + + /// \brief Get the camera FOV (vertical) + public: double GetVFOV() const; /// \brief Get the width of the image public: unsigned int GetImageWidth() const; Modified: code/gazebo/trunk/server/rendering/UserCamera.cc =================================================================== --- code/gazebo/trunk/server/rendering/UserCamera.cc 2008-06-23 22:19:19 UTC (rev 6669) +++ code/gazebo/trunk/server/rendering/UserCamera.cc 2008-06-23 22:51:30 UTC (rev 6670) @@ -57,7 +57,7 @@ { OgreCamera::LoadCam(node); - this->SetClipDist(0.1, 1000); + this->SetClipDist(0.1, 100); this->SetFOV( DTOR(60) ); } This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. ------------------------------------------------------------------------- Check out the new SourceForge.net Marketplace. It's the best place to buy or sell services for just about anything Open Source. http://sourceforge.net/services/buy/index.php _______________________________________________ Playerstage-commit mailing list Playerstage-commit@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/playerstage-commit