Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Ogre2 Implementation for Lidar Visual #116

Merged
merged 9 commits into from
Aug 5, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,9 @@

### Ignition Rendering 4.0.0

1. Added Lidar Visual for Ogre2
* [Pull request #116](https://github.com/ignitionrobotics/ign-rendering/pull/116)

1. Added Lidar Visual Types for Ogre1
* [Pull request #114](https://github.com/ignitionrobotics/ign-rendering/pull/114)

Expand Down
25 changes: 19 additions & 6 deletions examples/lidar_visual/GlutWindow.cc
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ unsigned int g_cameraIndex = 0;
ir::ImagePtr g_image;

bool g_initContext = false;

bool g_clear = false;
std::vector<double> g_lidarData;
ir::LidarVisualPtr g_lidar;
bool g_lidarVisualUpdateDirty = false;
Expand Down Expand Up @@ -249,12 +249,19 @@ void updateLidarVisual()
// change detected due to key press
if (g_lidarVisualUpdateDirty)
{
g_lidar->SetDisplayNonHitting(g_showNonHitting);
g_lidar->SetPoints(g_lidarData);
g_lidar->SetType(g_lidarVisType);
g_lidar->Update();
if (g_clear == true)
{
g_lidar->ClearPoints();
}
else
{
g_lidar->SetDisplayNonHitting(g_showNonHitting);
g_lidar->SetPoints(g_lidarData);
g_lidar->SetType(g_lidarVisType);
g_lidar->Update();
}
g_lidarVisualUpdateDirty = false;

g_clear = false;
g_time = std::chrono::steady_clock::now() - g_startTime;
prevUpdateTime = std::chrono::duration_cast<std::chrono::microseconds>(
g_time).count();
Expand Down Expand Up @@ -333,6 +340,11 @@ void keyboardCB(unsigned char _key, int, int)
g_showNonHitting = !g_showNonHitting;
g_lidarVisualUpdateDirty = true;
}
else if (_key == 'c' || _key == 'C')
{
g_clear = true;
g_lidarVisualUpdateDirty = true;
}
else if (_key == '0')
{
g_lidarVisType = LidarVisualType::LVT_NONE;
Expand Down Expand Up @@ -412,6 +424,7 @@ void printUsage()
std::cout << " ESC - Exit " << std::endl;
std::cout << " " << std::endl;
std::cout << " H: Toggle display for non-hitting rays " << std::endl;
std::cout << " C: Clear Visual " << std::endl;
std::cout << " " << std::endl;
std::cout << " 0: Do not display visual " << std::endl;
std::cout << " 1: Display ray lines visual " << std::endl;
Expand Down
4 changes: 2 additions & 2 deletions examples/lidar_visual/Main.cc
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ const std::string RESOURCE_PATH =
const double hMinAngle = -2.26889;
const double hMaxAngle = 2.26889;
const double vMinAngle = 0;
const double vMaxAngle = 0.1;
const double vMaxAngle = 0;
const double minRange = 0.08;
const double maxRange = 10.0;
const int hRayCount = 640;
Expand Down Expand Up @@ -219,7 +219,7 @@ LidarVisualPtr createLidar(ScenePtr _scene)
// LVT_RAY_LINES -> Lines along the lidar sensor to the obstacle
// LVT_TRIANGLE_STRIPS -> Coloured triangle strips denoting hitting and
// non-hitting parts of the scan
lidar->SetType(LidarVisualType::LVT_RAY_LINES);
lidar->SetType(LidarVisualType::LVT_TRIANGLE_STRIPS);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is there any reason to change this?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I did this as LVT_TRIANGLE_STRIPS was the standard visual before ( before we added types, and the only visual in Gazebo Classic), in order to retain the same in the example.

lidar->SetPoints(pts);

VisualPtr root = _scene->RootVisual();
Expand Down
19 changes: 14 additions & 5 deletions include/ignition/rendering/base/BaseLidarVisual.hh
Original file line number Diff line number Diff line change
Expand Up @@ -444,22 +444,27 @@ namespace ignition
mtl = this->Scene()->CreateMaterial("Lidar/BlueStrips");
mtl->SetAmbient(0.0, 0.0, 1.0);
mtl->SetDiffuse(0.0, 0.0, 1.0);
mtl->SetEmissive(0.0, 0.0, 1.0);
mtl->SetTransparency(0.4);
mtl->SetCastShadows(false);
mtl->SetReceiveShadows(false);
mtl->SetLightingEnabled(false);
mtl->SetMetalness(0.0);
mtl->SetReflectivity(0.0);
}

if (!this->Scene()->MaterialRegistered("Lidar/LightBlueStrips"))
{
mtl = this->Scene()->CreateMaterial("Lidar/LightBlueStrips");
mtl->SetAmbient(0.5, 0.5, 1.0);
mtl->SetDiffuse(0.5, 0.5, 1.0);
mtl->SetEmissive(0.5, 0.5, 1.0);
mtl->SetAmbient(0.0, 0.0, 1.0);
mtl->SetDiffuse(0.0, 0.0, 1.0);
mtl->SetEmissive(0.0, 0.0, 1.0);
mtl->SetTransparency(0.8);
mtl->SetCastShadows(false);
mtl->SetReceiveShadows(false);
mtl->SetLightingEnabled(false);
mtl->SetMetalness(0.0);
mtl->SetReflectivity(0.0);
}

if (!this->Scene()->MaterialRegistered("Lidar/TransBlack"))
Expand All @@ -468,10 +473,12 @@ namespace ignition
mtl->SetAmbient(0.0, 0.0, 0.0);
mtl->SetDiffuse(0.0, 0.0, 0.0);
mtl->SetEmissive(0.0, 0.0, 0.0);
mtl->SetTransparency(0.7);
mtl->SetTransparency(0.4);
mtl->SetCastShadows(false);
mtl->SetReceiveShadows(false);
mtl->SetLightingEnabled(false);
mtl->SetMetalness(0.5);
mtl->SetReflectivity(0.2);
}

if (!this->Scene()->MaterialRegistered("Lidar/BlueRay"))
Expand All @@ -480,11 +487,13 @@ namespace ignition
mtl->SetAmbient(0.0, 0.0, 1.0);
mtl->SetDiffuse(0.0, 0.0, 1.0);
mtl->SetEmissive(0.0, 0.0, 1.0);
mtl->SetSpecular(0.1, 0.1, 1);
mtl->SetSpecular(0.0, 0.0, 1.0);
mtl->SetTransparency(0.0);
mtl->SetCastShadows(false);
mtl->SetReceiveShadows(false);
mtl->SetLightingEnabled(false);
mtl->SetMetalness(0.1);
mtl->SetReflectivity(0.2);
}
return;
}
Expand Down
7 changes: 7 additions & 0 deletions ogre/src/OgreLidarVisual.cc
Original file line number Diff line number Diff line change
Expand Up @@ -131,6 +131,7 @@ void OgreLidarVisual::Create()
void OgreLidarVisual::ClearPoints()
{
this->dataPtr->lidarPoints.clear();
this->ClearVisualData();
this->dataPtr->receivedData = false;
}

