Skip to content

Commit

Permalink
Code formatting and Copyright updates
Browse files Browse the repository at this point in the history
Signed-off-by: Utkarsh <[email protected]>
  • Loading branch information
BA-Utkarsh committed Jan 11, 2025
1 parent bdc9edf commit 5c86f06
Show file tree
Hide file tree
Showing 11 changed files with 75 additions and 57 deletions.
5 changes: 3 additions & 2 deletions include/gz/rendering/FrustumVisual.hh
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
/*
* Copyright (C) 2024 Open Source Robotics Foundation
* Copyright (C) 2025 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -128,7 +128,8 @@ namespace gz
/// \brief Get a plane of the frustum.
/// \param[in] _plane The plane to return.
/// \return Plane of the frustum.
public: virtual gz::math::Planed Plane(const FrustumVisualPlane _plane) const = 0;
public: virtual gz::math::Planed Plane(
const FrustumVisualPlane _plane) const = 0;

/// \brief Get the pose of the frustum
/// \return Pose of the frustum
Expand Down
3 changes: 2 additions & 1 deletion include/gz/rendering/Scene.hh
Original file line number Diff line number Diff line change
Expand Up @@ -1118,7 +1118,8 @@ namespace gz
/// ID is already in use, NULL will be returned.
/// \param[in] _id ID of the new frustum visual
/// \return The created frustum visual
public: virtual FrustumVisualPtr CreateFrustumVisual(unsigned int _id) = 0;
public: virtual FrustumVisualPtr CreateFrustumVisual(
unsigned int _id) = 0;

/// \brief Create new frustum visual with the given name. A unique ID
/// will automatically be assigned to the frustum visual. If the given
Expand Down
16 changes: 6 additions & 10 deletions include/gz/rendering/base/BaseFrustumVisual.hh
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
/*
* Copyright (C) 2024 Open Source Robotics Foundation
* Copyright (C) 2025 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -78,13 +78,8 @@ namespace gz
public: virtual void SetAspectRatio(double _aspectRatio) override;

// Documentation inherited
public: virtual gz::math::Planed Plane(const FrustumVisualPlane _plane) const override;

// Documentation inherited
//public: virtual bool Contains(const gz::math::AxisAlignedBox &_b) const override;

// Documentation inherited
//public: virtual bool Contains(const gz::math::Vector3d &_p) const override;
public: virtual gz::math::Planed Plane(
const FrustumVisualPlane _plane) const override;

// Documentation inherited
public: virtual gz::math::Pose3d Pose() const override;
Expand Down Expand Up @@ -219,7 +214,8 @@ namespace gz

/////////////////////////////////////////////////
template <class T>
gz::math::Planed BaseFrustumVisual<T>::Plane(const FrustumVisualPlane _plane) const
gz::math::Planed BaseFrustumVisual<T>::Plane(
const FrustumVisualPlane _plane) const
{
return this->planes[_plane];
}
Expand All @@ -235,7 +231,7 @@ namespace gz
template <class T>
gz::math::Pose3d BaseFrustumVisual<T>::Pose() const
{
return this->pose;
return this->pose;
}
/////////////////////////////////////////////////
template <class T>
Expand Down
4 changes: 2 additions & 2 deletions include/gz/rendering/base/BaseScene.hh
Original file line number Diff line number Diff line change
Expand Up @@ -847,8 +847,8 @@ namespace gz
/// \param[in] _id unique object id.
/// \param[in] _name unique object name.
/// \return Pointer to a frustum visual
protected: virtual FrustumVisualPtr CreateFrustumVisualImpl(unsigned int _id,
const std::string &_name) = 0;
protected: virtual FrustumVisualPtr CreateFrustumVisualImpl(
unsigned int _id, const std::string &_name) = 0;

/// \brief Implementation for creating a heightmap geometry
/// \param[in] _id Unique object id.
Expand Down
2 changes: 1 addition & 1 deletion ogre/include/gz/rendering/ogre/OgreFrustumVisual.hh
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
/*
* Copyright (C) 2020 Open Source Robotics Foundation
* Copyright (C) 2025 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
Expand Down
4 changes: 2 additions & 2 deletions ogre/include/gz/rendering/ogre/OgreScene.hh
Original file line number Diff line number Diff line change
Expand Up @@ -181,8 +181,8 @@ namespace gz
const std::string &_name) override;

// Documentation inherited
protected: virtual FrustumVisualPtr CreateFrustumVisualImpl(unsigned int _id,
const std::string &_name) override;
protected: virtual FrustumVisualPtr CreateFrustumVisualImpl(
unsigned int _id, const std::string &_name) override;

// Documentation inherited
protected: virtual WireBoxPtr CreateWireBoxImpl(unsigned int _id,
Expand Down
11 changes: 6 additions & 5 deletions ogre/src/OgreFrustumVisual.cc
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
/*
* Copyright (C) 2020 Open Source Robotics Foundation
* Copyright (C) 2025 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -29,8 +29,8 @@ class gz::rendering::OgreFrustumVisualPrivate
public: std::vector<std::shared_ptr<OgreDynamicLines>> rayLines;

/// \brief Frustum visual type
//public: FrustumVisualPlane frustumVisPlane =
//FrustumVisualPlane::FRUSTUM_PLANE_TOP;
// public: FrustumVisualPlane frustumVisPlane =
// FrustumVisualPlane::FRUSTUM_PLANE_TOP;

/// \brief The visibility of the visual
public: bool visible = true;
Expand All @@ -39,7 +39,8 @@ class gz::rendering::OgreFrustumVisualPrivate
public: std::array<gz::math::Vector3d, 8> points;

/// \brief each edge of the frustum.
public: std::array<std::pair<gz::math::Vector3d, gz::math::Vector3d>, 12> edges;
public: std::array<std::pair<gz::math::Vector3d,
gz::math::Vector3d>, 12> edges;
};

using namespace gz;
Expand Down Expand Up @@ -91,7 +92,7 @@ void OgreFrustumVisual::ClearVisualData()
//////////////////////////////////////////////////
void OgreFrustumVisual::Update()
{
//no ops FIX-ME
// no ops
}

//////////////////////////////////////////////////
Expand Down
2 changes: 1 addition & 1 deletion ogre2/include/gz/rendering/ogre2/Ogre2FrustumVisual.hh
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
/*
* Copyright (C) 2020 Open Source Robotics Foundation
* Copyright (C) 2025 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
Expand Down
4 changes: 2 additions & 2 deletions ogre2/include/gz/rendering/ogre2/Ogre2Scene.hh
Original file line number Diff line number Diff line change
Expand Up @@ -344,8 +344,8 @@ namespace gz
const std::string &_name) override;

// Documentation inherited
protected: virtual FrustumVisualPtr CreateFrustumVisualImpl(unsigned int _id,
const std::string &_name) override;
protected: virtual FrustumVisualPtr CreateFrustumVisualImpl(
unsigned int _id, const std::string &_name) override;

// Documentation inherited
protected: virtual WireBoxPtr CreateWireBoxImpl(unsigned int _id,
Expand Down
79 changes: 49 additions & 30 deletions ogre2/src/Ogre2FrustumVisual.cc
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
/*
* Copyright (C) 2020 Open Source Robotics Foundation
* Copyright (C) 2025 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -58,8 +58,8 @@ class gz::rendering::Ogre2FrustumVisualPrivate
public: std::vector<std::shared_ptr<Ogre2DynamicRenderable>> rayLines;

/// \brief Frustum visual type
//public: FrustumVisualPlane frustumVisPlane =
//FrustumVisualPlane::FRUSTUM_PLANE_TOP;
// public: FrustumVisualPlane frustumVisPlane =
// FrustumVisualPlane::FRUSTUM_PLANE_TOP;

/// \brief The visibility of the visual
public: bool visible = true;
Expand All @@ -68,7 +68,8 @@ class gz::rendering::Ogre2FrustumVisualPrivate
public: std::array<gz::math::Vector3d, 8> points;

/// \brief each edge of the frustum.
public: std::array<std::pair<gz::math::Vector3d, gz::math::Vector3d>, 12> edges;
public: std::array<std::pair<gz::math::Vector3d,
gz::math::Vector3d>, 12> edges;
};

using namespace gz;
Expand Down Expand Up @@ -148,10 +149,9 @@ void Ogre2FrustumVisual::Update()
#if (OGRE_VERSION <= ((1 << 16) | (10 << 8) | 7))
MaterialPtr mat = this->Scene()->Material("Frustum/BlueRay");
#else
//MaterialPtr mat = this->Scene()->Material(rayLineMat); //FIX-ME
MaterialPtr mat = this->Scene()->Material("Frustum/BlueRay");
#endif

renderable->SetMaterial(mat, false);
renderable->SetOperationType(MT_LINE_LIST);
this->dataPtr->rayLines.push_back(renderable);
Expand All @@ -172,9 +172,12 @@ void Ogre2FrustumVisual::Update()
double farHeight = farWidth / this->aspectRatio;

// Up, right, and forward unit vectors.
gz::math::Vector3d forward = this->pose.Rot().RotateVector(gz::math::Vector3d::UnitX);
gz::math::Vector3d up = this->pose.Rot().RotateVector(gz::math::Vector3d::UnitZ);
gz::math::Vector3d right = this->pose.Rot().RotateVector(-gz::math::Vector3d::UnitY);
gz::math::Vector3d forward =
this->pose.Rot().RotateVector(gz::math::Vector3d::UnitX);
gz::math::Vector3d up =
this->pose.Rot().RotateVector(gz::math::Vector3d::UnitZ);
gz::math::Vector3d right =
this->pose.Rot().RotateVector(-gz::math::Vector3d::UnitY);

// Near plane center
gz::math::Vector3d nearCenter = this->pose.Pos() + forward * this->near;
Expand All @@ -189,10 +192,14 @@ void Ogre2FrustumVisual::Update()
gz::math::Vector3d rightFarWidth2 = right * (farWidth * 0.5);

// Compute the vertices of the near plane
gz::math::Vector3d nearTopLeft = nearCenter + upNearHeight2 - rightNearWidth2;
gz::math::Vector3d nearTopRight = nearCenter + upNearHeight2 + rightNearWidth2;
gz::math::Vector3d nearBottomLeft = nearCenter - upNearHeight2 - rightNearWidth2;
gz::math::Vector3d nearBottomRight = nearCenter - upNearHeight2 + rightNearWidth2;
gz::math::Vector3d nearTopLeft =
nearCenter + upNearHeight2 - rightNearWidth2;
gz::math::Vector3d nearTopRight =
nearCenter + upNearHeight2 + rightNearWidth2;
gz::math::Vector3d nearBottomLeft =
nearCenter - upNearHeight2 - rightNearWidth2;
gz::math::Vector3d nearBottomRight =
nearCenter - upNearHeight2 + rightNearWidth2;

// Compute the vertices of the far plane
gz::math::Vector3d farTopLeft = farCenter + upFarHeight2 - rightFarWidth2;
Expand Down Expand Up @@ -265,23 +272,35 @@ void Ogre2FrustumVisual::Update()
// Compute plane offsets
// Set the planes, where the first value is the plane normal and the
// second the plane offset
gz::math::Vector3d norm = gz::math::Vector3d::Normal(nearTopLeft, nearTopRight, nearBottomLeft);
this->planes[FrustumVisualPlane::FRUSTUM_PLANE_NEAR].Set(norm, nearCenter.Dot(norm));

norm = gz::math::Vector3d::Normal(farTopRight, farTopLeft, farBottomLeft);
this->planes[FrustumVisualPlane::FRUSTUM_PLANE_FAR].Set(norm, farCenter.Dot(norm));

norm = gz::math::Vector3d::Normal(farTopLeft, nearTopLeft, nearBottomLeft);
this->planes[FrustumVisualPlane::FRUSTUM_PLANE_LEFT].Set(norm, leftCenter.Dot(norm));

norm = gz::math::Vector3d::Normal(nearTopRight, farTopRight, farBottomRight);
this->planes[FrustumVisualPlane::FRUSTUM_PLANE_RIGHT].Set(norm, rightCenter.Dot(norm));

norm = gz::math::Vector3d::Normal(nearTopLeft, farTopLeft, nearTopRight);
this->planes[FrustumVisualPlane::FRUSTUM_PLANE_TOP].Set(norm, topCenter.Dot(norm));

norm = gz::math::Vector3d::Normal(nearBottomLeft, nearBottomRight, farBottomRight);
this->planes[FrustumVisualPlane::FRUSTUM_PLANE_BOTTOM].Set(norm, bottomCenter.Dot(norm));
gz::math::Vector3d norm = gz::math::Vector3d::Normal(
nearTopLeft, nearTopRight, nearBottomLeft);
this->planes[FrustumVisualPlane::FRUSTUM_PLANE_NEAR].Set(
norm, nearCenter.Dot(norm));

norm = gz::math::Vector3d::Normal(
farTopRight, farTopLeft, farBottomLeft);
this->planes[FrustumVisualPlane::FRUSTUM_PLANE_FAR].Set(
norm, farCenter.Dot(norm));

norm = gz::math::Vector3d::Normal(
farTopLeft, nearTopLeft, nearBottomLeft);
this->planes[FrustumVisualPlane::FRUSTUM_PLANE_LEFT].Set(
norm, leftCenter.Dot(norm));

norm = gz::math::Vector3d::Normal(
nearTopRight, farTopRight, farBottomRight);
this->planes[FrustumVisualPlane::FRUSTUM_PLANE_RIGHT].Set(
norm, rightCenter.Dot(norm));

norm = gz::math::Vector3d::Normal(
nearTopLeft, farTopLeft, nearTopRight);
this->planes[FrustumVisualPlane::FRUSTUM_PLANE_TOP].Set(
norm, topCenter.Dot(norm));

norm = gz::math::Vector3d::Normal(
nearBottomLeft, nearBottomRight, farBottomRight);
this->planes[FrustumVisualPlane::FRUSTUM_PLANE_BOTTOM].Set(
norm, bottomCenter.Dot(norm));

renderable->Update();
this->SetVisible(this->dataPtr->visible);
Expand Down
2 changes: 1 addition & 1 deletion src/FrustumVisual.cc
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
/*
* Copyright (C) 2024 Open Source Robotics Foundation
* Copyright (C) 2025 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
Expand Down

0 comments on commit 5c86f06

Please sign in to comment.