/* * Copyright (C) 2012-2015 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. * */ #ifdef _WIN32 // Ensure that Winsock2.h is included before Windows.h, which can get // pulled in by anybody (e.g., Boost). #include #endif #include #include #include "gazebo/physics/World.hh" #include "gazebo/common/Events.hh" #include "gazebo/common/Exception.hh" #include "gazebo/transport/transport.hh" #include "gazebo/rendering/DepthCamera.hh" #include "gazebo/rendering/Scene.hh" #include "gazebo/rendering/RenderingIface.hh" #include "gazebo/rendering/RenderEngine.hh" #include "gazebo/sensors/SensorFactory.hh" #include "gazebo/sensors/DepthCameraSensor.hh" #include "gazebo/sensors/Noise.hh" using namespace gazebo; using namespace sensors; // TODO: // 1) Handle new image formats (override getImageFormat) in DepthCamera.cc // 2) Return correct depths for the sensor (override getImageDepth) in DepthCamera.cc // 3) New saveFrame function that saves the correct depth data - look at saveframebuffer stuff that camera.cc has GZ_REGISTER_STATIC_SENSOR("depth", DepthCameraSensor) ////////////////////////////////////////////////// DepthCameraSensor::DepthCameraSensor() : Sensor(sensors::IMAGE) { this->rendered = false; this->connections.push_back( event::Events::ConnectRender( boost::bind(&DepthCameraSensor::Render, this))); } ////////////////////////////////////////////////// DepthCameraSensor::~DepthCameraSensor() { } ////////////////////////////////////////////////// void DepthCameraSensor::Load(const std::string &_worldName, sdf::ElementPtr _sdf) { Sensor::Load(_worldName, _sdf); } ////////////////////////////////////////////////// std::string DepthCameraSensor::GetTopic() const { std::string topicName = "~/"; topicName += this->parentName + "/" + this->GetName() + "/image"; boost::replace_all(topicName, "::", "/"); return topicName; } ////////////////////////////////////////////////// void DepthCameraSensor::Load(const std::string &_worldName) { Sensor::Load(_worldName); this->imagePub = this->node->Advertise( this->GetTopic(), 50); } ////////////////////////////////////////////////// void DepthCameraSensor::Init() { if (rendering::RenderEngine::Instance()->GetRenderPathType() == rendering::RenderEngine::NONE) { gzerr << "Unable to create DepthCameraSensor. Rendering is disabled.\n"; return; } std::string worldName = this->world->GetName(); if (!worldName.empty()) { this->scene = rendering::get_scene(worldName); if (!this->scene) { this->scene = rendering::create_scene(worldName, false, true); // This usually means rendering is not available if (!this->scene) { gzerr << "Unable to create DepthCameraSensor.\n"; return; } } this->camera = this->scene->CreateDepthCamera( this->sdf->Get("name"), false); if (!this->camera) { gzerr << "Unable to create depth camera sensor\n"; return; } this->camera->SetCaptureData(true); sdf::ElementPtr cameraSdf = this->sdf->GetElement("camera"); this->camera->Load(cameraSdf); // Do some sanity checks if (this->camera->GetImageWidth() == 0 || this->camera->GetImageHeight() == 0) { gzthrow("image has zero size"); } this->camera->Init(); this->camera->CreateRenderTexture(this->GetName() + "_RttTex_Image"); this->camera->CreateDepthTexture(this->GetName() + "_RttTex_Depth"); ignition::math::Pose3d cameraPose = this->pose; if (cameraSdf->HasElement("pose")) cameraPose = cameraSdf->Get("pose") + cameraPose; this->camera->SetWorldPose(cameraPose); this->camera->AttachToVisual(this->parentId, true); if (cameraSdf->HasElement("noise")) { this->noises[CAMERA_NOISE] = NoiseFactory::NewNoiseModel(cameraSdf->GetElement("noise"), this->GetType()); this->noises[CAMERA_NOISE]->SetCamera(this->camera); } } else gzerr << "No world name\n"; // Disable clouds and moon on server side until fixed and also to improve // performance this->scene->SetSkyXMode(rendering::Scene::GZ_SKYX_ALL & ~rendering::Scene::GZ_SKYX_CLOUDS & ~rendering::Scene::GZ_SKYX_MOON); Sensor::Init(); } ////////////////////////////////////////////////// void DepthCameraSensor::Fini() { this->imagePub.reset(); Sensor::Fini(); if (this->camera) { this->scene->RemoveCamera(this->camera->GetName()); } this->camera.reset(); this->scene.reset(); } ////////////////////////////////////////////////// void DepthCameraSensor::SetActive(bool value) { Sensor::SetActive(value); } ////////////////////////////////////////////////// void DepthCameraSensor::Render() { if (!this->camera || !this->IsActive() || !this->NeedsUpdate()) return; this->camera->Render(); this->rendered = true; this->lastMeasurementTime = this->scene->GetSimTime(); } ////////////////////////////////////////////////// bool DepthCameraSensor::UpdateImpl(bool /*_force*/) { // Sensor::Update(force); if (!this->rendered) return false; this->camera->PostRender(); // TODO: Is this correct?? if (this->imagePub && this->imagePub->HasConnections()) { msgs::ImageStamped msg; msgs::Set(msg.mutable_time(), this->scene->GetSimTime()); msg.mutable_image()->set_width(this->camera->GetImageWidth()); msg.mutable_image()->set_height(this->camera->GetImageHeight()); msg.mutable_image()->set_pixel_format(gazebo::common::Image::PixelFormat::R_FLOAT32); // Depth format - Float (from Carlos Aguero) msg.mutable_image()->set_step(this->camera->GetImageWidth() * 4); // ImageDepth = 4 bytes (float) msg.mutable_image()->set_data(this->camera->GetDepthData(), msg.image().width() * 4 * msg.image().height()); // NOTE: We need to get the depth data, not image data! ImageDepth = 4 bytes (float) this->imagePub->Publish(msg); } this->rendered = false; return true; } ////////////////////////////////////////////////// unsigned int DepthCameraSensor::GetImageWidth() const { if (this->camera) return this->camera->GetImageWidth(); return 0; } ////////////////////////////////////////////////// unsigned int DepthCameraSensor::GetImageHeight() const { if (this->camera) return this->camera->GetImageHeight(); return 0; } ////////////////////////////////////////////////// const float *DepthCameraSensor::GetDepthData() { return this->camera->GetDepthData(); } ////////////////////////////////////////////////// // TODO: SaveFrame reverts to the RGB camera's saveFrame function which takes an unsigned char array // and limited image formats (R_FLOAT32 not included) and tries to save it. // We need to write a separate one for DepthCamera bool DepthCameraSensor::SaveFrame(const std::string &_filename) { this->SetActive(true); return this->camera->SaveFrame(_filename); } ////////////////////////////////////////////////// bool DepthCameraSensor::IsActive() { return Sensor::IsActive() || (this->imagePub && this->imagePub->HasConnections()); }