diff --git a/examples/worlds/gpu_lidar_retro_values_sensor.sdf b/examples/worlds/gpu_lidar_retro_values_sensor.sdf
new file mode 100644
index 0000000000..f2d7a27c76
--- /dev/null
+++ b/examples/worlds/gpu_lidar_retro_values_sensor.sdf
@@ -0,0 +1,214 @@
+
+
+
+
+
+ 0.001
+ 1.0
+
+
+
+
+ ogre2
+
+
+
+
+
+ true
+ 0 0 10 0 0 0
+ 0.8 0.8 0.8 1
+ 0.2 0.2 0.2 1
+
+ 1000
+ 0.9
+ 0.01
+ 0.001
+
+ -0.5 0.1 -0.9
+
+
+
+ true
+
+
+
+
+
+ 20 20 0.1
+
+
+
+
+
+
+
+ 20 20 0.1
+
+
+
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+
+
+
+
+
+
+ 0 -1 0.5 0 0 0
+
+
+
+ 1
+ 0
+ 0
+ 1
+ 0
+ 1
+
+ 1.0
+
+
+
+
+ 1 1 1
+
+
+
+
+
+
+
+ 1 1 1
+
+
+
+ 1 0 0 1
+ 1 0 0 1
+ 1 0 0 1
+
+
+
+
+
+
+ 0 1 0.5 0 0 0
+
+
+
+ 1
+ 0
+ 0
+ 1
+ 0
+ 1
+
+ 1.0
+
+
+
+
+ 1 1 1
+
+
+
+
+
+ 500
+
+
+ 1 1 1
+
+
+
+ 0 0 1 1
+ 0 0 1 1
+ 0 0 1 1
+
+
+
+
+
+
+ 4 0 0.5 0 0.0 3.14
+
+ 0.05 0.05 0.05 0 0 0
+
+ 0.1
+
+ 0.000166667
+ 0.000166667
+ 0.000166667
+
+
+
+
+
+ 0.1 0.1 0.1
+
+
+
+
+
+
+ 0.1 0.1 0.1
+
+
+
+
+
+ lidar
+ 10
+
+
+
+ 640
+ 1
+ -1.396263
+ 1.396263
+
+
+ 16
+ 1
+ -0.261799
+ 0.261799
+
+
+
+ 0.08
+ 10.0
+ 0.01
+
+
+ 1
+ true
+
+
+
+ true
+
+
+
+
+
diff --git a/include/ignition/gazebo/components/LaserRetro.hh b/include/ignition/gazebo/components/LaserRetro.hh
new file mode 100644
index 0000000000..75d1145e92
--- /dev/null
+++ b/include/ignition/gazebo/components/LaserRetro.hh
@@ -0,0 +1,41 @@
+/*
+ * Copyright (C) 2020 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_GAZEBO_COMPONENTS_LASERRETRO_HH_
+#define IGNITION_GAZEBO_COMPONENTS_LASERRETRO_HH_
+
+#include
+#include
+#include
+
+namespace ignition
+{
+namespace gazebo
+{
+// Inline bracket to help doxygen filtering.
+inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
+namespace components
+{
+ /// \brief A component used to indicate an lidar reflective value
+ using LaserRetro = Component;
+ IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LaserRetro",
+ LaserRetro)
+}
+}
+}
+}
+
+#endif
diff --git a/src/SdfEntityCreator.cc b/src/SdfEntityCreator.cc
index 3845830acb..ca14ac7c4b 100644
--- a/src/SdfEntityCreator.cc
+++ b/src/SdfEntityCreator.cc
@@ -41,6 +41,7 @@
#include "ignition/gazebo/components/Joint.hh"
#include "ignition/gazebo/components/JointAxis.hh"
#include "ignition/gazebo/components/JointType.hh"
+#include "ignition/gazebo/components/LaserRetro.hh"
#include "ignition/gazebo/components/Lidar.hh"
#include "ignition/gazebo/components/Light.hh"
#include "ignition/gazebo/components/LinearAcceleration.hh"
@@ -503,6 +504,12 @@ Entity SdfEntityCreator::CreateEntities(const sdf::Visual *_visual)
this->dataPtr->ecm->CreateComponent(visualEntity,
components::Transparency(_visual->Transparency()));
+ if (_visual->HasLaserRetro())
+ {
+ this->dataPtr->ecm->CreateComponent(visualEntity,
+ components::LaserRetro(_visual->LaserRetro()));
+ }
+
if (_visual->Geom())
{
this->dataPtr->ecm->CreateComponent(visualEntity,
diff --git a/src/SdfEntityCreator_TEST.cc b/src/SdfEntityCreator_TEST.cc
index 94101b4b00..17e776b44d 100644
--- a/src/SdfEntityCreator_TEST.cc
+++ b/src/SdfEntityCreator_TEST.cc
@@ -35,6 +35,7 @@
#include "ignition/gazebo/components/Joint.hh"
#include "ignition/gazebo/components/JointAxis.hh"
#include "ignition/gazebo/components/JointType.hh"
+#include "ignition/gazebo/components/LaserRetro.hh"
#include "ignition/gazebo/components/Light.hh"
#include "ignition/gazebo/components/Link.hh"
#include "ignition/gazebo/components/Material.hh"
@@ -101,6 +102,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities)
EXPECT_TRUE(this->ecm.HasComponentType(components::Geometry::typeId));
EXPECT_TRUE(this->ecm.HasComponentType(components::Material::typeId));
EXPECT_TRUE(this->ecm.HasComponentType(components::Inertial::typeId));
+ EXPECT_TRUE(this->ecm.HasComponentType(components::LaserRetro::typeId));
// Check entities
// 1 x world + 3 x model + 3 x link + 3 x collision + 3 x visual + 1 x light
@@ -356,6 +358,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities)
unsigned int visualCount{0};
this->ecm.Eachecm.ParentEntity(_entity));
EXPECT_DOUBLE_EQ(0.0, _transparency->Data());
+ EXPECT_DOUBLE_EQ(1150.0, _laserRetro->Data());
EXPECT_TRUE(_castShadows->Data());
EXPECT_EQ(sdf::GeometryType::BOX, _geometry->Data().Type());
@@ -417,6 +422,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities)
EXPECT_EQ(cylLinkEntity, this->ecm.ParentEntity(_entity));
EXPECT_DOUBLE_EQ(0.0, _transparency->Data());
+ EXPECT_DOUBLE_EQ(1654.0, _laserRetro->Data());
EXPECT_TRUE(_castShadows->Data());
EXPECT_EQ(sdf::GeometryType::CYLINDER, _geometry->Data().Type());
@@ -440,6 +446,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities)
EXPECT_EQ(sphLinkEntity, this->ecm.ParentEntity(_entity));
EXPECT_DOUBLE_EQ(0.5, _transparency->Data());
+ EXPECT_DOUBLE_EQ(50.0, _laserRetro->Data());
EXPECT_FALSE(_castShadows->Data());
EXPECT_EQ(sdf::GeometryType::SPHERE, _geometry->Data().Type());
diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc
index 1dde5ba785..43c2ca676c 100644
--- a/src/rendering/RenderUtil.cc
+++ b/src/rendering/RenderUtil.cc
@@ -48,6 +48,7 @@
#include "ignition/gazebo/components/DepthCamera.hh"
#include "ignition/gazebo/components/GpuLidar.hh"
#include "ignition/gazebo/components/Geometry.hh"
+#include "ignition/gazebo/components/LaserRetro.hh"
#include "ignition/gazebo/components/Light.hh"
#include "ignition/gazebo/components/Link.hh"
#include "ignition/gazebo/components/Material.hh"
@@ -671,6 +672,12 @@ void RenderUtilPrivate::CreateRenderingEntities(
visual.SetMaterial(material->Data());
}
+ auto laserRetro = _ecm.Component(_entity);
+ if (laserRetro != nullptr)
+ {
+ visual.SetLaserRetro(laserRetro->Data());
+ }
+
// todo(anyone) make visual updates more generic without using extra
// variables like entityTemp just for storing one specific visual
// param?
@@ -863,6 +870,12 @@ void RenderUtilPrivate::CreateRenderingEntities(
visual.SetMaterial(material->Data());
}
+ auto laserRetro = _ecm.Component(_entity);
+ if (laserRetro != nullptr)
+ {
+ visual.SetLaserRetro(laserRetro->Data());
+ }
+
this->newVisuals.push_back(
std::make_tuple(_entity, visual, _parent->Data()));
return true;
diff --git a/src/rendering/SceneManager.cc b/src/rendering/SceneManager.cc
index 0be6da0be2..cc895f05b6 100644
--- a/src/rendering/SceneManager.cc
+++ b/src/rendering/SceneManager.cc
@@ -248,6 +248,11 @@ rendering::VisualPtr SceneManager::CreateVisual(Entity _id,
visualVis->SetUserData("pause-update", static_cast(0));
visualVis->SetLocalPose(_visual.RawPose());
+ if (_visual.HasLaserRetro())
+ {
+ visualVis->SetUserData("laser_retro", _visual.LaserRetro());
+ }
+
math::Vector3d scale = math::Vector3d::One;
math::Pose3d localPose;
rendering::GeometryPtr geom =
diff --git a/test/worlds/shapes.sdf b/test/worlds/shapes.sdf
index ac254fa80b..dad5d0a8db 100644
--- a/test/worlds/shapes.sdf
+++ b/test/worlds/shapes.sdf
@@ -64,6 +64,7 @@
+ 1150
0.12 0.12 0.12 0 0 0
@@ -105,6 +106,7 @@
+ 1654
0.22 0.22 0.22 0 0 0
@@ -146,6 +148,7 @@
+ 50
0.32 0.32 0.32 0 0 0
0.5
false