Skip to content

Commit

Permalink
Joint visual (#366)
Browse files Browse the repository at this point in the history
* Added main class

Signed-off-by: Atharva Pusalkar <[email protected]>

* Added base API

Signed-off-by: Atharva Pusalkar <[email protected]>

* Added scene impl

Signed-off-by: Atharva Pusalkar <[email protected]>

* Added UpdateAxisImpl

Signed-off-by: Atharva Pusalkar <[email protected]>

* Add rotation visual

Signed-off-by: Atharva Pusalkar <[email protected]>

* Add ShowAxisHead method

Signed-off-by: Atharva Pusalkar <[email protected]>

* codecheck

Signed-off-by: Atharva Pusalkar <[email protected]>

* Add ScaleToChild method

Signed-off-by: Atharva Pusalkar <[email protected]>

* Fix parent axis visual

Signed-off-by: Atharva Pusalkar <[email protected]>

* Add hinge2 example

Signed-off-by: Atharva Pusalkar <[email protected]>

* Fix parent scaling

Signed-off-by: Atharva Pusalkar <[email protected]>

* Update API to set axes

Signed-off-by: Atharva Pusalkar <[email protected]>

* Add Destroy impl

Signed-off-by: Atharva Pusalkar <[email protected]>

* Update ArrowVisual test

Signed-off-by: Atharva Pusalkar <[email protected]>

* Update AxisVisual test

Signed-off-by: Atharva Pusalkar <[email protected]>

* Fix variable name

Signed-off-by: Atharva Pusalkar <[email protected]>

* Fix visibility and destroy

Signed-off-by: Atharva Pusalkar <[email protected]>

* Fix destroy child visuals

Signed-off-by: Atharva Pusalkar <[email protected]>

* Fix BaseArrowVisual::Destroy

Signed-off-by: Atharva Pusalkar <[email protected]>

* Add test

Signed-off-by: Atharva Pusalkar <[email protected]>

* Use IGN_PI

Signed-off-by: Atharva Pusalkar <[email protected]>

* Style comments

Signed-off-by: Atharva Pusalkar <[email protected]>

* Add curly braces

Signed-off-by: Atharva Pusalkar <[email protected]>

* Add useParentFrame

Signed-off-by: Atharva Pusalkar <[email protected]>

* Style fixes

Signed-off-by: Atharva Pusalkar <[email protected]>

* Remove const

Signed-off-by: Atharva Pusalkar <[email protected]>

* Style fixes

Signed-off-by: Atharva Pusalkar <[email protected]>

* Add  documentation inherited

Signed-off-by: Atharva Pusalkar <[email protected]>

* Change joint parent material

Signed-off-by: Atharva Pusalkar <[email protected]>

* Improve joint visual demo

Signed-off-by: Atharva Pusalkar <[email protected]>

* Fix Revolute2 and Universal joint visual types

Signed-off-by: Atharva Pusalkar <[email protected]>

* Add destroy check to test

Signed-off-by: Atharva Pusalkar <[email protected]>
  • Loading branch information
atharva-18 authored Aug 19, 2021
1 parent afa2270 commit 3cbd121
Show file tree
Hide file tree
Showing 24 changed files with 1,319 additions and 6 deletions.
42 changes: 40 additions & 2 deletions examples/visualization_demo/Main.cc
Original file line number Diff line number Diff line change
Expand Up @@ -118,11 +118,21 @@ void buildScene(ScenePtr _scene)
blue->SetTransparency(0.5);
blue->SetDepthWriteEnabled(false);

// create gray material
MaterialPtr gray = _scene->CreateMaterial();
gray->SetAmbient(0.7, 0.7, 0.7);
gray->SetDiffuse(0.7, 0.7, 0.7);
gray->SetSpecular(0.7, 0.7, 0.7);
gray->SetShininess(50);
gray->SetReflectivity(0);
gray->SetTransparency(0.75);
gray->SetDepthWriteEnabled(false);

// create box visual
VisualPtr box = _scene->CreateVisual("parent_box");
box->AddGeometry(_scene->CreateBox());
box->SetOrigin(0.0, 0.0, 0.0);
box->SetLocalPosition(4.5, 0.0, 0.0);
box->SetLocalPosition(4.5, -1.0, 0.0);
box->SetLocalRotation(0, 0, 0);
box->SetMaterial(blue);
root->AddChild(box);
Expand All @@ -149,7 +159,7 @@ void buildScene(ScenePtr _scene)
ignition::math::Pose3d p(0.0, 0.0, 0.0, 0.0, 0.0, 0.0);
ignition::math::Inertiald inertial{massMatrix, p};
inertiaVisual->SetInertial(inertial);
inertiaVisual->SetLocalPosition(1, 0, 0);
inertiaVisual->SetLocalPosition(1.5, -1.0, 0);
root->AddChild(inertiaVisual);

// create CoM visual
Expand All @@ -162,6 +172,34 @@ void buildScene(ScenePtr _scene)
comVisual->SetInertial(comVisualInertial);
box->AddChild(comVisual);

// create joint child visual
VisualPtr jointChildBox = _scene->CreateVisual("joint_child");
jointChildBox->AddGeometry(_scene->CreateBox());
jointChildBox->SetOrigin(0.0, 0.0, 0.0);
jointChildBox->SetLocalPosition(3.5, 0.5, 0.0);
jointChildBox->SetLocalRotation(0, 0, 0);
jointChildBox->SetMaterial(blue);
root->AddChild(jointChildBox);

// create joint parent visual
VisualPtr jointParentBox = _scene->CreateVisual("joint_parent");
jointParentBox->AddGeometry(_scene->CreateBox());
jointParentBox->SetOrigin(0.0, 0.0, 0.0);
jointParentBox->SetLocalPosition(2.0, 0.5, 0.0);
jointParentBox->SetLocalRotation(1.5, -1.0, 0);
jointParentBox->SetMaterial(gray);
root->AddChild(jointParentBox);

// create joint visual
JointVisualPtr jointVisual = _scene->CreateJointVisual();
jointChildBox->AddChild(jointVisual);
jointVisual->SetType(JointVisualType::JVT_REVOLUTE2);
ignition::math::Vector3d axis2(1.0, 1.0, 1.0);
jointVisual->SetAxis(axis2);

ignition::math::Vector3d axis1(1.0, 0.0, 0.0);
jointVisual->SetParentAxis(axis1, jointParentBox->Name(), true);

// create camera
CameraPtr camera = _scene->CreateCamera("camera");
camera->SetLocalPosition(0.0, 0.0, 0.0);
Expand Down
12 changes: 12 additions & 0 deletions include/ignition/rendering/ArrowVisual.hh
Original file line number Diff line number Diff line change
Expand Up @@ -42,9 +42,21 @@ namespace ignition
/// \return The arrow-shaft visual
public: virtual VisualPtr Shaft() const = 0;

/// \brief Get arrow-rotation visual
/// \return The arrow-rotation visual
public: virtual VisualPtr Rotation() const = 0;

/// \brief set true to show the arrow head, false otherwise
/// \param[in] _b true to show the arrow head, false otherwise
public: virtual void ShowArrowHead(bool _b) = 0;

/// \brief set true to show the arrow shaft, false otherwise
/// \param[in] _b true to show the arrow shaft, false otherwise
public: virtual void ShowArrowShaft(bool _b) = 0;

/// \brief Set true to show the rotation of the arrow, false otherwise
/// \param[in] _b True to show the arrow rotation.
public: virtual void ShowArrowRotation(bool _b) = 0;
};
}
}
Expand Down
5 changes: 5 additions & 0 deletions include/ignition/rendering/AxisVisual.hh
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,11 @@ namespace ignition
/// \brief set true to show the axis heads, false otherwise
/// \param[in] _b true to show the axis heads, false otherwise
public: virtual void ShowAxisHead(bool _b) = 0;

