Skip to content

Commit

Permalink
Merge branch 'ign-sensors3' into 3_to_4_20210208
Browse files Browse the repository at this point in the history
  • Loading branch information
Nate Koenig committed Feb 8, 2021
2 parents 6532bfc + 818b388 commit dcc7b85
Show file tree
Hide file tree
Showing 3 changed files with 34 additions and 13 deletions.
5 changes: 5 additions & 0 deletions include/ignition/sensors/Lidar.hh
Original file line number Diff line number Diff line change
Expand Up @@ -72,6 +72,11 @@ namespace ignition
public: virtual bool IGN_DEPRECATED(4) PublishLidarScan(
const ignition::common::Time &_now);

/// \brief Apply noise to the laser buffer, if noise has been
/// configured. This should be called before PublishLidarScan if you
/// want the scan data to contain noise.
public: void ApplyNoise();

/// \brief Publish LaserScan message
/// \param[in] _now The current time
/// \return true if the update was successfull
Expand Down
14 changes: 9 additions & 5 deletions src/GpuLidarSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,8 @@ using namespace ignition::sensors;
class ignition::sensors::GpuLidarSensorPrivate
{
/// \brief Fill the point cloud packed message
public: void FillPointCloudMsg();
/// \param[in] _laserBuffer Lidar data buffer.
public: void FillPointCloudMsg(const float *_laserBuffer);

/// \brief Rendering camera
public: ignition::rendering::GpuRaysPtr gpuRays;
Expand Down Expand Up @@ -248,6 +249,9 @@ bool GpuLidarSensor::Update(const std::chrono::steady_clock::duration &_now)
/// \todo(anyone) It would be nice to remove this copy.
this->dataPtr->gpuRays->Copy(this->laserBuffer);

// Apply noise before publishing the data.
this->ApplyNoise();

this->PublishLidarScan(_now);

if (this->dataPtr->pointPub.HasConnections())
Expand All @@ -257,7 +261,7 @@ bool GpuLidarSensor::Update(const std::chrono::steady_clock::duration &_now)
msgs::Convert(_now);
this->dataPtr->pointMsg.set_is_dense(true);

this->dataPtr->FillPointCloudMsg();
this->dataPtr->FillPointCloudMsg(this->laserBuffer);

{
this->AddSequence(this->dataPtr->pointMsg.mutable_header());
Expand Down Expand Up @@ -302,7 +306,7 @@ ignition::math::Angle GpuLidarSensor::VFOV() const
}

//////////////////////////////////////////////////
void GpuLidarSensorPrivate::FillPointCloudMsg()
void GpuLidarSensorPrivate::FillPointCloudMsg(const float *_laserBuffer)
{
IGN_PROFILE("GpuLidarSensorPrivate::FillPointCloudMsg");
uint32_t width = this->pointMsg.width();
Expand Down Expand Up @@ -335,8 +339,8 @@ void GpuLidarSensorPrivate::FillPointCloudMsg()
{
// Index of current point, and the depth value at that point
auto index = j * width * channels + i * channels;
float depth = this->gpuRays->Data()[index];
float intensity = this->gpuRays->Data()[index + 1];
float depth = _laserBuffer[index];
float intensity = _laserBuffer[index + 1];
uint16_t ring = j;

int fieldIndex = 0;
Expand Down
28 changes: 20 additions & 8 deletions src/Lidar.cc
Original file line number Diff line number Diff line change
Expand Up @@ -199,6 +199,26 @@ bool Lidar::Update(const std::chrono::steady_clock::duration &/*_now*/)
return false;
}

//////////////////////////////////////////////////
void Lidar::ApplyNoise()
{
if (this->dataPtr->noises.find(LIDAR_NOISE) != this->dataPtr->noises.end())
{
for (unsigned int j = 0; j < this->VerticalRayCount(); ++j)
{
for (unsigned int i = 0; i < this->RayCount(); ++i)
{
int index = j * this->RayCount() + i;
double range = this->laserBuffer[index*3];
range = this->dataPtr->noises[LIDAR_NOISE]->Apply(range);
range = ignition::math::clamp(range,
this->RangeMin(), this->RangeMax());
this->laserBuffer[index*3] = range;
}
}
}
}

//////////////////////////////////////////////////
bool Lidar::PublishLidarScan(const ignition::common::Time &_now)
{
Expand Down Expand Up @@ -247,14 +267,6 @@ bool Lidar::PublishLidarScan(const std::chrono::steady_clock::duration &_now)
int index = j * this->RangeCount() + i;
double range = this->laserBuffer[index*3];

if (this->dataPtr->noises.find(LIDAR_NOISE) !=
this->dataPtr->noises.end())
{
range = this->dataPtr->noises[LIDAR_NOISE]->Apply(range);
range = ignition::math::clamp(range,
this->RangeMin(), this->RangeMax());
}

range = ignition::math::isnan(range) ? this->RangeMax() : range;
this->dataPtr->laserMsg.set_ranges(index, range);
this->dataPtr->laserMsg.set_intensities(index,
Expand Down

0 comments on commit dcc7b85

Please sign in to comment.