-
Notifications
You must be signed in to change notification settings - Fork 488
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
base: gazebo11
Are you sure you want to change the base?
Changes from 12 commits
03b65b5
6733e9b
2c41445
8e4decc
a28d71c
a29747c
dcd579f
499b47e
f3ad4c9
e51d311
5d3646e
e30dc2b
ca05d96
c776173
0106de6
c9d9b3e
b3f1fe4
87ec97f
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -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); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. should we use the There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I noticed that the other cameras are using a hard-coded 50Hz: When I tried changing the 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. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
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 & | ||
|
@@ -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; | ||
|
There was a problem hiding this comment.
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
There was a problem hiding this comment.
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.