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

Added reflectance output image for DepthCamera #2966

Open
wants to merge 18 commits into
base: gazebo11
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 12 commits
Commits
Show all changes
18 commits
Select commit Hold shift + click to select a range
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
12 changes: 12 additions & 0 deletions gazebo/rendering/DepthCamera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -659,6 +659,18 @@ const float* DepthCamera::DepthData() const
return this->dataPtr->depthBuffer;
}

//////////////////////////////////////////////////
bool DepthCamera::GetOutputReflectance() const
{
return this->dataPtr->outputReflectance;
}

//////////////////////////////////////////////////
const float* DepthCamera::ReflectanceData() const
{
return this->dataPtr->reflectanceBuffer;
}

//////////////////////////////////////////////////
void DepthCamera::SetDepthTarget(Ogre::RenderTarget *_target)
{
Expand Down
8 changes: 8 additions & 0 deletions gazebo/rendering/DepthCamera.hh
Original file line number Diff line number Diff line change
Expand Up @@ -92,6 +92,14 @@ namespace gazebo
/// \return The z-buffer as a float array
public: virtual const float *DepthData() const;

/// \brief Get whether reflectance has been generated.
/// \return True if reflectance is set to generate.
public: bool GetOutputReflectance() const;

/// \brief All things needed to get reflectance data
/// \return The reflectance buffer as a float array
Copy link
Member

Choose a reason for hiding this comment

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

can you clarify what the values in this array mean physically? does 0 mean nonreflective and 1 mean reflective?

I'm asking because you inverted the data in c776173

Copy link
Contributor

Choose a reason for hiding this comment

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

oh we should not invert the data on the sensors side. We should only update the visualization code. The gui visualization inverts the data when it detects that the underlying image has a FLOAT type:
https://github.com/osrf/gazebo/blob/gazebo11/gazebo/gui/viewers/ImageFrame.cc#L157-L167

The logic there was added for visualization of depth data, i.e. black pixels means far away while white means close to camera. However, now that the reflectance image output is also in FLOAT, we don't want the inversion to be applied to the reflectance image. I think there needs to be some way on the gui side to tell reflectance images from depth images so that the correct visualization is applied.

public: const float *ReflectanceData() const;

/// \brief Set the render target, which renders the depth data
/// \param[in] _target Pointer to the render target
public: virtual void SetDepthTarget(Ogre::RenderTarget *_target);
Expand Down
47 changes: 47 additions & 0 deletions gazebo/sensors/DepthCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -124,6 +124,20 @@ void DepthCameraSensor::Init()
gzerr << "No world name" << std::endl;
}

if (this->dataPtr->depthCamera->GetOutputReflectance())
{
ignition::transport::AdvertiseMessageOptions opts;
opts.SetMsgsPerSec(50);
Copy link
Member

Choose a reason for hiding this comment

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

should we use the Sensor::UpdateRate() instead of hard-coding to 50 Hz?

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 noticed that the other cameras are using a hard-coded 50Hz:

https://github.com/osrf/gazebo/blob/26b69a7cff29312164558d23344eb551a96508ba/gazebo/sensors/CameraSensor.cc#L110-L112

https://github.com/osrf/gazebo/blob/26b69a7cff29312164558d23344eb551a96508ba/gazebo/sensors/WideAngleCameraSensor.cc#L146-L148

When I tried changing the 50 to this->UpdateRate(), I get a broken topic because I think the update rate has not been set and still is the value 0.000.

I could change this and initialize the update rate before advertising the topic but I am unsure if this will cause problems to the other components on the depth camera.

Copy link
Member

Choose a reason for hiding this comment

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

gazebo::transport::Node::Advertise has two optional numeric parameters, first the queue size and then the rate of publishing in Hz. In these examples from CameraSensor and WideAngleCameraSensor, 50 is actually the queue size. In the ignition::transport code (that has now been removed) it was a bit more clear that SetMsgsPerSec was about the rate of publishing

I think no additional changes are needed to the queue size


this->dataPtr->imageReflectancePub =
this->node->Advertise<msgs::ImageStamped>(
this->Topic() + "_reflectance", 50);

this->dataPtr->imageReflectancePubIgn =
WilliamLewww marked this conversation as resolved.
Show resolved Hide resolved
this->nodeIgn.Advertise<ignition::msgs::Image>(
this->TopicIgn() + "_reflectance", opts);
}

// Disable clouds and moon on server side until fixed and also to improve
// performance
this->scene->SetSkyXMode(rendering::Scene::GZ_SKYX_ALL &
Expand Down Expand Up @@ -188,6 +202,39 @@ bool DepthCameraSensor::UpdateImpl(const bool /*_force*/)
this->imagePub->Publish(msg);
}

if (this->dataPtr->imageReflectancePub &&
this->dataPtr->imageReflectancePub->HasConnections() &&
// check if reflectance data is available.
this->dataPtr->depthCamera->ReflectanceData())
{
msgs::ImageStamped msg;
msgs::Set(msg.mutable_time(), this->scene->SimTime());
msg.mutable_image()->set_width(this->camera->ImageWidth());
msg.mutable_image()->set_height(this->camera->ImageHeight());
msg.mutable_image()->set_pixel_format(common::Image::R_FLOAT32);

WilliamLewww marked this conversation as resolved.
Show resolved Hide resolved
msg.mutable_image()->set_step(this->camera->ImageWidth() *
this->camera->ImageDepth());

unsigned int reflectanceSamples =
msg.image().width() * msg.image().height();

float f;
// cppchecker recommends using sizeof(varname)
unsigned int reflectanceBufferSize = reflectanceSamples * sizeof(f);

if (!this->dataPtr->reflectanceBuffer)
this->dataPtr->reflectanceBuffer = new float[reflectanceSamples];

memcpy(this->dataPtr->reflectanceBuffer,
this->dataPtr->depthCamera->ReflectanceData(), reflectanceBufferSize);

msg.mutable_image()->set_data(this->dataPtr->reflectanceBuffer,
reflectanceBufferSize);

this->dataPtr->imageReflectancePub->Publish(msg);
}

this->SetRendered(false);
IGN_PROFILE_END();
return true;
Expand Down
9 changes: 9 additions & 0 deletions gazebo/sensors/DepthCameraSensorPrivate.hh
Original file line number Diff line number Diff line change
Expand Up @@ -30,8 +30,17 @@ namespace gazebo
/// \brief Depth data buffer.
public: float *depthBuffer = nullptr;

/// \brief Reflectance data buffer.
public: float *reflectanceBuffer = nullptr;

/// \brief Local pointer to the depthCamera.
public: rendering::DepthCameraPtr depthCamera;

/// \brief Publisher of reflectance image messages.
public: transport::PublisherPtr imageReflectancePub;

/// \brief Publisher of reflectance image messages.
public: ignition::transport::Node::Publisher imageReflectancePubIgn;
};
}
}
Expand Down
Loading