diff --git a/CMakeLists.txt b/CMakeLists.txt
index da6ab9eed0..f8dcca143e 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -121,7 +121,6 @@ ign_find_package(ignition-sensors6 REQUIRED
# cameras
camera
- boundingbox_camera
segmentation_camera
depth_camera
rgbd_camera
diff --git a/examples/worlds/boundingbox_camera.sdf b/examples/worlds/boundingbox_camera.sdf
deleted file mode 100644
index c704eff8fd..0000000000
--- a/examples/worlds/boundingbox_camera.sdf
+++ /dev/null
@@ -1,327 +0,0 @@
-
-
-
-
-
- 0.001
- 1.0
-
-
-
-
- ogre2
-
-
-
-
-
-
-
- 1.0 1.0 1.0
- 0.8 0.8 0.8
- true
-
-
-
-
-
-
-
- 3D View
- false
- docked
-
-
- ogre2
- scene
- 1.0 1.0 1.0
- 0.8 0.8 0.8
- -6 0 6 0 0.5 0
-
-
-
-
-
- World control
- false
- false
- 72
- 121
- 1
-
- floating
-
-
-
-
-
-
- true
- true
- true
-
-
-
-
-
-
- World stats
- false
- false
- 110
- 290
- 1
-
- floating
-
-
-
-
-
-
- true
- true
- true
- true
-
-
-
- boxes_image
-
- docked
- 400
- 600
-
-
-
-
-
-
-
-
-
-
-
- true
- 0 0 10 0 0 0
- 0.8 0.8 0.8 1
- 0.8 0.8 0.8 1
-
- 1000
- 0.9
- 0.01
- 0.001
-
- -0.5 0.1 -0.9
-
-
-
- true
-
-
-
-
- 0 0 1
- 100 100
-
-
-
-
-
-
- 0 0 1
- 100 100
-
-
-
- 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
-
-
-
- 0 0 0.5 1
- 0 0 1 1
- 0 0 0.3 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
- 0.8 0.2 0 1
- 0.8 0 0 1
-
-
-
-
-
-
- true
- -1 -2 0.5 0 0 0
-
-
-
-
- 0.5
-
-
-
-
-
-
- 0.5
-
-
-
- 0 1 0 1
- 0 1 0 1
- 0 1 0 1
-
- false
-
-
-
-
-
-
-
-
- 4 0 1.0 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
-
-
-
-
-
- boxes
-
- full_2d
- 1.047
-
- 800
- 600
-
-
- 0.1
- 10
-
-
- boundingBox_data
-
-
- 1
- 30
- true
-
-
-
-
-
- -1 0 3 0.0 0.0 1.57
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Construction Cone
-
-
-
-
-
-
-
-
diff --git a/include/ignition/gazebo/components/BoundingBoxCamera.hh b/include/ignition/gazebo/components/BoundingBoxCamera.hh
deleted file mode 100644
index 1e18636e29..0000000000
--- a/include/ignition/gazebo/components/BoundingBoxCamera.hh
+++ /dev/null
@@ -1,45 +0,0 @@
-/*
- * 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_GAZEBO_COMPONENTS_BOUNDINGBOXCAMERA_HH_
-#define IGNITION_GAZEBO_COMPONENTS_BOUNDINGBOXCAMERA_HH_
-
-#include
-
-#include
-#include
-#include
-#include
-
-namespace ignition
-{
-namespace gazebo
-{
-// Inline bracket to help doxygen filtering.
-inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
-namespace components
-{
- /// \brief A component type that contains a BoundingBox camera sensor,
- /// sdf::Camera, information.
- using BoundingBoxCamera = Component;
- IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.BoundingBoxCamera",
- BoundingBoxCamera)
-}
-}
-}
-}
-#endif
diff --git a/src/SdfEntityCreator.cc b/src/SdfEntityCreator.cc
index 0e7693c84f..318e559d30 100644
--- a/src/SdfEntityCreator.cc
+++ b/src/SdfEntityCreator.cc
@@ -27,7 +27,6 @@
#include "ignition/gazebo/components/Altimeter.hh"
#include "ignition/gazebo/components/AngularVelocity.hh"
#include "ignition/gazebo/components/Atmosphere.hh"
-#include "ignition/gazebo/components/BoundingBoxCamera.hh"
#include "ignition/gazebo/components/Camera.hh"
#include "ignition/gazebo/components/CanonicalLink.hh"
#include "ignition/gazebo/components/CastShadows.hh"
@@ -811,11 +810,6 @@ Entity SdfEntityCreator::CreateEntities(const sdf::Sensor *_sensor)
this->dataPtr->ecm->CreateComponent(sensorEntity,
components::SegmentationCamera(*_sensor));
}
- else if (_sensor->Type() == sdf::SensorType::BOUNDINGBOX_CAMERA)
- {
- this->dataPtr->ecm->CreateComponent(sensorEntity,
- components::BoundingBoxCamera(*_sensor));
- }
else if (_sensor->Type() == sdf::SensorType::AIR_PRESSURE)
{
this->dataPtr->ecm->CreateComponent(sensorEntity,
diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc
index aacdd0f661..dfa442cd5e 100644
--- a/src/rendering/RenderUtil.cc
+++ b/src/rendering/RenderUtil.cc
@@ -52,7 +52,6 @@
#include
#include "ignition/gazebo/components/Actor.hh"
-#include "ignition/gazebo/components/BoundingBoxCamera.hh"
#include "ignition/gazebo/components/Camera.hh"
#include "ignition/gazebo/components/CastShadows.hh"
#include "ignition/gazebo/components/ChildLinkName.hh"
@@ -234,7 +233,7 @@ class ignition::gazebo::RenderUtilPrivate
public: std::map> entityTemp;
/// \brief A map of entity ids and label data for datasets annotations
- public: std::unordered_map entityLabel;
+ public: std::unordered_map entityLabel;
/// \brief A map of entity ids and wire boxes
public: std::unordered_map wireBoxes;
@@ -452,7 +451,7 @@ class ignition::gazebo::RenderUtilPrivate
/// \brief Update the visuals with label user data
/// \param[in] _entityLabel Map with key visual entity id and value label
public: void UpdateVisualLabels(
- const std::unordered_map &_entityLabel);
+ const std::unordered_map &_entityLabel);
/// \brief A helper function that removes the sensor associated with an
/// entity, if an associated sensor exists. This should be called in
@@ -1405,7 +1404,6 @@ void RenderUtilPrivate::CreateRenderingEntities(
const std::string thermalCameraSuffix{"/image"};
const std::string gpuLidarSuffix{"/scan"};
const std::string segmentationCameraSuffix{"/segmentation"};
- const std::string boundingBoxCameraSuffix{"/boundingbox"};
// Treat all pre-existent entities as new at startup
// TODO(anyone) refactor Each and EachNew below to reduce duplicate code
@@ -1715,17 +1713,6 @@ void RenderUtilPrivate::CreateRenderingEntities(
_parent->Data(), segmentationCameraSuffix);
return true;
});
-
- // Create bounding box cameras
- _ecm.Each(
- [&](const Entity &_entity,
- const components::BoundingBoxCamera *_boundingBoxCamera,
- const components::ParentEntity *_parent)->bool
- {
- addNewSensor(_entity, _boundingBoxCamera->Data(),
- _parent->Data(), boundingBoxCameraSuffix);
- return true;
- });
}
this->initialized = true;
}
@@ -2034,17 +2021,6 @@ void RenderUtilPrivate::CreateRenderingEntities(
_parent->Data(), segmentationCameraSuffix);
return true;
});
-
- // Create bounding box cameras
- _ecm.EachNew(
- [&](const Entity &_entity,
- const components::BoundingBoxCamera *_boundingBoxCamera,
- const components::ParentEntity *_parent)->bool
- {
- addNewSensor(_entity, _boundingBoxCamera->Data(),
- _parent->Data(), boundingBoxCameraSuffix);
- return true;
- });
}
}
}
@@ -2206,16 +2182,6 @@ void RenderUtilPrivate::UpdateRenderingEntities(
this->entityPoses[_entity] = _pose->Data();
return true;
});
-
- // Update bounding box cameras
- _ecm.Each(
- [&](const Entity &_entity,
- const components::BoundingBoxCamera *,
- const components::Pose *_pose)->bool
- {
- this->entityPoses[_entity] = _pose->Data();
- return true;
- });
}
//////////////////////////////////////////////////
@@ -2347,14 +2313,6 @@ void RenderUtilPrivate::RemoveRenderingEntities(
return true;
});
- // bounding box cameras
- _ecm.EachRemoved(
- [&](const Entity &_entity, const components::BoundingBoxCamera *)->bool
- {
- this->removeEntities[_entity] = _info.iterations;
- return true;
- });
-
// collisions
_ecm.EachRemoved(
[&](const Entity &_entity, const components::Collision *)->bool
@@ -2593,7 +2551,7 @@ void RenderUtil::SetTransformActive(bool _active)
////////////////////////////////////////////////
void RenderUtilPrivate::UpdateVisualLabels(
- const std::unordered_map &_entityLabel)
+ const std::unordered_map &_entityLabel)
{
// set visual label
for (const auto &label : _entityLabel)
diff --git a/src/systems/sensors/CMakeLists.txt b/src/systems/sensors/CMakeLists.txt
index 7f616f6c3d..8b56378885 100644
--- a/src/systems/sensors/CMakeLists.txt
+++ b/src/systems/sensors/CMakeLists.txt
@@ -5,7 +5,6 @@ gz_add_system(sensors
${rendering_target}
ignition-common${IGN_COMMON_VER}::ignition-common${IGN_COMMON_VER}
ignition-rendering${IGN_RENDERING_VER}::ignition-rendering${IGN_RENDERING_VER}
- ignition-sensors${IGN_SENSORS_VER}::boundingbox_camera
ignition-sensors${IGN_SENSORS_VER}::camera
ignition-sensors${IGN_SENSORS_VER}::depth_camera
ignition-sensors${IGN_SENSORS_VER}::gpu_lidar
diff --git a/src/systems/sensors/Sensors.cc b/src/systems/sensors/Sensors.cc
index 7e231beb49..4043124df5 100644
--- a/src/systems/sensors/Sensors.cc
+++ b/src/systems/sensors/Sensors.cc
@@ -31,7 +31,6 @@
#include
#include
-#include
#include
#include
#include
@@ -42,7 +41,6 @@
#include
#include "ignition/gazebo/components/Atmosphere.hh"
-#include "ignition/gazebo/components/BoundingBoxCamera.hh"
#include "ignition/gazebo/components/Camera.hh"
#include "ignition/gazebo/components/DepthCamera.hh"
#include "ignition/gazebo/components/GpuLidar.hh"
@@ -470,8 +468,7 @@ void Sensors::PostUpdate(const UpdateInfo &_info,
_ecm.HasComponentType(components::GpuLidar::typeId) ||
_ecm.HasComponentType(components::RgbdCamera::typeId) ||
_ecm.HasComponentType(components::ThermalCamera::typeId) ||
- _ecm.HasComponentType(components::SegmentationCamera::typeId) ||
- _ecm.HasComponentType(components::BoundingBoxCamera::typeId)
+ _ecm.HasComponentType(components::SegmentationCamera::typeId)
))
{
igndbg << "Initialization needed" << std::endl;
@@ -572,11 +569,6 @@ std::string Sensors::CreateSensor(const Entity &_entity,
sensor = this->dataPtr->sensorManager.CreateSensor<
sensors::ThermalCameraSensor>(_sdf);
}
- else if (_sdf.Type() == sdf::SensorType::BOUNDINGBOX_CAMERA)
- {
- sensor = this->dataPtr->sensorManager.CreateSensor<
- sensors::BoundingBoxCameraSensor>(_sdf);
- }
else if (_sdf.Type() == sdf::SensorType::SEGMENTATION_CAMERA)
{
sensor = this->dataPtr->sensorManager.CreateSensor<