/// \brief set true to show the specified axis head, false otherwise
/// \param[in] _axis Axis index. 0: x, 1: y, 2: z
/// \param[in] _b true to show the specified axis head, false otherwise
public: virtual void ShowAxisHead(unsigned int _axis, bool _b) = 0;
};
}
}
Expand Down
138 changes: 138 additions & 0 deletions include/ignition/rendering/JointVisual.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,138 @@
/*
* 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_JOINTVISUAL_HH_
#define IGNITION_RENDERING_JOINTVISUAL_HH_

#include <string>

#include <ignition/math/Vector3.hh>

#include "ignition/rendering/config.hh"
#include "ignition/rendering/Object.hh"
#include "ignition/rendering/RenderTypes.hh"
#include "ignition/rendering/Visual.hh"

namespace ignition
{
namespace rendering
{
inline namespace IGNITION_RENDERING_VERSION_NAMESPACE {
//
/// \brief Enum for JointVisual types
enum IGNITION_RENDERING_VISIBLE JointVisualType
{
/// \brief No type
JVT_NONE = 0,

/// \brief Revolute joint type
JVT_REVOLUTE = 1,

/// \brief Revolute2 joint type
JVT_REVOLUTE2 = 2,

/// \brief Prismatic joint type
JVT_PRISMATIC = 3,

/// \brief Universal joint type
JVT_UNIVERSAL = 4,

/// \brief Ball joint type
JVT_BALL = 5,

/// \brief Screw joint type
JVT_SCREW = 6,

/// \brief Gearbox joint type
JVT_GEARBOX = 7,

/// \brief Fixed joint type
JVT_FIXED = 8
};

/// \class JointVisual JointVisual.hh
/// ignition/rendering/JointVisual.hh
/// \brief Represents a joint visual
class IGNITION_RENDERING_VISIBLE JointVisual :
public virtual Visual
{
/// \brief Destructor
public: virtual ~JointVisual() {}

/// \brief Create an axis and attach it to the joint visual.
/// \param[in] _axis Axis vector.
/// \param[in] _useParentFrame True if axis vector is expressed in
/// parent frame.
public: virtual void SetAxis(const ignition::math::Vector3d &_axis,
bool _useParentFrame = false) = 0;

/// \brief Get axis vector.
/// \return The axis vector.
public: virtual ignition::math::Vector3d Axis() const = 0;

/// \brief Create a parent axis for hinge2 and universal joint types
/// and attach it to the joint visual.
/// \param[in] _axis Axis vector.
/// \param[in] _parentName Joint parent name.
/// \param[in] _useParentFrame True if axis vector is expressed in
/// parent frame.
public: virtual void SetParentAxis(
const ignition::math::Vector3d &_axis,
const std::string &_parentName,
bool _useParentFrame = false) = 0;

/// \brief Get parent axis vector.
/// \return The parent axis vector.
public: virtual ignition::math::Vector3d ParentAxis() const = 0;

/// \brief Update an axis' arrow visual.
/// \param[in] _axis Axis vector.
/// \param[in] _useParentFrame True if axis vector is expressed in
/// parent frame.
/// \return True if axis was updated else false.
public: virtual bool UpdateAxis(const ignition::math::Vector3d &_axis,
bool _useParentFrame = false) = 0;

/// \brief Update the parent axis' arrow visual if it exists.
/// \param[in] _axis Axis vector.
/// \param[in] _useParentFrame True if axis vector is expressed in
/// parent frame.
/// \return True if parent axis was updated else false.
public: virtual bool UpdateParentAxis(
const ignition::math::Vector3d &_axis,
bool _useParentFrame = false) = 0;

/// \brief Set type for joint visual.
/// \param[in] _type The type of visualisation for joint.
public: virtual void SetType(const JointVisualType _type) = 0;

/// \brief Get joint visual type.
/// \return The joint visual type.
public: virtual JointVisualType Type() const = 0;

/// \brief Get the JointVisual which is attached to the parent.
/// \return Parent axis visual.
public: virtual JointVisualPtr ParentAxisVisual() const = 0;

/// \brief Get the arrow visual which represents the axis attached to the
/// child.
/// \return Arrow visual.
public: virtual ArrowVisualPtr ArrowVisual() const = 0;
};
}
}
}
#endif
4 changes: 4 additions & 0 deletions include/ignition/rendering/Node.hh
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,10 @@ namespace ignition
/// \return The local pose
public: virtual math::Pose3d LocalPose() const = 0;

/// \brief Get the initial local pose
/// \return The initial local pose
public: virtual math::Pose3d InitialLocalPose() const = 0;

/// \brief Set the local pose
/// \param[in] _pose New local pose
public: virtual void SetLocalPose(const math::Pose3d &_pose) = 0;
Expand Down
29 changes: 29 additions & 0 deletions include/ignition/rendering/Scene.hh
Original file line number Diff line number Diff line change
Expand Up @@ -881,6 +881,35 @@ namespace ignition
public: virtual InertiaVisualPtr CreateInertiaVisual(
unsigned int _id, const std::string &_name) = 0;

/// \brief Create new joint visual. A unique ID and name will
/// automatically be assigned to the Joint visual.
/// \return The created Joint visual
public: virtual JointVisualPtr CreateJointVisual() = 0;

/// \brief Create new joint visual with the given ID. A unique name
/// will automatically be assigned to the visual. If the given ID is
/// already in use, NULL will be returned.
/// \param[in] _id ID of the new Joint visual
/// \return The created Joint visual
public: virtual JointVisualPtr CreateJointVisual(
unsigned int _id) = 0;

/// \brief Create new joint visual with the given name. A unique ID
/// will automatically be assigned to the visual. If the given name is
/// already in use, NULL will be returned.
/// \param[in] _name Name of the new Joint visual
/// \return The created Joint visual
public: virtual JointVisualPtr CreateJointVisual(
const std::string &_name) = 0;

/// \brief Create new joint visual with the given name. If either the
/// given ID or name is already in use, NULL will be returned.
/// \param[in] _id ID of the new Joint visual
/// \param[in] _name Name of the new Joint visual
/// \return The created Joint visual
public: virtual JointVisualPtr CreateJointVisual(
unsigned int _id, const std::string &_name) = 0;

/// \brief Create new light visual. A unique ID and name will
/// automatically be assigned to the light visual.
/// \return The created light visual
Expand Down
Loading

0 comments on commit 3cbd121

Please sign in to comment.