Expand All @@ -154,6 +155,12 @@ void OgreLidarVisual::SetPoints(const std::vector<double> &_points)
//////////////////////////////////////////////////
void OgreLidarVisual::Update()
{
if (this->lidarVisualType == LidarVisualType::LVT_NONE)
{
this->ClearVisualData();
return;
}

if (!this->dataPtr->receivedData || this->dataPtr->lidarPoints.size() == 0)
{
ignwarn << "New lidar data not received. Exiting update function"
Expand Down
36 changes: 33 additions & 3 deletions ogre2/include/ignition/rendering/ogre2/Ogre2LidarVisual.hh
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#define IGNITION_RENDERING_OGRE2_OGRELIDARVISUAL_HH_

#include <memory>
#include <vector>
#include "ignition/rendering/base/BaseLidarVisual.hh"
#include "ignition/rendering/ogre2/Ogre2Visual.hh"
#include "ignition/rendering/ogre2/Ogre2Scene.hh"
Expand All @@ -29,9 +30,13 @@ namespace ignition
namespace rendering
{
inline namespace IGNITION_RENDERING_VERSION_NAMESPACE {
/// \brief Ogre 2.x implementation of a marker geometry.
//
// Forward declaration
class Ogre2LidarVisualPrivate;

/// \brief Ogre 2.x implementation of a Lidar Visual.
class IGNITION_RENDERING_OGRE2_VISIBLE Ogre2LidarVisual
: public BaseLidarVisual<Ogre2Visual>
: public BaseLidarVisual<Ogre2Visual>
{
/// \brief Constructor
protected: Ogre2LidarVisual();
Expand All @@ -48,8 +53,33 @@ namespace ignition
// Documentation inherited.
public: virtual void Destroy() override;

/// \brief Marker should only be created by scene.
// Documentation inherited
public: virtual void Update() override;

// Documentation inherited
public: virtual void SetPoints(
const std::vector<double> &_points) override;

// Documentation inherited
public: virtual void ClearPoints() override;

// Documentation inherited
public: virtual unsigned int PointCount() const override;

// Documentation inherited
public: virtual std::vector<double> Points() const override;

/// \brief Create the Lidar Visual in ogre
private: void Create();

/// \brief Clear data stored by dynamiclines
private: void ClearVisualData();

/// \brief Lidar Visual should only be created by scene.
private: friend class Ogre2Scene;

/// \brief Private data class
private: std::unique_ptr<Ogre2LidarVisualPrivate> dataPtr;
};
}
}
Expand Down
Loading