Skip to content

Commit

Permalink
Added lidar component inspector (#1203)
Browse files Browse the repository at this point in the history
* Support editing air pressure sensor in the GUI

Signed-off-by: Nate Koenig <[email protected]>

* Add noise to qrc

Signed-off-by: Nate Koenig <[email protected]>

* Add noise to qrc

Signed-off-by: Nate Koenig <[email protected]>

* Added altimeter sensor inspector

Signed-off-by: Nate Koenig <[email protected]>

* Added magnetometer inspector

Signed-off-by: Nate Koenig <[email protected]>

* Fix lint

Signed-off-by: Michael Carroll <[email protected]>

* Update sensor icon

Signed-off-by: Nate Koenig <[email protected]>

* Move AirPressure functions out of ComponentInspector (#1179)

Signed-off-by: Louise Poubel <[email protected]>

* Fix get decimals, and address comments

Signed-off-by: Nate Koenig <[email protected]>

* cleanup and simplification

Signed-off-by: Nate Koenig <[email protected]>

* Require sdf 12.1.0

Signed-off-by: Nate Koenig <[email protected]>

* missign width

Signed-off-by: Nate Koenig <[email protected]>

* Added simulation state aware spin box

Signed-off-by: Nate Koenig <[email protected]>

* Merged

Signed-off-by: Nate Koenig <[email protected]>

* merged

Signed-off-by: Nate Koenig <[email protected]>

* Remove console output

Signed-off-by: Nate Koenig <[email protected]>

* alphabetize

Signed-off-by: Nate Koenig <[email protected]>

* Fix build

Signed-off-by: Nate Koenig <[email protected]>

* Add IMU component inspector

Signed-off-by: Nate Koenig <[email protected]>

* Added lidar component inspector

Signed-off-by: Nate Koenig <[email protected]>

* Fix codecheck

Signed-off-by: Nate Koenig <[email protected]>

Co-authored-by: Nate Koenig <[email protected]>
Co-authored-by: Michael Carroll <[email protected]>
Co-authored-by: Louise Poubel <[email protected]>
  • Loading branch information
4 people authored Nov 22, 2021
1 parent 5d7c95f commit 65cc189
Show file tree
Hide file tree
Showing 11 changed files with 1,005 additions and 7 deletions.
24 changes: 24 additions & 0 deletions examples/worlds/sensors.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -183,6 +183,30 @@
</z>
</magnetometer>
</sensor>
<sensor name="laser" type="gpu_ray">
<pose>0.43 0 0.26 0 0 0</pose>
<update_rate>20</update_rate>
<lidar>
<scan>
<horizontal>
<samples>720</samples>
<resolution>1</resolution>
<min_angle>-2.3562</min_angle>
<max_angle>2.3562</max_angle>
</horizontal>
</scan>
<range>
<min>0.04</min>
<max>5</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0</mean>
<stddev>0.01</stddev>
</noise>
</lidar>
</sensor>
</link>
</model>

Expand Down
48 changes: 48 additions & 0 deletions src/cmd/ModelCommandAPI.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
#include <sdf/Altimeter.hh>
#include <sdf/Camera.hh>
#include <sdf/Imu.hh>
#include <sdf/Lidar.hh>
#include <sdf/Magnetometer.hh>
#include <sdf/Noise.hh>
#include <sdf/Sensor.hh>
Expand All @@ -39,6 +40,7 @@
#include <ignition/gazebo/components/Altimeter.hh>
#include <ignition/gazebo/components/Camera.hh>
#include <ignition/gazebo/components/ChildLinkName.hh>
#include <ignition/gazebo/components/GpuLidar.hh>
#include <ignition/gazebo/components/Imu.hh>
#include <ignition/gazebo/components/Inertial.hh>
#include <ignition/gazebo/components/Joint.hh>
Expand Down Expand Up @@ -459,6 +461,51 @@ void printImu(const uint64_t _entity, const EntityComponentManager &_ecm,
<< "- Orientation enabled:" << imu->OrientationEnabled() << std::endl;
}

//////////////////////////////////////////////////
void printGpuLidar(const uint64_t _entity,
const EntityComponentManager &_ecm, int _spaces)
{
// Get the type and return if the _entity does not have the correct
// component.
auto comp = _ecm.Component<components::GpuLidar>(_entity);
if (!comp)
return;

const sdf::Sensor &sensor = comp->Data();
const sdf::Lidar *lidar = sensor.LidarSensor();

std::cout << std::string(_spaces, ' ') << "- Range:\n";
std::cout << std::string(_spaces+2, ' ') << "- Min: "
<< lidar->RangeMin() << std::endl;
std::cout << std::string(_spaces+2, ' ') << "- Max: "
<< lidar->RangeMax() << std::endl;
std::cout << std::string(_spaces+2, ' ') << "- Resolution: "
<< lidar->RangeResolution() << std::endl;

std::cout << std::string(_spaces, ' ') << "- Horizontal scan:\n";
std::cout << std::string(_spaces+2, ' ') << "- Samples: "
<< lidar->HorizontalScanSamples() << std::endl;
std::cout << std::string(_spaces+2, ' ') << "- Resolution: "
<< lidar->HorizontalScanResolution() << std::endl;
std::cout << std::string(_spaces+2, ' ') << "- Min angle: "
<< lidar->HorizontalScanMinAngle() << std::endl;
std::cout << std::string(_spaces+2, ' ') << "- Max angle: "
<< lidar->HorizontalScanMaxAngle() << std::endl;

std::cout << std::string(_spaces, ' ') << "- Vertical scan:\n";
std::cout << std::string(_spaces+2, ' ') << "- Samples: "
<< lidar->VerticalScanSamples() << std::endl;
std::cout << std::string(_spaces+2, ' ') << "- Resolution: "
<< lidar->VerticalScanResolution() << std::endl;
std::cout << std::string(_spaces+2, ' ') << "- Min angle: "
<< lidar->VerticalScanMinAngle() << std::endl;
std::cout << std::string(_spaces+2, ' ') << "- Max angle: "
<< lidar->VerticalScanMaxAngle() << std::endl;

std::cout << std::string(_spaces, ' ') << "- Noise:\n";
printNoise(lidar->LidarNoise(), _spaces + 2);
}

//////////////////////////////////////////////////
void printMagnetometer(const uint64_t _entity,
const EntityComponentManager &_ecm, int _spaces)
Expand Down Expand Up @@ -633,6 +680,7 @@ void printLinks(const uint64_t _modelEntity,
printAirPressure(sensor, _ecm, spaces + 2);
printAltimeter(sensor, _ecm, spaces + 2);
printCamera(sensor, _ecm, spaces + 2);
printGpuLidar(sensor, _ecm, spaces + 2);
printImu(sensor, _ecm, spaces + 2);
printMagnetometer(sensor, _ecm, spaces + 2);
printRgbdCamera(sensor, _ecm, spaces + 2);
Expand Down
2 changes: 2 additions & 0 deletions src/gui/plugins/component_inspector/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@ gz_add_gui_plugin(ComponentInspector
Altimeter.cc
ComponentInspector.cc
Imu.cc
Lidar.cc
Magnetometer.cc
ModelEditor.cc
Types.cc
Expand All @@ -12,6 +13,7 @@ gz_add_gui_plugin(ComponentInspector
Altimeter.hh
ComponentInspector.hh
Imu.hh
Lidar.hh
Magnetometer.hh
ModelEditor.hh
Types.hh
Expand Down
7 changes: 7 additions & 0 deletions src/gui/plugins/component_inspector/ComponentInspector.cc
Original file line number Diff line number Diff line change
Expand Up @@ -74,6 +74,7 @@
#include "Altimeter.hh"
#include "ComponentInspector.hh"
#include "Imu.hh"
#include "Lidar.hh"
#include "Magnetometer.hh"
#include "ModelEditor.hh"

Expand Down Expand Up @@ -126,6 +127,9 @@ namespace ignition::gazebo
/// \brief Imu inspector elements
public: std::unique_ptr<ignition::gazebo::Imu> imu;

/// \brief Lidar inspector elements
public: std::unique_ptr<ignition::gazebo::Lidar> lidar;

/// \brief Magnetometer inspector elements
public: std::unique_ptr<ignition::gazebo::Magnetometer> magnetometer;

Expand Down Expand Up @@ -451,6 +455,9 @@ void ComponentInspector::LoadConfig(const tinyxml2::XMLElement *)
// Create the imu
this->dataPtr->imu = std::make_unique<Imu>(this);

// Create the lidar
this->dataPtr->lidar = std::make_unique<Lidar>(this);

// Create the magnetometer
this->dataPtr->magnetometer = std::make_unique<Magnetometer>(this);
}
Expand Down
2 changes: 2 additions & 0 deletions src/gui/plugins/component_inspector/ComponentInspector.qrc
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,8 @@
<file>ComponentInspector.qml</file>
<file>ExpandingTypeHeader.qml</file>
<file>Imu.qml</file>
<file>Lidar.qml</file>
<file>LidarScan.qml</file>
<file>Light.qml</file>
<file>Magnetometer.qml</file>
<file>NoData.qml</file>
Expand Down
153 changes: 153 additions & 0 deletions src/gui/plugins/component_inspector/Lidar.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,153 @@
/*
* 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.
*
*/
#include <sdf/Lidar.hh>

#include <ignition/common/Console.hh>
#include <ignition/gazebo/components/GpuLidar.hh>
#include <ignition/gazebo/EntityComponentManager.hh>

#include "ComponentInspector.hh"
#include "Lidar.hh"
#include "Types.hh"

using namespace ignition;
using namespace gazebo;

/////////////////////////////////////////////////
Lidar::Lidar(ComponentInspector *_inspector)
{
_inspector->Context()->setContextProperty("LidarImpl", this);
this->inspector = _inspector;

ComponentCreator creator =
[=](EntityComponentManager &_ecm, Entity _entity, QStandardItem *_item)
{
auto comp = _ecm.Component<components::GpuLidar>(_entity);
if (nullptr == _item || nullptr == comp)
return;
const sdf::Lidar *lidar = comp->Data().LidarSensor();

_item->setData(QString("Lidar"),
ComponentsModel::RoleNames().key("dataType"));
_item->setData(QList({
QVariant(lidar->LidarNoise().Mean()),
QVariant(lidar->LidarNoise().BiasMean()),
QVariant(lidar->LidarNoise().StdDev()),
QVariant(lidar->LidarNoise().BiasStdDev()),
QVariant(lidar->LidarNoise().DynamicBiasStdDev()),
QVariant(lidar->LidarNoise().DynamicBiasCorrelationTime()),

QVariant(lidar->HorizontalScanSamples()),
QVariant(lidar->HorizontalScanResolution()),
QVariant(lidar->HorizontalScanMinAngle().Radian()),
QVariant(lidar->HorizontalScanMaxAngle().Radian()),

QVariant(lidar->VerticalScanSamples()),
QVariant(lidar->VerticalScanResolution()),
QVariant(lidar->VerticalScanMinAngle().Radian()),
QVariant(lidar->VerticalScanMaxAngle().Radian()),

QVariant(lidar->RangeMin()),
QVariant(lidar->RangeMax()),
QVariant(lidar->RangeResolution()),

}), ComponentsModel::RoleNames().key("data"));
};

this->inspector->RegisterComponentCreator(
components::GpuLidar::typeId, creator);
}

/////////////////////////////////////////////////
Q_INVOKABLE void Lidar::OnLidarNoise(
double _mean, double _meanBias, double _stdDev,
double _stdDevBias, double _dynamicBiasStdDev,
double _dynamicBiasCorrelationTime)
{
ignition::gazebo::UpdateCallback cb =
[=](EntityComponentManager &_ecm)
{
auto comp = _ecm.Component<components::GpuLidar>(
this->inspector->Entity());
if (comp)
{
sdf::Lidar *lidar = comp->Data().LidarSensor();
if (lidar)
{
sdf::Noise noise = lidar->LidarNoise();

setNoise(noise, _mean, _meanBias, _stdDev, _stdDevBias,
_dynamicBiasStdDev, _dynamicBiasCorrelationTime);

lidar->SetLidarNoise(noise);
}
else
ignerr << "Unable to get the lidar noise data.\n";
}
else
{
ignerr << "Unable to get the lidar component.\n";
}
};
this->inspector->AddUpdateCallback(cb);
}

/////////////////////////////////////////////////
Q_INVOKABLE void Lidar::OnLidarChange(
double _rangeMin, double _rangeMax,
double _rangeResolution, double _horizontalScanSamples,
double _horizontalScanResolution,
double _horizontalScanMinAngle,
double _horizontalScanMaxAngle, double _verticalScanSamples,
double _verticalScanResolution, double _verticalScanMinAngle,
double _verticalScanMaxAngle)
{
ignition::gazebo::UpdateCallback cb =
[=](EntityComponentManager &_ecm)
{
auto comp = _ecm.Component<components::GpuLidar>(
this->inspector->Entity());
if (comp)
{
sdf::Lidar *lidar = comp->Data().LidarSensor();
if (lidar)
{
lidar->SetRangeMin(_rangeMin);
lidar->SetRangeMax(_rangeMax);
lidar->SetRangeResolution(_rangeResolution);

lidar->SetHorizontalScanSamples(_horizontalScanSamples);
lidar->SetHorizontalScanResolution(_horizontalScanResolution);
lidar->SetHorizontalScanMinAngle(_horizontalScanMinAngle);
lidar->SetHorizontalScanMaxAngle(_horizontalScanMaxAngle);

lidar->SetVerticalScanSamples(_verticalScanSamples);
lidar->SetVerticalScanResolution(_verticalScanResolution);
lidar->SetVerticalScanMinAngle(_verticalScanMinAngle);
lidar->SetVerticalScanMaxAngle(_verticalScanMaxAngle);
}
else
ignerr << "Unable to get the lidar data.\n";
}
else
{
ignerr << "Unable to get the lidar component.\n";
}
};
this->inspector->AddUpdateCallback(cb);
}

66 changes: 66 additions & 0 deletions src/gui/plugins/component_inspector/Lidar.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,66 @@
/*
* 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_GUI_COMPONENTINSPECTOR_LIDAR_HH_
#define IGNITION_GAZEBO_GUI_COMPONENTINSPECTOR_LIDAR_HH_

#include <ignition/gazebo/gui/GuiSystem.hh>

namespace ignition
{
namespace gazebo
{
class ComponentInspector;

/// \brief A class that handles Lidar sensor changes.
class Lidar : public QObject
{
Q_OBJECT

/// \brief Constructor
/// \param[in] _inspector The component inspector.
public: explicit Lidar(ComponentInspector *_inspector);

/// \brief This function is called when a user changes values in the
/// Lidar sensor's linear acceleration X noise values.
/// \param[in] _mean Mean value
/// \param[in] _meanBias Bias mean value
/// \param[in] _stdDev Standard deviation value
/// \param[in] _stdDevBias Bias standard deviation value
/// \param[in] _dynamicBiasStdDev Dynamic bias standard deviation value
/// \param[in] _dynamicBiasCorrelationTime Dynamic bias correlation time
/// value
public: Q_INVOKABLE void OnLidarNoise(
double _mean, double _meanBias, double _stdDev,
double _stdDevBias, double _dynamicBiasStdDev,
double _dynamicBiasCorrelationTime);

public: Q_INVOKABLE void OnLidarChange(
double _rangeMin, double _rangeMax,
double _rangeResolution, double _horizontalScanSamples,
double _horizontalScanResolution,
double _horizontalScanMinAngle,
double _horizontalScanMaxAngle, double _verticalScanSamples,
double _verticalScanResolution, double _verticalScanMinAngle,
double _verticalScanMaxAngle);

/// \brief Pointer to the component inspector. This is used to add
/// update callbacks that modify the ECM.
private: ComponentInspector *inspector{nullptr};
};
}
}
#endif
Loading

0 comments on commit 65cc189

Please sign in to comment.