00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031 #include <algorithm>
00032 #include <assert.h>
00033
00034 #include <pr2_gazebo_plugins/gazebo_ros_prosilica.h>
00035
00036 #include <gazebo/Sensor.hh>
00037 #include <gazebo/Model.hh>
00038 #include <gazebo/Global.hh>
00039 #include <gazebo/XMLConfig.hh>
00040 #include <gazebo/Simulator.hh>
00041 #include <gazebo/gazebo.h>
00042 #include <gazebo/GazeboError.hh>
00043 #include <gazebo/ControllerFactory.hh>
00044 #include "gazebo/MonoCameraSensor.hh"
00045
00046
00047 #include <sensor_msgs/Image.h>
00048 #include <sensor_msgs/CameraInfo.h>
00049 #include <sensor_msgs/fill_image.h>
00050 #include <diagnostic_updater/diagnostic_updater.h>
00051 #include <sensor_msgs/RegionOfInterest.h>
00052
00053 #include <cv_bridge/CvBridge.h>
00054 #include <opencv/cv.h>
00055 #include <opencv/highgui.h>
00056
00057 #include <cv.h>
00058 #include <cvwimage.h>
00059
00060 #include <boost/scoped_ptr.hpp>
00061 #include <boost/bind.hpp>
00062 #include <boost/tokenizer.hpp>
00063 #include <boost/thread.hpp>
00064 #include <boost/thread/recursive_mutex.hpp>
00065 #include <string>
00066
00067 namespace gazebo
00068 {
00069
00070 GZ_REGISTER_DYNAMIC_CONTROLLER("gazebo_ros_prosilica", GazeboRosProsilica);
00071
00073
00074 GazeboRosProsilica::GazeboRosProsilica(Entity *parent)
00075 : Controller(parent)
00076 {
00077 this->myParent = dynamic_cast<MonoCameraSensor*>(this->parent);
00078
00079 if (!this->myParent)
00080 gzthrow("GazeboRosProsilica controller requires a Camera Sensor as its parent");
00081
00082 Param::Begin(&this->parameters);
00083 this->robotNamespaceP = new ParamT<std::string>("robotNamespace", "/", 0);
00084 this->imageTopicNameP = new ParamT<std::string>("imageTopicName","image_raw", 0);
00085 this->cameraInfoTopicNameP = new ParamT<std::string>("cameraInfoTopicName","camera_info", 0);
00086 this->pollServiceNameP = new ParamT<std::string>("pollServiceName","request_image", 0);
00087 this->frameNameP = new ParamT<std::string>("frameName","camera", 0);
00088
00089 this->CxPrimeP = new ParamT<double>("CxPrime",320, 0);
00090 this->CxP = new ParamT<double>("Cx" ,320, 0);
00091 this->CyP = new ParamT<double>("Cy" ,240, 0);
00092 this->focal_lengthP = new ParamT<double>("focal_length" ,554.256, 0);
00093 this->hack_baselineP = new ParamT<double>("hackBaseline" ,0, 0);
00094 this->distortion_k1P = new ParamT<double>("distortion_k1" ,0, 0);
00095 this->distortion_k2P = new ParamT<double>("distortion_k2" ,0, 0);
00096 this->distortion_k3P = new ParamT<double>("distortion_k3" ,0, 0);
00097 this->distortion_t1P = new ParamT<double>("distortion_t1" ,0, 0);
00098 this->distortion_t2P = new ParamT<double>("distortion_t2" ,0, 0);
00099 Param::End();
00100
00101 this->imageConnectCount = 0;
00102 this->infoConnectCount = 0;
00103 }
00104
00106
00107 GazeboRosProsilica::~GazeboRosProsilica()
00108 {
00109 delete this->robotNamespaceP;
00110 delete this->rosnode_;
00111 delete this->imageTopicNameP;
00112 delete this->cameraInfoTopicNameP;
00113 delete this->pollServiceNameP;
00114 delete this->frameNameP;
00115 delete this->CxPrimeP;
00116 delete this->CxP;
00117 delete this->CyP;
00118 delete this->focal_lengthP;
00119 delete this->hack_baselineP;
00120 delete this->distortion_k1P;
00121 delete this->distortion_k2P;
00122 delete this->distortion_k3P;
00123 delete this->distortion_t1P;
00124 delete this->distortion_t2P;
00125
00126 }
00127
00129
00130 void GazeboRosProsilica::LoadChild(XMLConfigNode *node)
00131 {
00132 this->robotNamespaceP->Load(node);
00133 this->robotNamespace = this->robotNamespaceP->GetValue();
00134 if (!ros::isInitialized())
00135 {
00136 int argc = 0;
00137 char** argv = NULL;
00138 ros::init(argc,argv,"gazebo",ros::init_options::NoSigintHandler|ros::init_options::AnonymousName);
00139 }
00140 this->rosnode_ = new ros::NodeHandle(this->robotNamespace);
00141 this->rosnode_->setCallbackQueue(&this->prosilica_queue_);
00142
00143 this->imageTopicNameP->Load(node);
00144 this->cameraInfoTopicNameP->Load(node);
00145 this->pollServiceNameP->Load(node);
00146 this->frameNameP->Load(node);
00147 this->CxPrimeP->Load(node);
00148 this->CxP->Load(node);
00149 this->CyP->Load(node);
00150 this->focal_lengthP->Load(node);
00151 this->hack_baselineP->Load(node);
00152 this->distortion_k1P->Load(node);
00153 this->distortion_k2P->Load(node);
00154 this->distortion_k3P->Load(node);
00155 this->distortion_t1P->Load(node);
00156 this->distortion_t2P->Load(node);
00157
00158 this->imageTopicName = this->imageTopicNameP->GetValue();
00159 this->cameraInfoTopicName = this->cameraInfoTopicNameP->GetValue();
00160 this->pollServiceName = this->pollServiceNameP->GetValue();
00161 this->frameName = this->frameNameP->GetValue();
00162 this->CxPrime = this->CxPrimeP->GetValue();
00163 this->Cx = this->CxP->GetValue();
00164 this->Cy = this->CyP->GetValue();
00165 this->focal_length = this->focal_lengthP->GetValue();
00166 this->hack_baseline = this->hack_baselineP->GetValue();
00167 this->distortion_k1 = this->distortion_k1P->GetValue();
00168 this->distortion_k2 = this->distortion_k2P->GetValue();
00169 this->distortion_k3 = this->distortion_k3P->GetValue();
00170 this->distortion_t1 = this->distortion_t1P->GetValue();
00171 this->distortion_t2 = this->distortion_t2P->GetValue();
00172 if ((this->distortion_k1 != 0.0) || (this->distortion_k2 != 0.0) ||
00173 (this->distortion_k3 != 0.0) || (this->distortion_t1 != 0.0) ||
00174 (this->distortion_t2 != 0.0))
00175 ROS_WARN("gazebo_ros_prosilica simulation does not support non-zero distortion parameters right now, your simulation maybe wrong.");
00176
00177
00178
00179 std::string mode_param_name;
00180
00181
00182
00183 if (!this->rosnode_->searchParam("trigger_mode",mode_param_name))
00184 mode_param_name = "trigger_mode";
00185
00186 if (!this->rosnode_->getParam(mode_param_name,this->mode_))
00187 this->mode_ = "streaming";
00188
00189 ROS_INFO("trigger_mode %s %s",mode_param_name.c_str(),this->mode_.c_str());
00190
00191
00192 if (this->mode_ == "polled")
00193 {
00194 poll_srv_ = polled_camera::advertise(*this->rosnode_,this->pollServiceName,&GazeboRosProsilica::pollCallback,this);
00195 }
00196 else if (this->mode_ == "streaming")
00197 {
00198 ROS_DEBUG("do nothing here,mode: %s",this->mode_.c_str());
00199 }
00200 else
00201 {
00202 ROS_ERROR("trigger_mode is invalid: %s, using streaming mode",this->mode_.c_str());
00203 }
00205 ros::AdvertiseOptions image_ao = ros::AdvertiseOptions::create<sensor_msgs::Image>(
00206 this->imageTopicName,1,
00207 boost::bind( &GazeboRosProsilica::ImageConnect,this),
00208 boost::bind( &GazeboRosProsilica::ImageDisconnect,this), ros::VoidPtr(), &this->prosilica_queue_);
00209 this->image_pub_ = this->rosnode_->advertise(image_ao);
00210
00211 ros::AdvertiseOptions camera_info_ao = ros::AdvertiseOptions::create<sensor_msgs::CameraInfo>(
00212 this->cameraInfoTopicName,1,
00213 boost::bind( &GazeboRosProsilica::InfoConnect,this),
00214 boost::bind( &GazeboRosProsilica::InfoDisconnect,this), ros::VoidPtr(), &this->prosilica_queue_);
00215 this->camera_info_pub_ = this->rosnode_->advertise(camera_info_ao);
00216
00217 }
00218
00220
00221 void GazeboRosProsilica::InitChild()
00222 {
00223
00224 this->myParent->SetActive(false);
00225
00226
00227 this->width = this->myParent->GetImageWidth();
00228 this->height = this->myParent->GetImageHeight();
00229 this->depth = this->myParent->GetImageDepth();
00230
00231 if (this->myParent->GetImageFormat() == "L8")
00232 {
00233 this->type = sensor_msgs::image_encodings::MONO8;
00234 this->skip = 1;
00235 }
00236 else if (this->myParent->GetImageFormat() == "R8G8B8")
00237 {
00238 this->type = sensor_msgs::image_encodings::RGB8;
00239 this->skip = 3;
00240 }
00241 else if (this->myParent->GetImageFormat() == "B8G8R8")
00242 {
00243 this->type = sensor_msgs::image_encodings::BGR8;
00244 this->skip = 3;
00245 }
00246 else if (this->myParent->GetImageFormat() == "BAYER_RGGB8")
00247 {
00248 this->type = sensor_msgs::image_encodings::BAYER_RGGB8;
00249 this->skip = 1;
00250 }
00251 else if (this->myParent->GetImageFormat() == "BAYER_BGGR8")
00252 {
00253 this->type = sensor_msgs::image_encodings::BAYER_BGGR8;
00254 this->skip = 1;
00255 }
00256 else if (this->myParent->GetImageFormat() == "BAYER_GBRG8")
00257 {
00258 this->type = sensor_msgs::image_encodings::BAYER_GBRG8;
00259 this->skip = 1;
00260 }
00261 else if (this->myParent->GetImageFormat() == "BAYER_GRBG8")
00262 {
00263 this->type = sensor_msgs::image_encodings::BAYER_GRBG8;
00264 this->skip = 1;
00265 }
00266 else
00267 {
00268 ROS_ERROR("Unsupported Gazebo ImageFormat for Prosilica, using BGR8\n");
00269 this->type = sensor_msgs::image_encodings::BGR8;
00270 this->skip = 3;
00271 }
00272
00274 if (this->CxPrime == 0)
00275 this->CxPrime = ((double)this->width+1.0) /2.0;
00276 if (this->Cx == 0)
00277 this->Cx = ((double)this->width+1.0) /2.0;
00278 if (this->Cy == 0)
00279 this->Cy = ((double)this->height+1.0) /2.0;
00280 if (this->focal_length == 0)
00281 this->focal_length = ((double)this->width) / (2.0 *tan(this->myParent->GetHFOV().GetAsRadian()/2.0));
00282
00283 #ifdef USE_CBQ
00284
00285 this->prosilica_callback_queue_thread_ = boost::thread( boost::bind( &GazeboRosProsilica::ProsilicaQueueThread,this ) );
00286 #else
00287
00288 this->ros_spinner_thread_ = boost::thread( boost::bind( &GazeboRosProsilica::ProsilicaROSThread,this ) );
00289 #endif
00290
00291 }
00292
00294
00295 void GazeboRosProsilica::ImageConnect()
00296 {
00297 this->imageConnectCount++;
00298 }
00300
00301 void GazeboRosProsilica::ImageDisconnect()
00302 {
00303 this->imageConnectCount--;
00304
00305 if ((this->infoConnectCount == 0) && (this->imageConnectCount == 0))
00306 this->myParent->SetActive(false);
00307 }
00308
00310
00311 void GazeboRosProsilica::InfoConnect()
00312 {
00313 this->infoConnectCount++;
00314 }
00316
00317 void GazeboRosProsilica::InfoDisconnect()
00318 {
00319 this->infoConnectCount--;
00320
00321 if ((this->infoConnectCount == 0) && (this->imageConnectCount == 0))
00322 this->myParent->SetActive(false);
00323 }
00324
00326
00327 void GazeboRosProsilica::UpdateChild()
00328 {
00329
00330
00332
00333
00334
00335 if (!this->myParent->IsActive())
00336 {
00337 if (this->imageConnectCount > 0)
00338
00339 this->myParent->SetActive(true);
00340 }
00341 else
00342 {
00343
00344 if (this->mode_ == "streaming")
00345 this->PutCameraData();
00346 }
00347
00349 if (this->infoConnectCount > 0)
00350 if (this->mode_ == "streaming")
00351 this->PublishCameraInfo();
00352 }
00354
00355 void GazeboRosProsilica::PutCameraData()
00356 {
00357 const unsigned char *src;
00358
00359
00360
00361
00362 src = this->myParent->GetImageData(0);
00363
00364 if (src)
00365 {
00366
00367
00368 unsigned char dst[this->width*this->height];
00369
00370 this->lock.lock();
00371
00372 this->imageMsg.header.frame_id = this->frameName;
00373 #if GAZEBO_MAJOR_VERSION == 0 && GAZEBO_MINOR_VERSION >= 10
00374 this->imageMsg.header.stamp.fromSec(Simulator::Instance()->GetSimTime().Double());
00375 #else
00376 this->imageMsg.header.stamp.fromSec(Simulator::Instance()->GetSimTime());
00377 #endif
00378
00379
00380
00381
00383 if (this->image_pub_.getNumSubscribers() > 0)
00384 {
00385
00386
00387
00388 if (this->myParent->GetImageFormat() == "BAYER_RGGB8" && this->depth == 3)
00389 {
00390 for (int i=0;i<this->width;i++)
00391 {
00392 for (int j=0;j<this->height;j++)
00393 {
00394
00395
00396
00397
00398
00399 if (j%2)
00400 if (i%2)
00401 dst[i+j*this->width] = src[i*3+j*this->width*3+0];
00402 else
00403 dst[i+j*this->width] = src[i*3+j*this->width*3+1];
00404 else
00405 if (i%2)
00406 dst[i+j*this->width] = src[i*3+j*this->width*3+1];
00407 else
00408 dst[i+j*this->width] = src[i*3+j*this->width*3+2];
00409 }
00410 }
00411 src=dst;
00412 }
00413 else if (this->myParent->GetImageFormat() == "BAYER_BGGR8" && this->depth == 3)
00414 {
00415 for (int i=0;i<this->width;i++)
00416 {
00417 for (int j=0;j<this->height;j++)
00418 {
00419
00420
00421
00422
00423
00424 if (j%2)
00425 if (i%2)
00426 dst[i+j*this->width] = src[i*3+j*this->width*3+2];
00427 else
00428 dst[i+j*this->width] = src[i*3+j*this->width*3+1];
00429 else
00430 if (i%2)
00431 dst[i+j*this->width] = src[i*3+j*this->width*3+1];
00432 else
00433 dst[i+j*this->width] = src[i*3+j*this->width*3+0];
00434 }
00435 }
00436 src=dst;
00437 }
00438 else if (this->myParent->GetImageFormat() == "BAYER_GBRG8" && this->depth == 3)
00439 {
00440 for (int i=0;i<this->width;i++)
00441 {
00442 for (int j=0;j<this->height;j++)
00443 {
00444
00445
00446
00447
00448
00449 if (j%2)
00450 if (i%2)
00451 dst[i+j*this->width] = src[i*3+j*this->width*3+1];
00452 else
00453 dst[i+j*this->width] = src[i*3+j*this->width*3+2];
00454 else
00455 if (i%2)
00456 dst[i+j*this->width] = src[i*3+j*this->width*3+0];
00457 else
00458 dst[i+j*this->width] = src[i*3+j*this->width*3+1];
00459 }
00460 }
00461 src=dst;
00462 }
00463 else if (this->myParent->GetImageFormat() == "BAYER_GRBG8" && this->depth == 3)
00464 {
00465 for (int i=0;i<this->width;i++)
00466 {
00467 for (int j=0;j<this->height;j++)
00468 {
00469
00470
00471
00472
00473
00474 if (j%2)
00475 if (i%2)
00476 dst[i+j*this->width] = src[i*3+j*this->width*3+1];
00477 else
00478 dst[i+j*this->width] = src[i*3+j*this->width*3+0];
00479 else
00480 if (i%2)
00481 dst[i+j*this->width] = src[i*3+j*this->width*3+2];
00482 else
00483 dst[i+j*this->width] = src[i*3+j*this->width*3+1];
00484 }
00485 }
00486 src=dst;
00487 }
00488
00489
00490
00491
00492 fillImage(this->imageMsg,
00493 this->type,
00494 this->height,
00495 this->width,
00496 this->skip*this->width,
00497 (void*)src );
00498
00499
00500
00501
00502 this->image_pub_.publish(this->imageMsg);
00503 }
00504
00505
00506
00507 this->lock.unlock();
00508 }
00509
00510 }
00511
00513
00514 void GazeboRosProsilica::PublishCameraInfo()
00515 {
00516
00517 this->cameraInfoMsg.header.frame_id = this->frameName;
00518 #if GAZEBO_MAJOR_VERSION == 0 && GAZEBO_MINOR_VERSION >= 10
00519 this->cameraInfoMsg.header.stamp.fromSec(Simulator::Instance()->GetSimTime().Double());
00520 #else
00521 this->cameraInfoMsg.header.stamp.fromSec(Simulator::Instance()->GetSimTime());
00522 #endif
00523 this->cameraInfoMsg.height = this->height;
00524 this->cameraInfoMsg.width = this->width;
00525
00526
00527 #if ROS_VERSION_MINIMUM(1, 3, 0)
00528 this->cameraInfoMsg.distortion_model = "plumb_bob";
00529 this->cameraInfoMsg.D.resize(5);
00530 #endif
00531 this->cameraInfoMsg.D[0] = this->distortion_k1;
00532 this->cameraInfoMsg.D[1] = this->distortion_k2;
00533 this->cameraInfoMsg.D[2] = this->distortion_k3;
00534 this->cameraInfoMsg.D[3] = this->distortion_t1;
00535 this->cameraInfoMsg.D[4] = this->distortion_t2;
00536
00537 this->cameraInfoMsg.K[0] = this->focal_length;
00538 this->cameraInfoMsg.K[1] = 0.0;
00539 this->cameraInfoMsg.K[2] = this->Cx;
00540 this->cameraInfoMsg.K[3] = 0.0;
00541 this->cameraInfoMsg.K[4] = this->focal_length;
00542 this->cameraInfoMsg.K[5] = this->Cy;
00543 this->cameraInfoMsg.K[6] = 0.0;
00544 this->cameraInfoMsg.K[7] = 0.0;
00545 this->cameraInfoMsg.K[8] = 1.0;
00546
00547 this->cameraInfoMsg.R[0] = 1.0;
00548 this->cameraInfoMsg.R[1] = 0.0;
00549 this->cameraInfoMsg.R[2] = 0.0;
00550 this->cameraInfoMsg.R[3] = 0.0;
00551 this->cameraInfoMsg.R[4] = 1.0;
00552 this->cameraInfoMsg.R[5] = 0.0;
00553 this->cameraInfoMsg.R[6] = 0.0;
00554 this->cameraInfoMsg.R[7] = 0.0;
00555 this->cameraInfoMsg.R[8] = 1.0;
00556
00557 this->cameraInfoMsg.P[0] = this->focal_length;
00558 this->cameraInfoMsg.P[1] = 0.0;
00559 this->cameraInfoMsg.P[2] = this->Cx;
00560 this->cameraInfoMsg.P[3] = -this->focal_length * this->hack_baseline;
00561 this->cameraInfoMsg.P[4] = 0.0;
00562 this->cameraInfoMsg.P[5] = this->focal_length;
00563 this->cameraInfoMsg.P[6] = this->Cy;
00564 this->cameraInfoMsg.P[7] = 0.0;
00565 this->cameraInfoMsg.P[8] = 0.0;
00566 this->cameraInfoMsg.P[9] = 0.0;
00567 this->cameraInfoMsg.P[10] = 1.0;
00568 this->cameraInfoMsg.P[11] = 0.0;
00569 this->camera_info_pub_.publish(this->cameraInfoMsg);
00570 }
00571
00573
00574 void GazeboRosProsilica::pollCallback(polled_camera::GetPolledImage::Request& req,
00575 polled_camera::GetPolledImage::Response& rsp,
00576 sensor_msgs::Image& image, sensor_msgs::CameraInfo& info)
00577 {
00581
00582 if (this->mode_ != "polled")
00583 {
00584 rsp.success = false;
00585 rsp.status_message = "Camera is not in triggered mode";
00586 return;
00587 }
00588
00589 if (req.binning_x > 1 || req.binning_y > 1)
00590 {
00591 rsp.success = false;
00592 rsp.status_message = "Gazebo Prosilica plugin does not support binning";
00593 return;
00594 }
00595
00596
00597
00598
00599
00600
00601
00602
00603
00604
00605
00606
00607
00608
00609
00610
00611
00612
00613
00614
00615
00616
00617
00618
00619
00620
00621
00622
00623
00624
00625
00626
00627
00628
00629
00630
00631
00632
00633
00634
00635
00636
00637
00638
00639
00640
00641
00642
00643
00644
00645
00646
00647
00648
00649
00650
00651
00652 if (req.roi.x_offset <= 0 || req.roi.y_offset <= 0 || req.roi.width <= 0 || req.roi.height <= 0)
00653 {
00654 req.roi.x_offset = 0;
00655 req.roi.y_offset = 0;
00656 req.roi.width = this->width;
00657 req.roi.height = this->height;
00658 }
00659 const unsigned char *src = NULL;
00660 ROS_ERROR("roidebug %d %d %d %d", req.roi.x_offset, req.roi.y_offset, req.roi.width, req.roi.height);
00661
00662
00663 this->ImageConnect();
00664
00665 while(!src)
00666 {
00667 {
00668 boost::recursive_mutex::scoped_lock lock(*Simulator::Instance()->GetMRMutex());
00669
00670 src = this->myParent->GetImageData(0);
00671
00672 if (src)
00673 {
00674
00675
00676 this->roiCameraInfoMsg = &info;
00677 this->roiCameraInfoMsg->header.frame_id = this->frameName;
00678 #if GAZEBO_MAJOR_VERSION == 0 && GAZEBO_MINOR_VERSION >= 10
00679 this->roiCameraInfoMsg->header.stamp.fromSec( (dynamic_cast<OgreCamera*>(this->myParent))->GetLastRenderTime().Double());
00680 #else
00681 this->roiCameraInfoMsg->header.stamp.fromSec( (dynamic_cast<OgreCamera*>(this->myParent))->GetLastRenderTime());
00682 #endif
00683 this->roiCameraInfoMsg->width = req.roi.width;
00684 this->roiCameraInfoMsg->height = req.roi.height;
00685
00686 #if ROS_VERSION_MINIMUM(1, 3, 0)
00687 this->roiCameraInfoMsg->distortion_model = "plumb_bob";
00688 this->roiCameraInfoMsg->D.resize(5);
00689 #endif
00690 this->roiCameraInfoMsg->D[0] = this->distortion_k1;
00691 this->roiCameraInfoMsg->D[1] = this->distortion_k2;
00692 this->roiCameraInfoMsg->D[2] = this->distortion_k3;
00693 this->roiCameraInfoMsg->D[3] = this->distortion_t1;
00694 this->roiCameraInfoMsg->D[4] = this->distortion_t2;
00695
00696 this->roiCameraInfoMsg->K[0] = this->focal_length;
00697 this->roiCameraInfoMsg->K[1] = 0.0;
00698 this->roiCameraInfoMsg->K[2] = this->Cx - req.roi.x_offset;
00699 this->roiCameraInfoMsg->K[3] = 0.0;
00700 this->roiCameraInfoMsg->K[4] = this->focal_length;
00701 this->roiCameraInfoMsg->K[5] = this->Cy - req.roi.y_offset;
00702 this->roiCameraInfoMsg->K[6] = 0.0;
00703 this->roiCameraInfoMsg->K[7] = 0.0;
00704 this->roiCameraInfoMsg->K[8] = 1.0;
00705
00706 this->roiCameraInfoMsg->R[0] = 1.0;
00707 this->roiCameraInfoMsg->R[1] = 0.0;
00708 this->roiCameraInfoMsg->R[2] = 0.0;
00709 this->roiCameraInfoMsg->R[3] = 0.0;
00710 this->roiCameraInfoMsg->R[4] = 1.0;
00711 this->roiCameraInfoMsg->R[5] = 0.0;
00712 this->roiCameraInfoMsg->R[6] = 0.0;
00713 this->roiCameraInfoMsg->R[7] = 0.0;
00714 this->roiCameraInfoMsg->R[8] = 1.0;
00715
00716 this->roiCameraInfoMsg->P[0] = this->focal_length;
00717 this->roiCameraInfoMsg->P[1] = 0.0;
00718 this->roiCameraInfoMsg->P[2] = this->Cx - req.roi.x_offset;
00719 this->roiCameraInfoMsg->P[3] = -this->focal_length * this->hack_baseline;
00720 this->roiCameraInfoMsg->P[4] = 0.0;
00721 this->roiCameraInfoMsg->P[5] = this->focal_length;
00722 this->roiCameraInfoMsg->P[6] = this->Cy - req.roi.y_offset;
00723 this->roiCameraInfoMsg->P[7] = 0.0;
00724 this->roiCameraInfoMsg->P[8] = 0.0;
00725 this->roiCameraInfoMsg->P[9] = 0.0;
00726 this->roiCameraInfoMsg->P[10] = 1.0;
00727 this->roiCameraInfoMsg->P[11] = 0.0;
00728 this->camera_info_pub_.publish(*this->roiCameraInfoMsg);
00729
00730
00731 this->imageMsg.header.frame_id = this->frameName;
00732 #if GAZEBO_MAJOR_VERSION == 0 && GAZEBO_MINOR_VERSION >= 10
00733 this->imageMsg.header.stamp.fromSec( (dynamic_cast<OgreCamera*>(this->myParent))->GetLastRenderTime().Double());
00734 #else
00735 this->imageMsg.header.stamp.fromSec( (dynamic_cast<OgreCamera*>(this->myParent))->GetLastRenderTime());
00736 #endif
00737
00738 unsigned char dst[this->width*this->height];
00739
00741
00742
00743
00744 if (this->myParent->GetImageFormat() == "BAYER_RGGB8" && this->depth == 3)
00745 {
00746 for (int i=0;i<this->width;i++)
00747 {
00748 for (int j=0;j<this->height;j++)
00749 {
00750
00751
00752
00753
00754
00755 if (j%2)
00756 if (i%2)
00757 dst[i+j*this->width] = src[i*3+j*this->width*3+0];
00758 else
00759 dst[i+j*this->width] = src[i*3+j*this->width*3+1];
00760 else
00761 if (i%2)
00762 dst[i+j*this->width] = src[i*3+j*this->width*3+1];
00763 else
00764 dst[i+j*this->width] = src[i*3+j*this->width*3+2];
00765 }
00766 }
00767 src=dst;
00768 }
00769 else if (this->myParent->GetImageFormat() == "BAYER_BGGR8" && this->depth == 3)
00770 {
00771 for (int i=0;i<this->width;i++)
00772 {
00773 for (int j=0;j<this->height;j++)
00774 {
00775
00776
00777
00778
00779
00780 if (j%2)
00781 if (i%2)
00782 dst[i+j*this->width] = src[i*3+j*this->width*3+2];
00783 else
00784 dst[i+j*this->width] = src[i*3+j*this->width*3+1];
00785 else
00786 if (i%2)
00787 dst[i+j*this->width] = src[i*3+j*this->width*3+1];
00788 else
00789 dst[i+j*this->width] = src[i*3+j*this->width*3+0];
00790 }
00791 }
00792 src=dst;
00793 }
00794 else if (this->myParent->GetImageFormat() == "BAYER_GBRG8" && this->depth == 3)
00795 {
00796 for (int i=0;i<this->width;i++)
00797 {
00798 for (int j=0;j<this->height;j++)
00799 {
00800
00801
00802
00803
00804
00805 if (j%2)
00806 if (i%2)
00807 dst[i+j*this->width] = src[i*3+j*this->width*3+1];
00808 else
00809 dst[i+j*this->width] = src[i*3+j*this->width*3+2];
00810 else
00811 if (i%2)
00812 dst[i+j*this->width] = src[i*3+j*this->width*3+0];
00813 else
00814 dst[i+j*this->width] = src[i*3+j*this->width*3+1];
00815 }
00816 }
00817 src=dst;
00818 }
00819 else if (this->myParent->GetImageFormat() == "BAYER_GRBG8" && this->depth == 3)
00820 {
00821 for (int i=0;i<this->width;i++)
00822 {
00823 for (int j=0;j<this->height;j++)
00824 {
00825
00826
00827
00828
00829
00830 if (j%2)
00831 if (i%2)
00832 dst[i+j*this->width] = src[i*3+j*this->width*3+1];
00833 else
00834 dst[i+j*this->width] = src[i*3+j*this->width*3+0];
00835 else
00836 if (i%2)
00837 dst[i+j*this->width] = src[i*3+j*this->width*3+2];
00838 else
00839 dst[i+j*this->width] = src[i*3+j*this->width*3+1];
00840 }
00841 }
00842 src=dst;
00843 }
00844
00845
00846 fillImage(this->imageMsg,
00847 this->type,
00848 this->height,
00849 this->width,
00850 this->skip*this->width,
00851 (void*)src );
00852
00854
00855 this->image_pub_.publish(this->imageMsg);
00856
00857
00858
00859
00860 if (((this->myParent->GetImageFormat() == "BAYER_RGGB8") ||
00861 (this->myParent->GetImageFormat() == "BAYER_BGGR8") ||
00862 (this->myParent->GetImageFormat() == "BAYER_GBRG8") ||
00863 (this->myParent->GetImageFormat() == "BAYER_GRBG8") ) &&
00864 this->depth == 3)
00865 {
00866 ROS_ERROR("prosilica does not support bayer roi, using full image");
00867
00868
00869 fillImage(image,
00870 this->type,
00871 this->height,
00872 this->width,
00873 this->skip*this->width,
00874 (void*)src );
00875 }
00876 else
00877 {
00878
00879 this->roiImageMsg = ℑ
00880 this->roiImageMsg->header.frame_id = this->frameName;
00881 #if GAZEBO_MAJOR_VERSION == 0 && GAZEBO_MINOR_VERSION >= 10
00882 this->roiImageMsg->header.stamp.fromSec( (dynamic_cast<OgreCamera*>(this->myParent))->GetLastRenderTime().Double());
00883 #else
00884 this->roiImageMsg->header.stamp.fromSec( (dynamic_cast<OgreCamera*>(this->myParent))->GetLastRenderTime());
00885 #endif
00886
00887
00888
00889
00890
00891 sensor_msgs::CvBridge img_bridge_;
00892 img_bridge_.fromImage(this->imageMsg);
00893
00894
00895
00896
00897
00898
00899 cvSetImageROI(img_bridge_.toIpl(),cvRect(req.roi.x_offset,req.roi.y_offset,req.roi.width,req.roi.height));
00900 IplImage *roi = cvCreateImage(cvSize(req.roi.width,req.roi.height),
00901 img_bridge_.toIpl()->depth,
00902 img_bridge_.toIpl()->nChannels);
00903 cvCopy(img_bridge_.toIpl(),roi);
00904
00905 img_bridge_.fromIpltoRosImage(roi,*this->roiImageMsg);
00906
00907 cvReleaseImage(&roi);
00908 }
00909 }
00910 }
00911 usleep(100000);
00912 }
00913 this->ImageDisconnect();
00914 rsp.success = true;
00915 return;
00916 }
00917
00919
00920 void GazeboRosProsilica::FiniChild()
00921 {
00922 this->myParent->SetActive(false);
00923 this->rosnode_->shutdown();
00924 #ifdef USE_CBQ
00925 this->prosilica_queue_.clear();
00926 this->prosilica_queue_.disable();
00927 this->prosilica_callback_queue_thread_.join();
00928 #else
00929 this->ros_spinner_thread_.join();
00930 #endif
00931
00932 this->poll_srv_.shutdown();
00933 this->image_pub_.shutdown();
00934 this->camera_info_pub_.shutdown();
00935
00936 }
00937
00938 #ifdef USE_CBQ
00939
00940
00941 void GazeboRosProsilica::ProsilicaQueueThread()
00942 {
00943 static const double timeout = 0.01;
00944
00945 while (this->rosnode_->ok())
00946 {
00947 this->prosilica_queue_.callAvailable(ros::WallDuration(timeout));
00948 }
00949 }
00950 #else
00951 void GazeboRosProsilica::ProsilicaROSThread()
00952 {
00953 ROS_INFO_STREAM("Callback thread id=" << boost::this_thread::get_id());
00954
00955 ros::Rate rate(1000);
00956
00957 while (this->rosnode_->ok())
00958 {
00959
00960 usleep(1000);
00961 ros::spinOnce();
00962 }
00963 }
00964 #endif
00965
00966
00967 }