Skip to content

Commit

Permalink
Set near/far camera clipping distance (#309)
Browse files Browse the repository at this point in the history
Signed-off-by: Jenn Nguyen <jenn@openrobotics.org>
  • Loading branch information
jennuine authored Nov 3, 2021
1 parent 443bfac commit a8e18ab
Show file tree
Hide file tree
Showing 3 changed files with 78 additions and 2 deletions.
54 changes: 54 additions & 0 deletions src/plugins/minimal_scene/MinimalScene.cc
Original file line number Diff line number Diff line change
Expand Up @@ -542,6 +542,8 @@ void IgnRenderer::Initialize()
this->dataPtr->camera->SetUserData("user-camera", true);
root->AddChild(this->dataPtr->camera);
this->dataPtr->camera->SetLocalPose(this->cameraPose);
this->dataPtr->camera->SetNearClipPlane(this->cameraNearClip);
this->dataPtr->camera->SetFarClipPlane(this->cameraFarClip);
this->dataPtr->camera->SetImageWidth(this->textureSize.width());
this->dataPtr->camera->SetImageHeight(this->textureSize.height());
this->dataPtr->camera->SetAntiAliasing(8);
Expand Down Expand Up @@ -944,6 +946,18 @@ void RenderWindowItem::SetCameraPose(const math::Pose3d &_pose)
this->dataPtr->renderThread->ignRenderer.cameraPose = _pose;
}

/////////////////////////////////////////////////
void RenderWindowItem::SetCameraNearClip(double _near)
{
this->dataPtr->renderThread->ignRenderer.cameraNearClip = _near;
}

/////////////////////////////////////////////////
void RenderWindowItem::SetCameraFarClip(double _far)
{
this->dataPtr->renderThread->ignRenderer.cameraFarClip = _far;
}

/////////////////////////////////////////////////
void RenderWindowItem::SetSceneService(const std::string &_service)
{
Expand Down Expand Up @@ -1044,6 +1058,46 @@ void MinimalScene::LoadConfig(const tinyxml2::XMLElement *_pluginElem)
renderWindow->SetCameraPose(pose);
}

elem = _pluginElem->FirstChildElement("camera_clip");
if (nullptr != elem && !elem->NoChildren())
{
auto child = elem->FirstChildElement("near");
if (nullptr != child && nullptr != child->GetText())
{
double n;
std::stringstream nearStr;
nearStr << std::string(child->GetText());
nearStr >> n;
if (nearStr.fail())
{
ignerr << "Unable to set <near> to '" << nearStr.str()
<< "' using default near clip distance" << std::endl;
}
else
{
renderWindow->SetCameraNearClip(n);
}
}

child = elem->FirstChildElement("far");
if (nullptr != child && nullptr != child->GetText())
{
double f;
std::stringstream farStr;
farStr << std::string(child->GetText());
farStr >> f;
if (farStr.fail())
{
ignerr << "Unable to set <far> to '" << farStr.str()
<< "' using default far clip distance" << std::endl;
}
else
{
renderWindow->SetCameraFarClip(f);
}
}
}

elem = _pluginElem->FirstChildElement("service");
if (nullptr != elem && nullptr != elem->GetText())
{
Expand Down
19 changes: 18 additions & 1 deletion src/plugins/minimal_scene/MinimalScene.hh
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,9 @@ namespace plugins
/// (0.3, 0.3, 0.3, 1.0)
/// * \<camera_pose\> : Optional starting pose for the camera, defaults to
/// (0, 0, 5, 0, 0, 0)
/// * \<camera_clip\> : Optional near/far clipping distance for camera
/// * \<near\> : Camera's near clipping plane distance, defaults to 0.01
/// * \<far\> : Camera's far clipping plane distance, defaults to 1000.0
/// * \<sky\> : If present, sky is enabled.
class MinimalScene : public Plugin
{
Expand Down Expand Up @@ -181,6 +184,12 @@ namespace plugins
/// \brief Initial Camera pose
public: math::Pose3d cameraPose = math::Pose3d(0, 0, 2, 0, 0.4, 0);

/// \brief Default camera near clipping plane distance
public: double cameraNearClip = 0.01;

/// \brief Default camera far clipping plane distance
public: double cameraFarClip = 1000.0;

/// \brief Scene background color
public: math::Color backgroundColor = math::Color::Black;

Expand Down Expand Up @@ -283,9 +292,17 @@ namespace plugins
public: void SetSceneName(const std::string &_name);

/// \brief Set the initial pose the render window camera
/// \param[in] _pose Initical camera pose
/// \param[in] _pose Initial camera pose
public: void SetCameraPose(const math::Pose3d &_pose);

/// \brief Set the render window camera's near clipping plane distance
/// \param[in] _near Near clipping plane distance
public: void SetCameraNearClip(double _near);

/// \brief Set the render window camera's far clipping plane distance
/// \param[in] _far Far clipping plane distance
public: void SetCameraFarClip(double _far);

/// \brief Set scene service to use in this render window
/// A service call will be made using ign-transport to get scene
/// data using this service
Expand Down
7 changes: 6 additions & 1 deletion test/integration/minimal_scene.cc
Original file line number Diff line number Diff line change
Expand Up @@ -82,6 +82,10 @@ TEST(MinimalSceneTest, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(Config))
"<ambient_light>1.0 0 0</ambient_light>"
"<background_color>0 1 0</background_color>"
"<camera_pose>1 2 3 0 0 1.57</camera_pose>"
"<camera_clip>"
" <near>0.1</near>"
" <far>5000</far>"
"</camera_clip>"
"</plugin>";

tinyxml2::XMLDocument pluginDoc;
Expand Down Expand Up @@ -126,6 +130,8 @@ TEST(MinimalSceneTest, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(Config))
ASSERT_NE(nullptr, camera);

EXPECT_EQ(math::Pose3d(1, 2, 3, 0, 0, 1.57), camera->WorldPose());
EXPECT_DOUBLE_EQ(0.1, camera->NearClipPlane());
EXPECT_DOUBLE_EQ(5000.0, camera->FarClipPlane());

// Cleanup
auto plugins = win->findChildren<Plugin *>();
Expand All @@ -139,4 +145,3 @@ TEST(MinimalSceneTest, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(Config))
engine->DestroyScene(scene);
EXPECT_TRUE(rendering::unloadEngine(engine->Name()));
}

0 comments on commit a8e18ab

Please sign in to comment.