Skip to content

Commit

Permalink
Added capsule geometry (#200)
Browse files Browse the repository at this point in the history
Signed-off-by: ahcorde <[email protected]>
Signed-off-by: Ian Chen <[email protected]>
Signed-off-by: Louise Poubel <[email protected]>

Co-authored-by: Louise Poubel <[email protected]>
Co-authored-by: Ian Chen <[email protected]>
  • Loading branch information
3 people authored Mar 20, 2021
1 parent 3584189 commit eefcdd9
Show file tree
Hide file tree
Showing 24 changed files with 977 additions and 46 deletions.
16 changes: 16 additions & 0 deletions examples/gazebo_scene_viewer/SceneManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1505,6 +1505,19 @@ void SubSceneManager::ProcessCone(
_parent->AddGeometry(cone);
}

//////////////////////////////////////////////////
void SubSceneManager::ProcessCapsule(
const gazebo::msgs::Geometry & _geometryMsg, VisualPtr _parent)
{
GeometryPtr capsule = this->activeScene->CreateCapsule();
const gazebo::msgs::CapsuleGeom &capsuleMsg = _geometryMsg.capsule();
double x = 2 * capsuleMsg.radius();
double y = 2 * capsuleMsg.radius();
double z = capsuleMsg.length();
_parent->SetLocalScale(x, y, z);
_parent->AddGeometry(capsule);
}

//////////////////////////////////////////////////
//! [process cylinder]
void SubSceneManager::ProcessCylinder(
Expand Down Expand Up @@ -1824,6 +1837,9 @@ void SubSceneManager::CreateGeometryFunctionMap()
// this->geomFunctions[gazebo::msgs::Geometry::CONE] =
// &SubSceneManager::ProcessCone;

this->geomFunctions[gazebo::msgs::Geometry::CAPSULE] =
&SubSceneManager::ProcessSphere;

this->geomFunctions[gazebo::msgs::Geometry::CYLINDER] =
&SubSceneManager::ProcessCylinder;

Expand Down
3 changes: 3 additions & 0 deletions examples/gazebo_scene_viewer/SceneManagerPrivate.hh
Original file line number Diff line number Diff line change
Expand Up @@ -325,6 +325,9 @@ namespace ignition
protected: virtual void ProcessCone(
const gazebo::msgs::Geometry &_geometryMsg, VisualPtr _parent);

protected: virtual void ProcessCapsule(
const gazebo::msgs::Geometry &_geometryMsg, VisualPtr _parent);

protected: virtual void ProcessCylinder(
const gazebo::msgs::Geometry &_geometryMsg, VisualPtr _parent);

Expand Down
11 changes: 11 additions & 0 deletions examples/simple_demo/Main.cc
Original file line number Diff line number Diff line change
Expand Up @@ -137,6 +137,17 @@ void buildScene(ScenePtr _scene)
white->SetRenderOrder(0);
//! [white material]

VisualPtr capsuleVisual = _scene->CreateVisual();
CapsulePtr capsule = _scene->CreateCapsule();
capsule->SetLength(0.2);
capsule->SetRadius(0.2);
capsuleVisual->AddGeometry(capsule);
capsuleVisual->SetOrigin(0.0, 0.0, 0.0);
capsuleVisual->SetLocalPosition(4, 2, 0);
capsuleVisual->SetLocalScale(1, 1, 1);
capsuleVisual->SetMaterial(red);
root->AddChild(capsuleVisual);

// create plane visual
VisualPtr plane = _scene->CreateVisual();
plane->AddGeometry(_scene->CreatePlane());
Expand Down
53 changes: 53 additions & 0 deletions include/ignition/rendering/Capsule.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,53 @@
/*
* Copyright (C) 2021 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.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/

#ifndef IGNITION_RENDERING_CAPSULE_HH_
#define IGNITION_RENDERING_CAPSULE_HH_

#include "ignition/rendering/config.hh"
#include "ignition/rendering/Geometry.hh"
#include "ignition/rendering/Object.hh"

namespace ignition
{
namespace rendering
{
inline namespace IGNITION_RENDERING_VERSION_NAMESPACE {
/// \class Capsule Capsule.hh ignition/rendering/Capsule
/// \brief Geometry for a capsule shape.
class IGNITION_RENDERING_VISIBLE Capsule :
public virtual Geometry
{
/// \brief Destructor
public: virtual ~Capsule() { }

/// \brief Set the radius of the capsule
public: virtual void SetRadius(double _radius) = 0;

/// \brief Set the length of the capsule
public: virtual void SetLength(double _length) = 0;

/// \brief Get the radius of the capsule
public: virtual double Radius() const = 0;

/// \brief Get the length of the capsule
public: virtual double Length() const = 0;
};
}
}
}
#endif
5 changes: 4 additions & 1 deletion include/ignition/rendering/Marker.hh
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,10 @@ namespace ignition
MT_TRIANGLE_LIST = 9,

/// \brief Triangle strip primitive
MT_TRIANGLE_STRIP = 10
MT_TRIANGLE_STRIP = 10,

/// \brief Capsule geometry
MT_CAPSULE = 11,
};

/// \class Marker Marker.hh ignition/rendering/Marker
Expand Down
5 changes: 5 additions & 0 deletions include/ignition/rendering/RenderTypes.hh
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,7 @@ namespace ignition
class ArrowVisual;
class AxisVisual;
class Camera;
class Capsule;
class DepthCamera;
class DirectionalLight;
class GaussianNoisePass;
Expand Down Expand Up @@ -128,6 +129,10 @@ namespace ignition
/// \brief Shared pointer to GizmoVisual
typedef shared_ptr<GizmoVisual> GizmoVisualPtr;

/// \def CapsulePtr
/// \brief Shared pointer to Capsule
typedef shared_ptr<Capsule> CapsulePtr;

/// \def GridPtr
/// \brief Shared pointer to Grid
typedef shared_ptr<Grid> GridPtr;
Expand Down
4 changes: 4 additions & 0 deletions include/ignition/rendering/Scene.hh
Original file line number Diff line number Diff line change
Expand Up @@ -856,6 +856,10 @@ namespace ignition
/// \return The created box
public: virtual GeometryPtr CreateBox() = 0;

/// \brief Create new capsule geometry
/// \return The created capsule
public: virtual CapsulePtr CreateCapsule() = 0;

/// \brief Create new cone geometry
/// \return The created cone
public: virtual GeometryPtr CreateCone() = 0;
Expand Down
109 changes: 109 additions & 0 deletions include/ignition/rendering/base/BaseCapsule.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,109 @@
/*
* Copyright (C) 2021 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.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/

#ifndef IGNITION_RENDERING_BASECAPSULE_HH_
#define IGNITION_RENDERING_BASECAPSULE_HH_

#include "ignition/rendering/Capsule.hh"
#include "ignition/rendering/base/BaseObject.hh"

namespace ignition
{
namespace rendering
{
inline namespace IGNITION_RENDERING_VERSION_NAMESPACE {
/// \brief Base implementation of a Capsule Geometry
template <class T>
class BaseCapsule :
public virtual Capsule,
public virtual T
{
// Documentation inherited
protected: BaseCapsule();

// Documentation inherited
public: virtual ~BaseCapsule();

// Documentation inherited
public: virtual void SetRadius(double _radius) override;

// Documentation inherited
public: virtual void SetLength(double _length) override;

// Documentation inherited
public: virtual double Radius() const override;

// Documentation inherited
public: virtual double Length() const override;

/// \brief Radius of the capsule
protected: double radius = 0.5;

/// \brief Length of the capsule
protected: double length = 0.5;

/// \brief Flag to indicate capsule properties have changed
protected: bool capsuleDirty = false;
};

/////////////////////////////////////////////////
// BaseCapsule
/////////////////////////////////////////////////
template <class T>
BaseCapsule<T>::BaseCapsule()
{
}

/////////////////////////////////////////////////
template <class T>
BaseCapsule<T>::~BaseCapsule()
{
}

/////////////////////////////////////////////////
template <class T>
void BaseCapsule<T>::SetRadius(double _radius)
{
this->radius = _radius;
this->capsuleDirty = true;
}

/////////////////////////////////////////////////
template <class T>
double BaseCapsule<T>::Radius() const
{
return this->radius;
}

/////////////////////////////////////////////////
template <class T>
void BaseCapsule<T>::SetLength(double _length)
{
this->length = _length;
this->capsuleDirty = true;
}

/////////////////////////////////////////////////
template <class T>
double BaseCapsule<T>::Length() const
{
return this->length;
}
}
}
}
#endif
10 changes: 10 additions & 0 deletions include/ignition/rendering/base/BaseScene.hh
Original file line number Diff line number Diff line change
Expand Up @@ -407,6 +407,9 @@ namespace ignition

public: virtual MeshPtr CreateMesh(const MeshDescriptor &_desc) override;

// Documentation inherited.
public: virtual CapsulePtr CreateCapsule() override;

// Documentation inherited.
public: virtual GridPtr CreateGrid() override;

Expand Down Expand Up @@ -565,6 +568,13 @@ namespace ignition
const std::string &_name,
const MeshDescriptor &_desc) = 0;

/// \brief Implementation for creating a capsule geometry object
/// \param[in] _id unique object id.
/// \param[in] _name unique object name.
/// \return Pointer to a capsule geometry object
protected: virtual CapsulePtr CreateCapsuleImpl(unsigned int _id,
const std::string &_name) = 0;

/// \brief Implementation for creating a grid geometry object
/// \param[in] _id unique object id.
/// \param[in] _name unique object name.
Expand Down
80 changes: 80 additions & 0 deletions ogre/include/ignition/rendering/ogre/OgreCapsule.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,80 @@
/*
* Copyright (C) 2021 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.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/

#ifndef IGNITION_RENDERING_OGRE_OGRECAPSULE_HH_
#define IGNITION_RENDERING_OGRE_OGRECAPSULE_HH_

#include <memory>
#include "ignition/rendering/base/BaseCapsule.hh"
#include "ignition/rendering/ogre/OgreGeometry.hh"
#include "ignition/rendering/ogre/OgreIncludes.hh"

namespace Ogre
{
class MovableObject;
}

namespace ignition
{
namespace rendering
{
inline namespace IGNITION_RENDERING_VERSION_NAMESPACE {
// Forward declaration
class OgreCapsulePrivate;

/// \brief Ogre 2.x implementation of a Capsule Visual.
class IGNITION_RENDERING_OGRE_VISIBLE OgreCapsule
: public BaseCapsule<OgreGeometry>
{
/// \brief Constructor
protected: OgreCapsule();

/// \brief Destructor
public: virtual ~OgreCapsule();

// Documentation inherited.
public: virtual void Init() override;

// Documentation inherited.
public: virtual void Destroy() override;

// Documentation inherited.
public: virtual Ogre::MovableObject *OgreObject() const override;

// Documentation inherited.
public: virtual void PreRender() override;

// Documentation inherited.
public: virtual MaterialPtr Material() const override;

// Documentation inherited.
public: virtual void
SetMaterial(MaterialPtr _material, bool _unique) override;

/// \brief Update the capsule geometry in ogre
private: void Update();

/// \brief Capsule should only be created by scene.
private: friend class OgreScene;

/// \brief Private data class
private: std::unique_ptr<OgreCapsulePrivate> dataPtr;
};
}
}
}
#endif
2 changes: 2 additions & 0 deletions ogre/include/ignition/rendering/ogre/OgreRenderTypes.hh
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@ namespace ignition
class OgreArrowVisual;
class OgreAxisVisual;
class OgreCamera;
class OgreCapsule;
class OgreDepthCamera;
class OgreDirectionalLight;
class OgreGeometry;
Expand Down Expand Up @@ -76,6 +77,7 @@ namespace ignition
typedef shared_ptr<OgreArrowVisual> OgreArrowVisualPtr;
typedef shared_ptr<OgreAxisVisual> OgreAxisVisualPtr;
typedef shared_ptr<OgreCamera> OgreCameraPtr;
typedef shared_ptr<OgreCapsule> OgreCapsulePtr;
typedef shared_ptr<OgreDepthCamera> OgreDepthCameraPtr;
typedef shared_ptr<OgreDirectionalLight> OgreDirectionalLightPtr;
typedef shared_ptr<OgreGeometry> OgreGeometryPtr;
Expand Down
3 changes: 3 additions & 0 deletions ogre/include/ignition/rendering/ogre/OgreScene.hh
Original file line number Diff line number Diff line change
Expand Up @@ -148,6 +148,9 @@ namespace ignition
const HeightmapDescriptor &_desc) override;

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

protected: virtual GridPtr CreateGridImpl(
unsigned int _id,
const std::string &_name) override;
Expand Down
Loading

0 comments on commit eefcdd9

Please sign in to comment.