$search
00001 /* 00002 * Gazebo - Outdoor Multi-Robot Simulator 00003 * Copyright (C) 2003 00004 * Nate Koenig & Andrew Howard 00005 * 00006 * This program is free software; you can redistribute it and/or modify 00007 * it under the terms of the GNU General Public License as published by 00008 * the Free Software Foundation; either version 2 of the License, or 00009 * (at your option) any later version. 00010 * 00011 * This program is distributed in the hope that it will be useful, 00012 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00013 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00014 * GNU General Public License for more details. 00015 * 00016 * You should have received a copy of the GNU General Public License 00017 * along with this program; if not, write to the Free Software 00018 * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA 00019 * 00020 */ 00021 /* 00022 @mainpage 00023 Desc: GazeboRosCamera plugin for simulating cameras in Gazebo 00024 Author: John Hsu 00025 Date: 24 Sept 2008 00026 SVN info: $Id$ 00027 @htmlinclude manifest.html 00028 @b GazeboRosCamera plugin broadcasts ROS Image messages 00029 */ 00030 00031 #include <algorithm> 00032 #include <assert.h> 00033 #include <boost/thread/thread.hpp> 00034 #include <boost/bind.hpp> 00035 00036 #include <gazebo_plugins/gazebo_ros_camera.h> 00037 00038 #include <gazebo/Timer.hh> 00039 #include <gazebo/Sensor.hh> 00040 #include <gazebo/Model.hh> 00041 #include <gazebo/Global.hh> 00042 #include <gazebo/XMLConfig.hh> 00043 #include <gazebo/Simulator.hh> 00044 #include <gazebo/gazebo.h> 00045 #include <gazebo/GazeboError.hh> 00046 #include <gazebo/ControllerFactory.hh> 00047 #include <gazebo/MonoCameraSensor.hh> 00048 #include <gazebo/Pose3d.hh> 00049 00050 00051 #include "sensor_msgs/Image.h" 00052 #include "sensor_msgs/fill_image.h" 00053 #include "image_transport/image_transport.h" 00054 00055 #include <geometry_msgs/Point32.h> 00056 #include <sensor_msgs/ChannelFloat32.h> 00057 00058 namespace gazebo 00059 { 00060 00061 GZ_REGISTER_DYNAMIC_CONTROLLER("gazebo_ros_camera", GazeboRosCamera); 00062 00064 // Constructor 00065 GazeboRosCamera::GazeboRosCamera(Entity *parent) 00066 : Controller(parent) 00067 { 00068 this->myParent = dynamic_cast<MonoCameraSensor*>(this->parent); 00069 00070 if (!this->myParent) 00071 gzthrow("GazeboRosCamera controller requires a Camera Sensor as its parent"); 00072 00073 Param::Begin(&this->parameters); 00074 this->robotNamespaceP = new ParamT<std::string>("robotNamespace","/",0); 00075 this->imageTopicNameP = new ParamT<std::string>("imageTopicName","image_raw", 0); 00076 this->cameraInfoTopicNameP = new ParamT<std::string>("cameraInfoTopicName","camera_info", 0); 00077 this->pointCloudTopicNameP = new ParamT<std::string>("pointCloudTopicName","points", 0); 00078 this->cameraNameP = new ParamT<std::string>("cameraName","", 0); 00079 this->frameNameP = new ParamT<std::string>("frameName","generic_camera_link", 0); 00080 // camera parameters 00081 this->CxPrimeP = new ParamT<double>("CxPrime",0, 0); // default to 0 for compute on the fly 00082 this->CxP = new ParamT<double>("Cx" ,0, 0); // default to 0 for compute on the fly 00083 this->CyP = new ParamT<double>("Cy" ,0, 0); // default to 0 for compute on the fly 00084 this->focal_lengthP = new ParamT<double>("focal_length" ,0, 0); // == image_width(px) / (2*tan( hfov(radian) /2)), default to 0 for compute on the fly 00085 this->hack_baselineP = new ParamT<double>("hackBaseline" ,0, 0); // hack for right stereo camera 00086 this->pointCloudCutoffP = new ParamT<double>("pointCloudCutoff" ,0.4, 0); 00087 this->distortion_k1P = new ParamT<double>("distortion_k1" ,0, 0); 00088 this->distortion_k2P = new ParamT<double>("distortion_k2" ,0, 0); 00089 this->distortion_k3P = new ParamT<double>("distortion_k3" ,0, 0); 00090 this->distortion_t1P = new ParamT<double>("distortion_t1" ,0, 0); 00091 this->distortion_t2P = new ParamT<double>("distortion_t2" ,0, 0); 00092 Param::End(); 00093 00094 this->imageConnectCount = 0; 00095 this->infoConnectCount = 0; 00096 this->pointCloudConnectCount = 0; 00097 00098 last_image_pub_time_ = Time(0); 00099 last_camera_info_pub_time_ = Time(0); 00100 last_point_cloud_pub_time_ = Time(0); 00101 00102 // set sensor update rate to controller update rate? 00103 //(dynamic_cast<OgreCamera*>(this->myParent))->SetUpdateRate(this->updateRateP->GetValue()); 00104 } 00105 00106 void GazeboRosCamera::configCallback(gazebo_plugins::GazeboRosCameraConfig &config, uint32_t level) 00107 { 00108 ROS_INFO("Reconfigure request for the gazebo ros camera: %s. New rate: %.2f", this->cameraName.c_str(), config.imager_rate); 00109 00110 (dynamic_cast<OgreCamera*>(this->myParent))->SetUpdateRate(config.imager_rate); 00111 } 00112 00114 // Destructor 00115 GazeboRosCamera::~GazeboRosCamera() 00116 { 00117 delete this->robotNamespaceP; 00118 delete this->rosnode_; 00119 delete this->managernode_; 00120 delete this->manager_; 00121 delete this->imageTopicNameP; 00122 delete this->cameraInfoTopicNameP; 00123 delete this->pointCloudTopicNameP; 00124 delete this->frameNameP; 00125 delete this->CxPrimeP; 00126 delete this->CxP; 00127 delete this->CyP; 00128 delete this->focal_lengthP; 00129 delete this->hack_baselineP; 00130 delete this->pointCloudCutoffP; 00131 delete this->distortion_k1P; 00132 delete this->distortion_k2P; 00133 delete this->distortion_k3P; 00134 delete this->distortion_t1P; 00135 delete this->distortion_t2P; 00136 } 00137 00139 // Load the controller 00140 void GazeboRosCamera::LoadChild(XMLConfigNode *node) 00141 { 00142 this->robotNamespaceP->Load(node); 00143 this->robotNamespace = this->robotNamespaceP->GetValue(); 00144 if (!ros::isInitialized()) 00145 { 00146 int argc = 0; 00147 char** argv = NULL; 00148 ros::init(argc,argv,"gazebo",ros::init_options::NoSigintHandler|ros::init_options::AnonymousName); 00149 } 00150 00151 this->imageTopicNameP->Load(node); 00152 this->cameraInfoTopicNameP->Load(node); 00153 this->pointCloudTopicNameP->Load(node); 00154 this->cameraNameP->Load(node); 00155 this->frameNameP->Load(node); 00156 this->CxPrimeP->Load(node); 00157 this->CxP->Load(node); 00158 this->CyP->Load(node); 00159 this->focal_lengthP->Load(node); 00160 this->hack_baselineP->Load(node); 00161 this->pointCloudCutoffP->Load(node); 00162 this->distortion_k1P->Load(node); 00163 this->distortion_k2P->Load(node); 00164 this->distortion_k3P->Load(node); 00165 this->distortion_t1P->Load(node); 00166 this->distortion_t2P->Load(node); 00167 this->imageTopicName = this->imageTopicNameP->GetValue(); 00168 this->cameraInfoTopicName = this->cameraInfoTopicNameP->GetValue(); 00169 this->pointCloudTopicName = this->pointCloudTopicNameP->GetValue(); 00170 this->frameName = this->frameNameP->GetValue(); 00171 this->CxPrime = this->CxPrimeP->GetValue(); 00172 this->Cx = this->CxP->GetValue(); 00173 this->Cy = this->CyP->GetValue(); 00174 this->focal_length = this->focal_lengthP->GetValue(); 00175 this->hack_baseline = this->hack_baselineP->GetValue(); 00176 this->pointCloudCutoff = this->pointCloudCutoffP->GetValue(); 00177 this->distortion_k1 = this->distortion_k1P->GetValue(); 00178 this->distortion_k2 = this->distortion_k2P->GetValue(); 00179 this->distortion_k3 = this->distortion_k3P->GetValue(); 00180 this->distortion_t1 = this->distortion_t1P->GetValue(); 00181 this->distortion_t2 = this->distortion_t2P->GetValue(); 00182 if ((this->distortion_k1 != 0.0) || (this->distortion_k2 != 0.0) || 00183 (this->distortion_k3 != 0.0) || (this->distortion_t1 != 0.0) || 00184 (this->distortion_t2 != 0.0)) 00185 ROS_WARN("gazebo_ros_camera simulation does not support non-zero distortion parameters right now, your simulation maybe wrong."); 00186 00187 this->cameraName = this->cameraNameP->GetValue(); 00188 this->rosnode_ = new ros::NodeHandle(this->robotNamespace+"/"+this->cameraName); 00189 if (!this->cameraName.empty()) 00190 this->managernode_ = new ros::NodeHandle(this->robotNamespace+"/"+this->cameraName+"_manager"); 00191 else 00192 this->managernode_ = new ros::NodeHandle(this->robotNamespace+"/"+this->GetName()+"_manager"); 00193 this->manager_ = new nodelet::Loader(*this->managernode_); 00194 this->itnode_ = new image_transport::ImageTransport(*this->rosnode_); 00195 00196 if (!this->cameraName.empty()) { 00197 dyn_srv_ = new dynamic_reconfigure::Server<gazebo_plugins::GazeboRosCameraConfig>(*this->rosnode_); 00198 dynamic_reconfigure::Server<gazebo_plugins::GazeboRosCameraConfig>::CallbackType f = boost::bind(&GazeboRosCamera::configCallback, this, _1, _2); 00199 dyn_srv_->setCallback(f); 00200 } 00201 00202 00203 #ifdef USE_CBQ 00204 this->image_pub_ = this->itnode_->advertise( 00205 this->imageTopicName,1, 00206 boost::bind( &GazeboRosCamera::ImageConnect,this), 00207 boost::bind( &GazeboRosCamera::ImageDisconnect,this), ros::VoidPtr(), &this->camera_queue_); 00208 00209 ros::AdvertiseOptions camera_info_ao = ros::AdvertiseOptions::create<sensor_msgs::CameraInfo>( 00210 this->cameraInfoTopicName,1, 00211 boost::bind( &GazeboRosCamera::InfoConnect,this), 00212 boost::bind( &GazeboRosCamera::InfoDisconnect,this), ros::VoidPtr(), &this->camera_queue_); 00213 this->camera_info_pub_ = this->rosnode_->advertise(camera_info_ao); 00214 00215 ros::SubscribeOptions zoom_so = ros::SubscribeOptions::create<std_msgs::Float64>( 00216 "set_hfov",1, 00217 boost::bind( &GazeboRosCamera::SetHFOV,this,_1), 00218 ros::VoidPtr(), &this->camera_queue_); 00219 this->cameraHFOVSubscriber_ = this->rosnode_->subscribe(zoom_so); 00220 00221 ros::SubscribeOptions rate_so = ros::SubscribeOptions::create<std_msgs::Float64>( 00222 "set_update_rate",1, 00223 boost::bind( &GazeboRosCamera::SetUpdateRate,this,_1), 00224 ros::VoidPtr(), &this->camera_queue_); 00225 this->cameraUpdateRateSubscriber_ = this->rosnode_->subscribe(rate_so); 00226 00227 ros::AdvertiseOptions point_cloud_ao = ros::AdvertiseOptions::create<pcl::PointCloud<pcl::PointXYZ> >( 00228 this->pointCloudTopicName,1, 00229 boost::bind( &GazeboRosCamera::PointCloudConnect,this), 00230 boost::bind( &GazeboRosCamera::PointCloudDisconnect,this), ros::VoidPtr(), &this->camera_queue_); 00231 this->point_cloud_pub_ = this->rosnode_->advertise(point_cloud_ao); 00232 00233 #else 00234 this->image_pub_ = this->rosnode_->advertise<sensor_msgs::Image>(this->imageTopicName,1, 00235 boost::bind( &GazeboRosCamera::ImageConnect, this), 00236 boost::bind( &GazeboRosCamera::ImageDisconnect, this)); 00237 this->camera_info_pub_ = this->rosnode_->advertise<sensor_msgs::CameraInfo>(this->cameraInfoTopicName,1, 00238 boost::bind( &GazeboRosCamera::InfoConnect, this), 00239 boost::bind( &GazeboRosCamera::InfoDisconnect, this)); 00240 this->point_cloud_pub_ = this->rosnode_->advertise<pcl::PointCloud<pcl::PointXYZ> >(this->pointCloudTopicName,1, 00241 boost::bind( &GazeboRosCamera::PointCloudConnect, this), 00242 boost::bind( &GazeboRosCamera::PointCloudDisconnect, this)); 00243 #endif 00244 } 00245 00247 // Increment count 00248 void GazeboRosCamera::InfoConnect() 00249 { 00250 this->infoConnectCount++; 00251 } 00253 // Decrement count 00254 void GazeboRosCamera::InfoDisconnect() 00255 { 00256 this->infoConnectCount--; 00257 } 00258 00260 // Set Horizontal Field of View 00261 void GazeboRosCamera::SetHFOV(const std_msgs::Float64::ConstPtr& hfov) 00262 { 00263 (dynamic_cast<OgreCamera*>(this->myParent))->SetFOV(hfov->data); 00264 } 00265 00267 // Set Update Rate 00268 void GazeboRosCamera::SetUpdateRate(const std_msgs::Float64::ConstPtr& update_rate) 00269 { 00270 (dynamic_cast<OgreCamera*>(this->myParent))->SetUpdateRate(update_rate->data); 00271 } 00272 00274 // Increment count 00275 void GazeboRosCamera::ImageConnect() 00276 { 00277 this->imageConnectCount++; 00278 this->myParent->SetActive(true); 00279 } 00281 // Decrement count 00282 void GazeboRosCamera::ImageDisconnect() 00283 { 00284 this->imageConnectCount--; 00285 00286 if (this->pointCloudConnectCount == 0) 00287 { 00288 this->myParent->SimulateDepthData(false); 00289 if (this->imageConnectCount == 0) 00290 this->myParent->SetActive(false); 00291 } 00292 } 00293 00295 // Increment count 00296 void GazeboRosCamera::PointCloudConnect() 00297 { 00298 this->pointCloudConnectCount++; 00299 this->myParent->SetActive(true); 00300 this->myParent->SimulateDepthData(true); 00301 } 00303 // Decrement count 00304 void GazeboRosCamera::PointCloudDisconnect() 00305 { 00306 this->pointCloudConnectCount--; 00307 00308 if (this->pointCloudConnectCount == 0) 00309 { 00310 this->myParent->SimulateDepthData(false); 00311 if (this->imageConnectCount == 0) 00312 this->myParent->SetActive(false); 00313 } 00314 } 00315 00317 // Initialize the controller 00318 void GazeboRosCamera::InitChild() 00319 { 00320 // sensor generation off by default 00321 this->myParent->SetActive(false); 00322 this->myParent->SimulateDepthData(false); 00323 00324 // set buffer size 00325 this->width = this->myParent->GetImageWidth(); 00326 this->height = this->myParent->GetImageHeight(); 00327 this->depth = this->myParent->GetImageDepth(); 00328 if (this->myParent->GetImageFormat() == "L8") 00329 { 00330 this->type = sensor_msgs::image_encodings::MONO8; 00331 this->skip = 1; 00332 } 00333 else if (this->myParent->GetImageFormat() == "R8G8B8") 00334 { 00335 this->type = sensor_msgs::image_encodings::RGB8; 00336 this->skip = 3; 00337 } 00338 else if (this->myParent->GetImageFormat() == "B8G8R8") 00339 { 00340 this->type = sensor_msgs::image_encodings::BGR8; 00341 this->skip = 3; 00342 } 00343 else if (this->myParent->GetImageFormat() == "BAYER_RGGB8") 00344 { 00345 ROS_WARN("bayer simulation maybe computationally expensive."); 00346 this->type = sensor_msgs::image_encodings::BAYER_RGGB8; 00347 this->skip = 1; 00348 } 00349 else if (this->myParent->GetImageFormat() == "BAYER_BGGR8") 00350 { 00351 ROS_WARN("bayer simulation maybe computationally expensive."); 00352 this->type = sensor_msgs::image_encodings::BAYER_BGGR8; 00353 this->skip = 1; 00354 } 00355 else if (this->myParent->GetImageFormat() == "BAYER_GBRG8") 00356 { 00357 ROS_WARN("bayer simulation maybe computationally expensive."); 00358 this->type = sensor_msgs::image_encodings::BAYER_GBRG8; 00359 this->skip = 1; 00360 } 00361 else if (this->myParent->GetImageFormat() == "BAYER_GRBG8") 00362 { 00363 ROS_WARN("bayer simulation maybe computationally expensive."); 00364 this->type = sensor_msgs::image_encodings::BAYER_GRBG8; 00365 this->skip = 1; 00366 } 00367 else 00368 { 00369 ROS_ERROR("Unsupported Gazebo ImageFormat\n"); 00370 this->type = sensor_msgs::image_encodings::BGR8; 00371 this->skip = 3; 00372 } 00373 00375 if (this->CxPrime == 0) 00376 this->CxPrime = ((double)this->width+1.0) /2.0; 00377 if (this->Cx == 0) 00378 this->Cx = ((double)this->width+1.0) /2.0; 00379 if (this->Cy == 0) 00380 this->Cy = ((double)this->height+1.0) /2.0; 00381 00382 00383 double computed_focal_length = ((double)this->width) / (2.0 *tan(this->myParent->GetHFOV().GetAsRadian()/2.0)); 00384 if (this->focal_length == 0) 00385 this->focal_length = computed_focal_length; 00386 else 00387 if (fabs(this->focal_length - computed_focal_length) > 1e-8) // check against float precision 00388 ROS_WARN("The <focal_length>[%f] you have provided for camera [%s] is inconsistent with specified image_width [%d] and HFOV [%f]. Please double check to see that focal_length = width / (2.0 * tan( HFOV/2.0 )), the explected focal_lengtth value is [%f], please update your camera model description accordingly.", 00389 this->focal_length,this->myParent->GetName().c_str(),this->width,this->myParent->GetHFOV().GetAsRadian(), 00390 computed_focal_length); 00391 00392 00393 #ifdef USE_CBQ 00394 // start custom queue for camera 00395 this->callback_queue_thread_ = boost::thread( boost::bind( &GazeboRosCamera::CameraQueueThread,this ) ); 00396 #endif 00397 00398 00399 } 00400 00402 // Update the controller 00403 void GazeboRosCamera::UpdateChild() 00404 { 00405 00406 // Only publish to ROS when the camera updates 00407 Time sensor_update_time = (dynamic_cast<OgreCamera*>(this->myParent))->GetLastRenderTime(); 00408 00409 // as long as ros is connected, parent is active 00410 if (this->myParent->IsActive()) 00411 { 00412 if (sensor_update_time > last_image_pub_time_) 00413 this->PutCameraData(); 00414 } 00415 00417 if (this->infoConnectCount > 0) //publish regardless camera image subscription 00418 this->PublishCameraInfo(); 00419 } 00420 00422 // Finalize the controller 00423 void GazeboRosCamera::FiniChild() 00424 { 00425 this->myParent->SetActive(false); 00426 this->manager_->clear(); 00427 this->managernode_->shutdown(); 00428 this->rosnode_->shutdown(); 00429 #ifdef USE_CBQ 00430 this->camera_queue_.clear(); 00431 this->camera_queue_.disable(); 00432 this->callback_queue_thread_.join(); 00433 #endif 00434 00435 } 00436 00438 // Put laser data to the interface 00439 void GazeboRosCamera::PutCameraData() 00440 { 00441 //ROS_ERROR("debug %d %s",this->imageConnectCount,this->GetName().c_str()); 00442 const unsigned char *src; 00443 const float* depths; 00444 00445 // Get a pointer to image data 00446 { 00447 // prevent parent from updating the image and the depth data while we are retrieving it 00448 boost::recursive_mutex::scoped_lock mr_lock(*Simulator::Instance()->GetMRMutex()); 00449 00450 //DIAGNOSTICTIMER(timer("gazebo_ros_camera: GetImageData",6)); 00451 src = this->myParent->GetImageData(0); 00452 if (src) 00453 { 00454 //double tmpT0 = Simulator::Instance()->GetWallTime(); 00455 00456 unsigned char dst[this->width*this->height]; 00457 00458 this->lock.lock(); 00459 // copy data into image 00460 this->imageMsg.header.frame_id = this->frameName; 00461 Time lastRenderTime = (dynamic_cast<OgreCamera*>(this->myParent))->GetLastRenderTime(); 00462 //Time lastRenderTime = Simulator::Instance()->GetSimTime(); 00463 //printf("name[%s] render[%f] vs. sim time[%f], diff[%f]\n",this->GetName().c_str(),lastRenderTime.Double(),Simulator::Instance()->GetSimTime().Double(),lastRenderTime.Double()-Simulator::Instance()->GetSimTime().Double()); 00464 //ROS_DEBUG("camera time %f %d %d",lastRenderTime.Double(),lastRenderTime.sec,lastRenderTime.nsec); 00465 this->imageMsg.header.stamp.sec = lastRenderTime.sec; 00466 this->imageMsg.header.stamp.nsec = lastRenderTime.nsec; 00467 00468 //double tmpT1 = Simulator::Instance()->GetWallTime(); 00469 //double tmpT2; 00470 00472 if (this->image_pub_.getNumSubscribers() > 0) 00473 { 00474 00475 //convertImageFormat(dst,src); 00476 00477 // copy from src to imageMsg 00478 fillImage(this->imageMsg, 00479 this->type, 00480 this->height, 00481 this->width, 00482 this->skip*this->width, 00483 (void*)src ); 00484 00485 //tmpT2 = Simulator::Instance()->GetWallTime(); 00486 00487 // publish to ros 00488 last_image_pub_time_ = Simulator::Instance()->GetSimTime(); 00489 this->image_pub_.publish(this->imageMsg); 00490 } 00491 00492 //double tmpT3 = Simulator::Instance()->GetWallTime(); 00493 00494 this->lock.unlock(); 00495 } 00496 } 00497 00498 { 00499 // prevent parent from updating the image and the depth data while we are retrieving it 00500 boost::recursive_mutex::scoped_lock mr_lock(*Simulator::Instance()->GetMRMutex()); 00501 00502 depths = this->myParent->GetDepthData(0); 00503 if (depths) 00504 { 00505 //double tmpT0 = Simulator::Instance()->GetWallTime(); 00506 this->lock.lock(); 00507 this->pointCloudMsg.header.frame_id = this->frameName; 00508 Time lastRenderTime = (dynamic_cast<OgreCamera*>(this->myParent))->GetLastRenderTime(); 00509 this->pointCloudMsg.header.stamp.sec = lastRenderTime.sec; 00510 this->pointCloudMsg.header.stamp.nsec = lastRenderTime.nsec; 00511 this->pointCloudMsg.width = this->width; 00512 this->pointCloudMsg.height = this->height; 00513 00515 fillDepthImage(this->pointCloudMsg, 00516 this->height, 00517 this->width, 00518 this->skip, 00519 (void*)depths ); 00520 /* 00521 for (int i = 0 ; i < this->height; i++) 00522 for (int j = 0 ; j < this->width; i++) { 00523 ROS_ERROR("test %d %d %f",i,j,depths[j + i*this->width]); 00524 } 00525 */ 00526 00527 //tmpT2 = Simulator::Instance()->GetWallTime(); 00528 00529 // publish to ros 00530 this->point_cloud_pub_.publish(this->pointCloudMsg); 00531 00532 //double tmpT3 = Simulator::Instance()->GetWallTime(); 00533 00534 this->lock.unlock(); 00535 } 00536 } 00537 } 00538 00539 00541 // Convert image format from gazebo sensor provided foramt to desired ros format 00542 void GazeboRosCamera::convertImageFormat(unsigned char *dst, const unsigned char *src) 00543 { 00544 // do last minute conversion if Bayer pattern is requested but not provided, go from R8G8B8 00545 // deprecated in gazebo2 branch, keep for backwards compatibility 00546 if (this->myParent->GetImageFormat() == "BAYER_RGGB8" && this->depth == 3) 00547 { 00548 for (int i=0;i<this->width;i++) 00549 { 00550 for (int j=0;j<this->height;j++) 00551 { 00552 // 00553 // RG 00554 // GB 00555 // 00556 // determine position 00557 if (j%2) // even column 00558 if (i%2) // even row, red 00559 dst[i+j*this->width] = src[i*3+j*this->width*3+0]; 00560 else // odd row, green 00561 dst[i+j*this->width] = src[i*3+j*this->width*3+1]; 00562 else // odd column 00563 if (i%2) // even row, green 00564 dst[i+j*this->width] = src[i*3+j*this->width*3+1]; 00565 else // odd row, blue 00566 dst[i+j*this->width] = src[i*3+j*this->width*3+2]; 00567 } 00568 } 00569 src=dst; 00570 } 00571 else if (this->myParent->GetImageFormat() == "BAYER_BGGR8" && this->depth == 3) 00572 { 00573 for (int i=0;i<this->width;i++) 00574 { 00575 for (int j=0;j<this->height;j++) 00576 { 00577 // 00578 // BG 00579 // GR 00580 // 00581 // determine position 00582 if (j%2) // even column 00583 if (i%2) // even row, blue 00584 dst[i+j*this->width] = src[i*3+j*this->width*3+2]; 00585 else // odd row, green 00586 dst[i+j*this->width] = src[i*3+j*this->width*3+1]; 00587 else // odd column 00588 if (i%2) // even row, green 00589 dst[i+j*this->width] = src[i*3+j*this->width*3+1]; 00590 else // odd row, red 00591 dst[i+j*this->width] = src[i*3+j*this->width*3+0]; 00592 } 00593 } 00594 src=dst; 00595 } 00596 else if (this->myParent->GetImageFormat() == "BAYER_GBRG8" && this->depth == 3) 00597 { 00598 for (int i=0;i<this->width;i++) 00599 { 00600 for (int j=0;j<this->height;j++) 00601 { 00602 // 00603 // GB 00604 // RG 00605 // 00606 // determine position 00607 if (j%2) // even column 00608 if (i%2) // even row, green 00609 dst[i+j*this->width] = src[i*3+j*this->width*3+1]; 00610 else // odd row, blue 00611 dst[i+j*this->width] = src[i*3+j*this->width*3+2]; 00612 else // odd column 00613 if (i%2) // even row, red 00614 dst[i+j*this->width] = src[i*3+j*this->width*3+0]; 00615 else // odd row, green 00616 dst[i+j*this->width] = src[i*3+j*this->width*3+1]; 00617 } 00618 } 00619 src=dst; 00620 } 00621 else if (this->myParent->GetImageFormat() == "BAYER_GRBG8" && this->depth == 3) 00622 { 00623 for (int i=0;i<this->width;i++) 00624 { 00625 for (int j=0;j<this->height;j++) 00626 { 00627 // 00628 // GR 00629 // BG 00630 // 00631 // determine position 00632 if (j%2) // even column 00633 if (i%2) // even row, green 00634 dst[i+j*this->width] = src[i*3+j*this->width*3+1]; 00635 else // odd row, red 00636 dst[i+j*this->width] = src[i*3+j*this->width*3+0]; 00637 else // odd column 00638 if (i%2) // even row, blue 00639 dst[i+j*this->width] = src[i*3+j*this->width*3+2]; 00640 else // odd row, green 00641 dst[i+j*this->width] = src[i*3+j*this->width*3+1]; 00642 } 00643 } 00644 src=dst; 00645 } 00646 } 00647 00649 // Fill depth information 00650 bool GazeboRosCamera::fillDepthImage(pcl::PointCloud<pcl::PointXYZ>& point_cloud, 00651 uint32_t rows_arg, 00652 uint32_t cols_arg, 00653 uint32_t step_arg, 00654 void* data_arg) 00655 { 00656 point_cloud.points.resize(0); 00657 point_cloud.is_dense = true; 00658 //point_cloud.channels.resize(1); 00659 //point_cloud.channels[0].values.resize(0); 00660 00661 float* toCopyFrom = (float*)data_arg; 00662 int index = 0; 00663 00664 double hfov = this->myParent->GetHFOV().GetAsRadian(); 00665 double fl = ((double)this->width) / (2.0 *tan(hfov/2.0)); 00666 //ROS_ERROR("debug hfov: %f fl: %f w: %f h: %f",hfov, fl, (double)cols_arg, (double)rows_arg); 00667 //ROS_ERROR("debug %f %f", this->myParent->GetFarClip() , this->myParent->GetNearClip()); 00668 00669 // convert depth to point cloud 00670 for (uint32_t j=0; j<rows_arg; j++) 00671 { 00672 double pAngle; 00673 if (rows_arg>1) pAngle = atan2( (double)j - 0.5*(double)(rows_arg-1), fl); 00674 else pAngle = 0.0; 00675 00676 for (uint32_t i=0; i<cols_arg; i++) 00677 { 00678 double yAngle; 00679 if (cols_arg>1) yAngle = atan2( (double)i - 0.5*(double)(cols_arg-1), fl); 00680 else yAngle = 0.0; 00681 00682 //double depth = (this->myParent->GetFarClip() - this->myParent->GetNearClip()) * ( toCopyFrom[index++] ) + 1.0 * this->myParent->GetNearClip() ; 00683 //double depth = ( this->myParent->GetFarClip() + this->myParent->GetNearClip() + toCopyFrom[index++] ) 00684 // * 0.5 ; //this->myParent->GetNearClip() ; 00685 double depth = toCopyFrom[index++]; // + 0.0*this->myParent->GetNearClip(); 00686 00687 // in optical frame 00688 // hardcoded rotation rpy(-M_PI/2, 0, -M_PI/2) is built-in 00689 // to urdf, where the *_optical_frame should have above relative 00690 // rotation from the physical camera *_frame 00691 pcl::PointXYZ point; 00692 point.x = depth * tan(yAngle); 00693 point.y = depth * tan(pAngle); 00694 if(depth > this->pointCloudCutoff) 00695 { 00696 point.z = depth; 00697 } 00698 else //point in the unseeable range 00699 { 00700 point.x = point.y = point.z = std::numeric_limits<float>::quiet_NaN (); 00701 point_cloud.is_dense = false; 00702 } 00703 point_cloud.points.push_back(point); 00704 } 00705 } 00706 //this->pointCloudMsg.channels[0].values.push_back(1.0); 00707 return true; 00708 } 00710 // Put laser data to the interface 00711 void GazeboRosCamera::PublishCameraInfo() 00712 { 00713 // fill CameraInfo 00714 this->cameraInfoMsg.header.frame_id = this->frameName; 00715 Time lastRenderTime = (dynamic_cast<OgreCamera*>(this->myParent))->GetLastRenderTime(); 00716 //Time lastRenderTime = Simulator::Instance()->GetSimTime(); 00717 this->cameraInfoMsg.header.stamp.sec = lastRenderTime.sec; 00718 this->cameraInfoMsg.header.stamp.nsec = lastRenderTime.nsec; 00719 this->cameraInfoMsg.height = this->height; 00720 this->cameraInfoMsg.width = this->width; 00721 // distortion 00722 #if ROS_VERSION_MINIMUM(1, 3, 0) 00723 this->cameraInfoMsg.distortion_model = "plumb_bob"; 00724 this->cameraInfoMsg.D.resize(5); 00725 #endif 00726 this->cameraInfoMsg.D[0] = this->distortion_k1; 00727 this->cameraInfoMsg.D[1] = this->distortion_k2; 00728 this->cameraInfoMsg.D[2] = this->distortion_k3; 00729 this->cameraInfoMsg.D[3] = this->distortion_t1; 00730 this->cameraInfoMsg.D[4] = this->distortion_t2; 00731 // original camera matrix 00732 this->cameraInfoMsg.K[0] = this->focal_length; 00733 this->cameraInfoMsg.K[1] = 0.0; 00734 this->cameraInfoMsg.K[2] = this->Cx; 00735 this->cameraInfoMsg.K[3] = 0.0; 00736 this->cameraInfoMsg.K[4] = this->focal_length; 00737 this->cameraInfoMsg.K[5] = this->Cy; 00738 this->cameraInfoMsg.K[6] = 0.0; 00739 this->cameraInfoMsg.K[7] = 0.0; 00740 this->cameraInfoMsg.K[8] = 1.0; 00741 // rectification 00742 this->cameraInfoMsg.R[0] = 1.0; 00743 this->cameraInfoMsg.R[1] = 0.0; 00744 this->cameraInfoMsg.R[2] = 0.0; 00745 this->cameraInfoMsg.R[3] = 0.0; 00746 this->cameraInfoMsg.R[4] = 1.0; 00747 this->cameraInfoMsg.R[5] = 0.0; 00748 this->cameraInfoMsg.R[6] = 0.0; 00749 this->cameraInfoMsg.R[7] = 0.0; 00750 this->cameraInfoMsg.R[8] = 1.0; 00751 // camera projection matrix (same as camera matrix due to lack of distortion/rectification) (is this generated?) 00752 this->cameraInfoMsg.P[0] = this->focal_length; 00753 this->cameraInfoMsg.P[1] = 0.0; 00754 this->cameraInfoMsg.P[2] = this->Cx; 00755 this->cameraInfoMsg.P[3] = -this->focal_length * this->hack_baseline; 00756 this->cameraInfoMsg.P[4] = 0.0; 00757 this->cameraInfoMsg.P[5] = this->focal_length; 00758 this->cameraInfoMsg.P[6] = this->Cy; 00759 this->cameraInfoMsg.P[7] = 0.0; 00760 this->cameraInfoMsg.P[8] = 0.0; 00761 this->cameraInfoMsg.P[9] = 0.0; 00762 this->cameraInfoMsg.P[10] = 1.0; 00763 this->cameraInfoMsg.P[11] = 0.0; 00764 00765 last_camera_info_pub_time_ = Simulator::Instance()->GetSimTime(); 00766 this->camera_info_pub_.publish(this->cameraInfoMsg); 00767 } 00768 00769 00770 #ifdef USE_CBQ 00771 00772 // Put laser data to the interface 00773 void GazeboRosCamera::CameraQueueThread() 00774 { 00775 static const double timeout = 0.01; 00776 00777 while (this->rosnode_->ok()) 00778 { 00779 this->camera_queue_.callAvailable(ros::WallDuration(timeout)); 00780 } 00781 } 00782 #endif 00783 00784 }