gazebo_ros_camera_utils.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2013 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 #include <string>
19 #include <algorithm>
20 #include <assert.h>
21 #include <boost/thread/thread.hpp>
22 #include <boost/bind.hpp>
23 
24 #include <tf/tf.h>
25 #include <tf/transform_listener.h>
26 #include <sensor_msgs/Image.h>
27 #include <sensor_msgs/fill_image.h>
29 #include <geometry_msgs/Point32.h>
30 #include <sensor_msgs/ChannelFloat32.h>
32 
33 #include <sdf/sdf.hh>
34 
35 #include <gazebo/physics/World.hh>
36 #include <gazebo/physics/HingeJoint.hh>
37 #include <gazebo/sensors/Sensor.hh>
38 #include <gazebo/common/Exception.hh>
39 #include <gazebo/sensors/CameraSensor.hh>
40 #include <gazebo/sensors/SensorTypes.hh>
41 #include <gazebo/rendering/Camera.hh>
42 #include <gazebo/rendering/Distortion.hh>
43 
45 
46 namespace gazebo
47 {
49 // Constructor
51 {
52  this->last_update_time_ = common::Time(0);
53  this->last_info_update_time_ = common::Time(0);
54  this->height_ = 0;
55  this->width_ = 0;
56  this->skip_ = 0;
57  this->format_ = "";
58  this->initialized_ = false;
59 }
60 
62  gazebo_plugins::GazeboRosCameraConfig &config, uint32_t level)
63 {
64  if (this->initialized_)
65  {
66  ROS_INFO_NAMED("camera_utils", "Reconfigure request for the gazebo ros camera_: %s. New rate: %.2f",
67  this->camera_name_.c_str(), config.imager_rate);
68  this->parentSensor_->SetUpdateRate(config.imager_rate);
69  }
70 }
71 
73 // Destructor
75 {
76  this->parentSensor_->SetActive(false);
77  this->rosnode_->shutdown();
78  this->camera_queue_.clear();
79  this->camera_queue_.disable();
80  this->callback_queue_thread_.join();
81  delete this->rosnode_;
82 }
83 
85 // Load the controller
86 void GazeboRosCameraUtils::Load(sensors::SensorPtr _parent,
87  sdf::ElementPtr _sdf,
88  const std::string &_camera_name_suffix,
89  double _hack_baseline)
90 {
91  // default Load:
92  // provide _camera_name_suffix to prevent LoadThread() creating the ros::NodeHandle with
93  //an incomplete this->camera_name_ namespace. There was a race condition when the _camera_name_suffix
94  //was appended in this function.
95  this->Load(_parent, _sdf, _camera_name_suffix);
96 
97  // overwrite hack baseline if specified at load
98  // example usage in gazebo_ros_multicamera
99  this->hack_baseline_ = _hack_baseline;
100 }
101 
103 // Load the controller
104 void GazeboRosCameraUtils::Load(sensors::SensorPtr _parent,
105  sdf::ElementPtr _sdf,
106  const std::string &_camera_name_suffix)
107 {
108  // Get the world name.
109  std::string world_name = _parent->WorldName();
110 
111  // Get the world_
112  this->world_ = physics::get_world(world_name);
113 
114  // save pointers
115  this->sdf = _sdf;
116 
117  // maintain for one more release for backwards compatibility with
118  // pr2_gazebo_plugins
119  this->world = this->world_;
120 
121  std::stringstream ss;
122  this->robot_namespace_ = GetRobotNamespace(_parent, _sdf, "Camera");
123 
124  this->image_topic_name_ = "image_raw";
125  if (this->sdf->HasElement("imageTopicName"))
126  this->image_topic_name_ = this->sdf->Get<std::string>("imageTopicName");
127 
128  this->trigger_topic_name_ = "image_trigger";
129  if (this->sdf->HasElement("triggerTopicName"))
130  this->trigger_topic_name_ = this->sdf->Get<std::string>("triggerTopicName");
131 
132  this->camera_info_topic_name_ = "camera_info";
133  if (this->sdf->HasElement("cameraInfoTopicName"))
135  this->sdf->Get<std::string>("cameraInfoTopicName");
136 
137  if (!this->sdf->HasElement("cameraName"))
138  ROS_DEBUG_NAMED("camera_utils", "Camera plugin missing <cameraName>, default to empty");
139  else
140  this->camera_name_ = this->sdf->Get<std::string>("cameraName");
141 
142  // overwrite camera suffix
143  // example usage in gazebo_ros_multicamera
144  this->camera_name_ += _camera_name_suffix;
145 
146  if (!this->sdf->HasElement("frameName"))
147  ROS_DEBUG_NAMED("camera_utils", "Camera plugin missing <frameName>, defaults to /world");
148  else
149  this->frame_name_ = this->sdf->Get<std::string>("frameName");
150 
151  if (!this->sdf->HasElement("updateRate"))
152  {
153  ROS_DEBUG_NAMED("camera_utils", "Camera plugin missing <updateRate>, defaults to unlimited (0).");
154  this->update_rate_ = 0;
155  }
156  else
157  this->update_rate_ = this->sdf->Get<double>("updateRate");
158 
159  if (!this->sdf->HasElement("CxPrime"))
160  {
161  ROS_DEBUG_NAMED("camera_utils", "Camera plugin missing <CxPrime>, defaults to 0");
162  this->cx_prime_ = 0;
163  }
164  else
165  this->cx_prime_ = this->sdf->Get<double>("CxPrime");
166 
167  if (!this->sdf->HasElement("Cx"))
168  {
169  ROS_DEBUG_NAMED("camera_utils", "Camera plugin missing <Cx>, defaults to 0");
170  this->cx_= 0;
171  }
172  else
173  this->cx_ = this->sdf->Get<double>("Cx");
174 
175  if (!this->sdf->HasElement("Cy"))
176  {
177  ROS_DEBUG_NAMED("camera_utils", "Camera plugin missing <Cy>, defaults to 0");
178  this->cy_= 0;
179  }
180  else
181  this->cy_ = this->sdf->Get<double>("Cy");
182 
183  if (!this->sdf->HasElement("focalLength"))
184  {
185  ROS_DEBUG_NAMED("camera_utils", "Camera plugin missing <focalLength>, defaults to 0");
186  this->focal_length_= 0;
187  }
188  else
189  this->focal_length_ = this->sdf->Get<double>("focalLength");
190 
191  if (!this->sdf->HasElement("hackBaseline"))
192  {
193  ROS_DEBUG_NAMED("camera_utils", "Camera plugin missing <hackBaseline>, defaults to 0");
194  this->hack_baseline_= 0;
195  }
196  else
197  this->hack_baseline_ = this->sdf->Get<double>("hackBaseline");
198 
199  if (!this->sdf->HasElement("distortionK1"))
200  {
201  ROS_DEBUG_NAMED("camera_utils", "Camera plugin missing <distortionK1>, defaults to 0");
202  this->distortion_k1_= 0;
203  }
204  else
205  this->distortion_k1_ = this->sdf->Get<double>("distortionK1");
206 
207  if (!this->sdf->HasElement("distortionK2"))
208  {
209  ROS_DEBUG_NAMED("camera_utils", "Camera plugin missing <distortionK2>, defaults to 0");
210  this->distortion_k2_= 0;
211  }
212  else
213  this->distortion_k2_ = this->sdf->Get<double>("distortionK2");
214 
215  if (!this->sdf->HasElement("distortionK3"))
216  {
217  ROS_DEBUG_NAMED("camera_utils", "Camera plugin missing <distortionK3>, defaults to 0");
218  this->distortion_k3_= 0;
219  }
220  else
221  this->distortion_k3_ = this->sdf->Get<double>("distortionK3");
222 
223  if (!this->sdf->HasElement("distortionT1"))
224  {
225  ROS_DEBUG_NAMED("camera_utils", "Camera plugin missing <distortionT1>, defaults to 0");
226  this->distortion_t1_= 0;
227  }
228  else
229  this->distortion_t1_ = this->sdf->Get<double>("distortionT1");
230 
231  if (!this->sdf->HasElement("distortionT2"))
232  {
233  ROS_DEBUG_NAMED("camera_utils", "Camera plugin missing <distortionT2>, defaults to 0");
234  this->distortion_t2_= 0;
235  }
236  else
237  this->distortion_t2_ = this->sdf->Get<double>("distortionT2");
238 
239  // TODO: make default behavior auto_distortion_ = true
240  if (!this->sdf->HasElement("autoDistortion"))
241  {
242  ROS_DEBUG_NAMED("camera_utils", "Camera plugin missing <autoDistortion>, defaults to false");
243  this->auto_distortion_ = false;
244  }
245  else
246  this->auto_distortion_ = this->sdf->Get<bool>("autoDistortion");
247 
248  if (!this->sdf->HasElement("borderCrop"))
249  {
250  ROS_DEBUG_NAMED("camera_utils", "Camera plugin missing <borderCrop>, defaults to true");
251  this->border_crop_ = true;
252  }
253  else
254  this->border_crop_ = this->sdf->Get<bool>("borderCrop");
255 
256  // initialize shared_ptr members
257  if (!this->image_connect_count_) this->image_connect_count_ = boost::shared_ptr<int>(new int(0));
259  if (!this->was_active_) this->was_active_ = boost::shared_ptr<bool>(new bool(false));
260 
261  // ros callback queue for processing subscription
262  this->deferred_load_thread_ = boost::thread(
263  boost::bind(&GazeboRosCameraUtils::LoadThread, this));
264 }
265 
266 event::ConnectionPtr GazeboRosCameraUtils::OnLoad(const boost::function<void()>& load_function)
267 {
268  return load_event_.Connect(load_function);
269 }
270 
272 // Load the controller
274 {
275  // Exit if no ROS
276  if (!ros::isInitialized())
277  {
278  gzerr << "Not loading plugin since ROS hasn't been "
279  << "properly initialized. Try starting gazebo with ros plugin:\n"
280  << " gazebo -s libgazebo_ros_api_plugin.so\n";
281  return;
282  }
283 
284  // Sensor generation off by default. Must do this before advertising the
285  // associated ROS topics.
286  this->parentSensor_->SetActive(false);
287 
288  this->rosnode_ = new ros::NodeHandle(this->robot_namespace_ + "/" + this->camera_name_);
289 
290  // initialize camera_info_manager
292  *this->rosnode_, this->camera_name_));
293 
295 
296  // resolve tf prefix
297  this->tf_prefix_ = tf::getPrefixParam(*this->rosnode_);
298  this->frame_name_ = tf::resolve(this->tf_prefix_, this->frame_name_);
299 
300  ROS_INFO_NAMED("camera_utils", "Camera Plugin (ns = %s) <tf_prefix_>, set to \"%s\"",
301  this->robot_namespace_.c_str(), this->tf_prefix_.c_str());
302 
303 
304  if (!this->camera_name_.empty())
305  {
306  dyn_srv_ =
307  new dynamic_reconfigure::Server<gazebo_plugins::GazeboRosCameraConfig>
308  (*this->rosnode_);
309  dynamic_reconfigure::Server<gazebo_plugins::GazeboRosCameraConfig>
310  ::CallbackType f =
311  boost::bind(&GazeboRosCameraUtils::configCallback, this, _1, _2);
312  dyn_srv_->setCallback(f);
313  }
314  else
315  {
316  ROS_WARN_NAMED("camera_utils", "dynamic reconfigure is not enabled for this image topic [%s]"
317  " becuase <cameraName> is not specified",
318  this->image_topic_name_.c_str());
319  }
320 
321  this->image_pub_ = this->itnode_->advertise(
322  this->image_topic_name_, 2,
323  boost::bind(&GazeboRosCameraUtils::ImageConnect, this),
324  boost::bind(&GazeboRosCameraUtils::ImageDisconnect, this),
325  ros::VoidPtr(), true);
326 
327  // camera info publish rate will be synchronized to image sensor
328  // publish rates.
329  // If someone connects to camera_info, sensor will be activated
330  // and camera_info will be published alongside image_raw with the
331  // same timestamps. This incurrs additional computational cost when
332  // there are subscribers to camera_info, but better mimics behavior
333  // of image_pipeline.
335  ros::AdvertiseOptions::create<sensor_msgs::CameraInfo>(
336  this->camera_info_topic_name_, 2,
337  boost::bind(&GazeboRosCameraUtils::ImageConnect, this),
338  boost::bind(&GazeboRosCameraUtils::ImageDisconnect, this),
339  ros::VoidPtr(), &this->camera_queue_);
340  this->camera_info_pub_ = this->rosnode_->advertise(cio);
341 
342  /* disabling fov and rate setting for each camera
343  ros::SubscribeOptions zoom_so =
344  ros::SubscribeOptions::create<std_msgs::Float64>(
345  "set_hfov", 1,
346  boost::bind(&GazeboRosCameraUtils::SetHFOV, this, _1),
347  ros::VoidPtr(), &this->camera_queue_);
348  this->cameraHFOVSubscriber_ = this->rosnode_->subscribe(zoom_so);
349 
350  ros::SubscribeOptions rate_so =
351  ros::SubscribeOptions::create<std_msgs::Float64>(
352  "set_update_rate", 1,
353  boost::bind(&GazeboRosCameraUtils::SetUpdateRate, this, _1),
354  ros::VoidPtr(), &this->camera_queue_);
355  this->cameraUpdateRateSubscriber_ = this->rosnode_->subscribe(rate_so);
356  */
357 
358  if (this->CanTriggerCamera())
359  {
360  ros::SubscribeOptions trigger_so =
361  ros::SubscribeOptions::create<std_msgs::Empty>(
362  this->trigger_topic_name_, 1,
363  boost::bind(&GazeboRosCameraUtils::TriggerCameraInternal, this, _1),
364  ros::VoidPtr(), &this->camera_queue_);
365  this->trigger_subscriber_ = this->rosnode_->subscribe(trigger_so);
366  }
367 
368  this->Init();
369 }
370 
372 {
373 }
374 
376 {
377  return false;
378 }
379 
381  const std_msgs::Empty::ConstPtr &dummy)
382 {
383  TriggerCamera();
384 }
385 
387 // Set Horizontal Field of View
388 void GazeboRosCameraUtils::SetHFOV(const std_msgs::Float64::ConstPtr& hfov)
389 {
390 #if GAZEBO_MAJOR_VERSION >= 7
391  this->camera_->SetHFOV(ignition::math::Angle(hfov->data));
392 #else
393  this->camera_->SetHFOV(gazebo::math::Angle(hfov->data));
394 #endif
395 }
396 
398 // Set Update Rate
400  const std_msgs::Float64::ConstPtr& update_rate)
401 {
402  this->parentSensor_->SetUpdateRate(update_rate->data);
403 }
404 
406 // Increment count
408 {
409  boost::mutex::scoped_lock lock(*this->image_connect_count_lock_);
410 
411  // upon first connection, remember if camera was active.
412  if ((*this->image_connect_count_) == 0)
413  *this->was_active_ = this->parentSensor_->IsActive();
414 
415  (*this->image_connect_count_)++;
416 
417  this->parentSensor_->SetActive(true);
418 }
420 // Decrement count
422 {
423  boost::mutex::scoped_lock lock(*this->image_connect_count_lock_);
424 
425  (*this->image_connect_count_)--;
426 
427  // if there are no more subscribers, but camera was active to begin with,
428  // leave it active. Use case: this could be a multicamera, where
429  // each camera shares the same parentSensor_.
430  if ((*this->image_connect_count_) <= 0 && !*this->was_active_)
431  this->parentSensor_->SetActive(false);
432 }
433 
435 // Initialize the controller
437 {
438  // prepare to throttle this plugin at the same rate
439  // ideally, we should invoke a plugin update when the sensor updates,
440  // have to think about how to do that properly later
441  if (this->update_rate_ > 0.0)
442  this->update_period_ = 1.0/this->update_rate_;
443  else
444  this->update_period_ = 0.0;
445 
446  // set buffer size
447  if (this->format_ == "L8" || this->format_ == "L_INT8")
448  {
450  this->skip_ = 1;
451  }
452  else if (this->format_ == "L16" || this->format_ == "L_INT16")
453  {
455  this->skip_ = 2;
456  }
457  else if (this->format_ == "R8G8B8" || this->format_ == "RGB_INT8")
458  {
460  this->skip_ = 3;
461  }
462  else if (this->format_ == "B8G8R8" || this->format_ == "BGR_INT8")
463  {
465  this->skip_ = 3;
466  }
467  else if (this->format_ == "R16G16B16" || this->format_ == "RGB_INT16")
468  {
470  this->skip_ = 6;
471  }
472  else if (this->format_ == "BAYER_RGGB8")
473  {
474  ROS_INFO_NAMED("camera_utils", "bayer simulation maybe computationally expensive.");
476  this->skip_ = 1;
477  }
478  else if (this->format_ == "BAYER_BGGR8")
479  {
480  ROS_INFO_NAMED("camera_utils", "bayer simulation maybe computationally expensive.");
482  this->skip_ = 1;
483  }
484  else if (this->format_ == "BAYER_GBRG8")
485  {
486  ROS_INFO_NAMED("camera_utils", "bayer simulation maybe computationally expensive.");
488  this->skip_ = 1;
489  }
490  else if (this->format_ == "BAYER_GRBG8")
491  {
492  ROS_INFO_NAMED("camera_utils", "bayer simulation maybe computationally expensive.");
494  this->skip_ = 1;
495  }
496  else
497  {
498  ROS_ERROR_NAMED("camera_utils", "Unsupported Gazebo ImageFormat\n");
500  this->skip_ = 3;
501  }
502 
504  if (this->cx_prime_ == 0)
505  this->cx_prime_ = (static_cast<double>(this->width_) + 1.0) /2.0;
506  if (this->cx_ == 0)
507  this->cx_ = (static_cast<double>(this->width_) + 1.0) /2.0;
508  if (this->cy_ == 0)
509  this->cy_ = (static_cast<double>(this->height_) + 1.0) /2.0;
510 
511 
512  double hfov = this->camera_->HFOV().Radian();
513  double computed_focal_length =
514  (static_cast<double>(this->width_)) /
515  (2.0 * tan(hfov / 2.0));
516 
517  if (this->focal_length_ == 0)
518  {
519  this->focal_length_ = computed_focal_length;
520  }
521  else
522  {
523  // check against float precision
524  if (!ignition::math::equal(this->focal_length_, computed_focal_length))
525  {
526  ROS_WARN_NAMED("camera_utils", "The <focal_length>[%f] you have provided for camera_ [%s]"
527  " is inconsistent with specified image_width [%d] and"
528  " HFOV [%f]. Please double check to see that"
529  " focal_length = width_ / (2.0 * tan(HFOV/2.0)),"
530  " the explected focal_lengtth value is [%f],"
531  " please update your camera_ model description accordingly.",
532  this->focal_length_, this->parentSensor_->Name().c_str(),
533  this->width_, hfov,
534  computed_focal_length);
535  }
536  }
537 
538  // fill CameraInfo
539  sensor_msgs::CameraInfo camera_info_msg;
540 
541  camera_info_msg.header.frame_id = this->frame_name_;
542 
543  camera_info_msg.height = this->height_;
544  camera_info_msg.width = this->width_;
545  // distortion
546 #if ROS_VERSION_MINIMUM(1, 3, 0)
547  camera_info_msg.distortion_model = "plumb_bob";
548  camera_info_msg.D.resize(5);
549 #endif
550  // Allow the user to disable automatic cropping (used to remove barrel
551  // distortion black border. The crop can be useful, but also skewes
552  // the lens distortion, making the supplied k and t values incorrect.
553  if(this->camera_->LensDistortion())
554  {
555  this->camera_->LensDistortion()->SetCrop(this->border_crop_);
556  }
557 
558  // Get distortion parameters from gazebo sensor if auto_distortion is true
559  if(this->auto_distortion_)
560  {
561 #if GAZEBO_MAJOR_VERSION >= 8
562  this->distortion_k1_ = this->camera_->LensDistortion()->K1();
563  this->distortion_k2_ = this->camera_->LensDistortion()->K2();
564  this->distortion_k3_ = this->camera_->LensDistortion()->K3();
565  this->distortion_t1_ = this->camera_->LensDistortion()->P1();
566  this->distortion_t2_ = this->camera_->LensDistortion()->P2();
567 #else
568  // TODO: remove version gaurd once gazebo7 is not supported
569  this->distortion_k1_ = this->camera_->LensDistortion()->GetK1();
570  this->distortion_k2_ = this->camera_->LensDistortion()->GetK2();
571  this->distortion_k3_ = this->camera_->LensDistortion()->GetK3();
572  this->distortion_t1_ = this->camera_->LensDistortion()->GetP1();
573  this->distortion_t2_ = this->camera_->LensDistortion()->GetP2();
574 #endif
575  }
576 
577  // D = {k1, k2, t1, t2, k3}, as specified in:
578  // - sensor_msgs/CameraInfo: http://docs.ros.org/api/sensor_msgs/html/msg/CameraInfo.html
579  // - OpenCV: http://docs.opencv.org/2.4/modules/calib3d/doc/camera_calibration_and_3d_reconstruction.html
580  camera_info_msg.D[0] = this->distortion_k1_;
581  camera_info_msg.D[1] = this->distortion_k2_;
582  camera_info_msg.D[2] = this->distortion_t1_;
583  camera_info_msg.D[3] = this->distortion_t2_;
584  camera_info_msg.D[4] = this->distortion_k3_;
585  // original camera_ matrix
586  camera_info_msg.K[0] = this->focal_length_;
587  camera_info_msg.K[1] = 0.0;
588  camera_info_msg.K[2] = this->cx_;
589  camera_info_msg.K[3] = 0.0;
590  camera_info_msg.K[4] = this->focal_length_;
591  camera_info_msg.K[5] = this->cy_;
592  camera_info_msg.K[6] = 0.0;
593  camera_info_msg.K[7] = 0.0;
594  camera_info_msg.K[8] = 1.0;
595  // rectification
596  camera_info_msg.R[0] = 1.0;
597  camera_info_msg.R[1] = 0.0;
598  camera_info_msg.R[2] = 0.0;
599  camera_info_msg.R[3] = 0.0;
600  camera_info_msg.R[4] = 1.0;
601  camera_info_msg.R[5] = 0.0;
602  camera_info_msg.R[6] = 0.0;
603  camera_info_msg.R[7] = 0.0;
604  camera_info_msg.R[8] = 1.0;
605  // camera_ projection matrix (same as camera_ matrix due
606  // to lack of distortion/rectification) (is this generated?)
607  camera_info_msg.P[0] = this->focal_length_;
608  camera_info_msg.P[1] = 0.0;
609  camera_info_msg.P[2] = this->cx_;
610  camera_info_msg.P[3] = -this->focal_length_ * this->hack_baseline_;
611  camera_info_msg.P[4] = 0.0;
612  camera_info_msg.P[5] = this->focal_length_;
613  camera_info_msg.P[6] = this->cy_;
614  camera_info_msg.P[7] = 0.0;
615  camera_info_msg.P[8] = 0.0;
616  camera_info_msg.P[9] = 0.0;
617  camera_info_msg.P[10] = 1.0;
618  camera_info_msg.P[11] = 0.0;
619 
620  this->camera_info_manager_->setCameraInfo(camera_info_msg);
621 
622  // start custom queue for camera_
623  this->callback_queue_thread_ = boost::thread(
624  boost::bind(&GazeboRosCameraUtils::CameraQueueThread, this));
625 
626  load_event_();
627  this->initialized_ = true;
628 }
629 
631 // Put camera_ data to the interface
632 void GazeboRosCameraUtils::PutCameraData(const unsigned char *_src,
633  common::Time &last_update_time)
634 {
635  this->sensor_update_time_ = last_update_time;
636  this->PutCameraData(_src);
637 }
638 
639 void GazeboRosCameraUtils::PutCameraData(const unsigned char *_src)
640 {
641  if (!this->initialized_ || this->height_ <=0 || this->width_ <=0)
642  return;
643 
645  if ((*this->image_connect_count_) > 0)
646  {
647  boost::mutex::scoped_lock lock(this->lock_);
648 
649  // copy data into image
650  this->image_msg_.header.frame_id = this->frame_name_;
651  this->image_msg_.header.stamp.sec = this->sensor_update_time_.sec;
652  this->image_msg_.header.stamp.nsec = this->sensor_update_time_.nsec;
653 
654  // copy from src to image_msg_
655  fillImage(this->image_msg_, this->type_, this->height_, this->width_,
656  this->skip_*this->width_, reinterpret_cast<const void*>(_src));
657 
658  // publish to ros
659  this->image_pub_.publish(this->image_msg_);
660  }
661 }
662 
664 // Put camera_ data to the interface
665 void GazeboRosCameraUtils::PublishCameraInfo(common::Time &last_update_time)
666 {
667  if (!this->initialized_ || this->height_ <=0 || this->width_ <=0)
668  return;
669 
670  this->sensor_update_time_ = last_update_time;
671  this->PublishCameraInfo();
672 }
673 
675 {
676  if (!this->initialized_ || this->height_ <=0 || this->width_ <=0)
677  return;
678 
679  if (this->camera_info_pub_.getNumSubscribers() > 0)
680  {
681  this->sensor_update_time_ = this->parentSensor_->LastMeasurementTime();
682  if (this->sensor_update_time_ - this->last_info_update_time_ >= this->update_period_)
683  {
684  this->PublishCameraInfo(this->camera_info_pub_);
686  }
687  }
688 }
689 
691  ros::Publisher camera_info_publisher)
692 {
693  sensor_msgs::CameraInfo camera_info_msg = camera_info_manager_->getCameraInfo();
694 
695  camera_info_msg.header.stamp.sec = this->sensor_update_time_.sec;
696  camera_info_msg.header.stamp.nsec = this->sensor_update_time_.nsec;
697 
698  camera_info_publisher.publish(camera_info_msg);
699 }
700 
701 
703 // Put camera_ data to the interface
705 {
706  static const double timeout = 0.001;
707 
708  while (this->rosnode_->ok())
709  {
712  }
713 }
714 }
gazebo::GazeboRosCameraUtils::ImageConnect
void ImageConnect()
Definition: gazebo_ros_camera_utils.cpp:407
gazebo::GazeboRosCameraUtils::initialized_
bool initialized_
True if camera util is initialized.
Definition: gazebo_ros_camera_utils.h:224
gazebo::GazeboRosCameraUtils::itnode_
image_transport::ImageTransport * itnode_
Definition: gazebo_ros_camera_utils.h:111
gazebo::GazeboRosCameraUtils::image_pub_
image_transport::Publisher image_pub_
Definition: gazebo_ros_camera_utils.h:110
sensor_msgs::image_encodings::BAYER_RGGB8
const std::string BAYER_RGGB8
fill_image.h
gazebo::GazeboRosCameraUtils::border_crop_
bool border_crop_
Definition: gazebo_ros_camera_utils.h:160
gazebo::GazeboRosCameraUtils::LoadThread
void LoadThread()
Definition: gazebo_ros_camera_utils.cpp:273
ros::Publisher
image_transport::ImageTransport
boost::shared_ptr< int >
gazebo::GazeboRosCameraUtils::parentSensor_
sensors::SensorPtr parentSensor_
Definition: gazebo_ros_camera_utils.h:193
gazebo::GazeboRosCameraUtils::ImageDisconnect
void ImageDisconnect()
Definition: gazebo_ros_camera_utils.cpp:421
gazebo
gazebo::GazeboRosCameraUtils::CanTriggerCamera
virtual bool CanTriggerCamera()
Definition: gazebo_ros_camera_utils.cpp:375
gazebo::GazeboRosCameraUtils::callback_queue_thread_
boost::thread callback_queue_thread_
Definition: gazebo_ros_camera_utils.h:186
ros::CallbackQueue::clear
void clear()
gazebo::GazeboRosCameraUtils::PutCameraData
void PutCameraData(const unsigned char *_src)
Put camera data to the ROS topic.
Definition: gazebo_ros_camera_utils.cpp:639
gazebo::GazeboRosCameraUtils::sdf
sdf::ElementPtr sdf
Definition: gazebo_ros_camera_utils.h:207
camera_info_manager.h
gazebo::GazeboRosCameraUtils::camera_info_pub_
ros::Publisher camera_info_pub_
camera info
Definition: gazebo_ros_camera_utils.h:136
gazebo::GazeboRosCameraUtils::cx_
double cx_
Definition: gazebo_ros_camera_utils.h:149
gazebo::GazeboRosCameraUtils::load_event_
event::EventT< void()> load_event_
Definition: gazebo_ros_camera_utils.h:210
sensor_msgs::image_encodings::BAYER_GBRG8
const std::string BAYER_GBRG8
tf::resolve
std::string resolve(const std::string &prefix, const std::string &frame_name)
gazebo::GazeboRosCameraUtils::last_update_time_
common::Time last_update_time_
Definition: gazebo_ros_camera_utils.h:146
gazebo::GazeboRosCameraUtils::focal_length_
double focal_length_
Definition: gazebo_ros_camera_utils.h:151
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
gazebo::GazeboRosCameraUtils::distortion_t2_
double distortion_t2_
Definition: gazebo_ros_camera_utils.h:157
gazebo::GazeboRosCameraUtils::SetUpdateRate
void SetUpdateRate(const std_msgs::Float64::ConstPtr &update_rate)
Definition: gazebo_ros_camera_utils.cpp:399
gazebo::GazeboRosCameraUtils::image_topic_name_
std::string image_topic_name_
ROS image topic name.
Definition: gazebo_ros_camera_utils.h:126
gazebo::GazeboRosCameraUtils::width_
unsigned int width_
Definition: gazebo_ros_camera_utils.h:190
sensor_msgs::image_encodings::RGB8
const std::string RGB8
gazebo::GazeboRosCameraUtils::world
physics::WorldPtr world
Definition: gazebo_ros_camera_utils.h:204
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
gazebo::GazeboRosCameraUtils::rosnode_
ros::NodeHandle * rosnode_
A pointer to the ROS node. A node will be instantiated if it does not exist.
Definition: gazebo_ros_camera_utils.h:109
ros::AdvertiseOptions
f
f
image_transport::ImageTransport::advertise
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
gazebo::GazeboRosCameraUtils::last_info_update_time_
common::Time last_info_update_time_
Definition: gazebo_ros_camera_utils.h:138
gazebo::GazeboRosCameraUtils::hack_baseline_
double hack_baseline_
Definition: gazebo_ros_camera_utils.h:152
gazebo::GazeboRosCameraUtils::robot_namespace_
std::string robot_namespace_
for setting ROS name space
Definition: gazebo_ros_camera_utils.h:117
gazebo::GazeboRosCameraUtils::image_connect_count_lock_
boost::shared_ptr< boost::mutex > image_connect_count_lock_
A mutex to lock access to image_connect_count_.
Definition: gazebo_ros_camera_utils.h:94
gazebo::GazeboRosCameraUtils::height_
unsigned int height_
Definition: gazebo_ros_camera_utils.h:190
gazebo::GazeboRosCameraUtils::PublishCameraInfo
void PublishCameraInfo()
Definition: gazebo_ros_camera_utils.cpp:674
gazebo::GazeboRosCameraUtils::type_
std::string type_
size of image buffer
Definition: gazebo_ros_camera_utils.h:170
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
gazebo_ros_camera_utils.h
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
gazebo::GazeboRosCameraUtils::frame_name_
std::string frame_name_
ROS frame transform name to use in the image message header. This should typically match the link nam...
Definition: gazebo_ros_camera_utils.h:142
tf::getPrefixParam
std::string getPrefixParam(ros::NodeHandle &nh)
gazebo::GazeboRosCameraUtils::SetHFOV
void SetHFOV(const std_msgs::Float64::ConstPtr &hfov)
: Camera modification functions
Definition: gazebo_ros_camera_utils.cpp:388
gazebo::GazeboRosCameraUtils::CameraQueueThread
void CameraQueueThread()
Definition: gazebo_ros_camera_utils.cpp:704
sensor_msgs::image_encodings::BAYER_BGGR8
const std::string BAYER_BGGR8
gazebo::GazeboRosCameraUtils::cy_
double cy_
Definition: gazebo_ros_camera_utils.h:150
ros::isInitialized
ROSCPP_DECL bool isInitialized()
gazebo::GazeboRosCameraUtils::TriggerCamera
virtual void TriggerCamera()
Definition: gazebo_ros_camera_utils.cpp:371
gazebo::GazeboRosCameraUtils::image_connect_count_
boost::shared_ptr< int > image_connect_count_
Keep track of number of image connections.
Definition: gazebo_ros_camera_utils.h:92
gazebo::GazeboRosCameraUtils::update_period_
double update_period_
Definition: gazebo_ros_camera_utils.h:145
gazebo::GazeboRosCameraUtils::sensor_update_time_
common::Time sensor_update_time_
Definition: gazebo_ros_camera_utils.h:201
camera_info_manager::CameraInfoManager
gazebo::GazeboRosCameraUtils::GazeboRosCameraUtils
GazeboRosCameraUtils()
Constructor.
Definition: gazebo_ros_camera_utils.cpp:50
gazebo::GazeboRosCameraUtils::distortion_k2_
double distortion_k2_
Definition: gazebo_ros_camera_utils.h:154
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
gazebo::GazeboRosCameraUtils::cx_prime_
double cx_prime_
Definition: gazebo_ros_camera_utils.h:148
gazebo::GazeboRosCameraUtils::trigger_subscriber_
ros::Subscriber trigger_subscriber_
Definition: gazebo_ros_camera_utils.h:218
image_transport::Publisher::publish
void publish(const sensor_msgs::Image &message) const
gazebo::GazeboRosCameraUtils::lock_
boost::mutex lock_
A mutex to lock access to fields that are used in ROS message callbacks.
Definition: gazebo_ros_camera_utils.h:167
image_transport.h
gazebo::GazeboRosCameraUtils::deferred_load_thread_
boost::thread deferred_load_thread_
Definition: gazebo_ros_camera_utils.h:209
gazebo::GazeboRosCameraUtils::configCallback
void configCallback(gazebo_plugins::GazeboRosCameraConfig &config, uint32_t level)
Definition: gazebo_ros_camera_utils.cpp:61
gazebo::GazeboRosCameraUtils::Load
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf, const std::string &_camera_name_suffix="")
Load the plugin.
Definition: gazebo_ros_camera_utils.cpp:104
gazebo::GazeboRosCameraUtils::Init
void Init()
Definition: gazebo_ros_camera_utils.cpp:436
gazebo::GazeboRosCameraUtils::camera_info_manager_
boost::shared_ptr< camera_info_manager::CameraInfoManager > camera_info_manager_
Definition: gazebo_ros_camera_utils.h:162
transform_listener.h
tf.h
gazebo::GazeboRosCameraUtils::distortion_k3_
double distortion_k3_
Definition: gazebo_ros_camera_utils.h:155
ros::NodeHandle::ok
bool ok() const
gazebo::GazeboRosCameraUtils::dyn_srv_
dynamic_reconfigure::Server< gazebo_plugins::GazeboRosCameraConfig > * dyn_srv_
Definition: gazebo_ros_camera_utils.h:180
ros::SubscribeOptions
gazebo::GazeboRosCameraUtils::was_active_
boost::shared_ptr< bool > was_active_
Keep track when we activate this camera through ros subscription, was it already active?...
Definition: gazebo_ros_camera_utils.h:101
gazebo::GazeboRosCameraUtils::auto_distortion_
bool auto_distortion_
Definition: gazebo_ros_camera_utils.h:159
sensor_msgs::image_encodings::MONO8
const std::string MONO8
gazebo::GazeboRosCameraUtils::update_rate_
double update_rate_
update rate of this sensor
Definition: gazebo_ros_camera_utils.h:144
sensor_msgs::image_encodings::MONO16
const std::string MONO16
gazebo::GazeboRosCameraUtils::skip_
int skip_
Definition: gazebo_ros_camera_utils.h:171
gazebo::GazeboRosCameraUtils::camera_name_
std::string camera_name_
ROS camera name.
Definition: gazebo_ros_camera_utils.h:120
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
gazebo::GazeboRosCameraUtils::~GazeboRosCameraUtils
~GazeboRosCameraUtils()
Destructor.
Definition: gazebo_ros_camera_utils.cpp:74
gazebo::GazeboRosCameraUtils::format_
std::string format_
Definition: gazebo_ros_camera_utils.h:191
gazebo::GazeboRosCameraUtils::image_msg_
sensor_msgs::Image image_msg_
ROS image message.
Definition: gazebo_ros_camera_utils.h:114
sensor_msgs::image_encodings::BGR8
const std::string BGR8
gazebo::GazeboRosCameraUtils::world_
physics::WorldPtr world_
Definition: gazebo_ros_camera_utils.h:197
gazebo::GazeboRosCameraUtils::distortion_k1_
double distortion_k1_
Definition: gazebo_ros_camera_utils.h:153
sensor_msgs::image_encodings::BAYER_GRBG8
const std::string BAYER_GRBG8
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
gazebo::GazeboRosCameraUtils::TriggerCameraInternal
void TriggerCameraInternal(const std_msgs::Empty::ConstPtr &dummy)
Definition: gazebo_ros_camera_utils.cpp:380
ros::WallDuration
gazebo::GazeboRosCameraUtils::distortion_t1_
double distortion_t1_
Definition: gazebo_ros_camera_utils.h:156
assert.h
gazebo::GazeboRosCameraUtils::camera_info_topic_name_
std::string camera_info_topic_name_
Definition: gazebo_ros_camera_utils.h:137
ros::NodeHandle::shutdown
void shutdown()
gazebo::GazeboRosCameraUtils::camera_queue_
ros::CallbackQueue camera_queue_
Definition: gazebo_ros_camera_utils.h:184
gazebo::GazeboRosCameraUtils::camera_
rendering::CameraPtr camera_
Definition: gazebo_ros_camera_utils.h:194
gazebo::GetRobotNamespace
std::string GetRobotNamespace(const sensors::SensorPtr &parent, const sdf::ElementPtr &sdf, const char *pInfo=NULL)
Reads the name space tag of a sensor plugin.
Definition: gazebo_ros_utils.h:83
ros::CallbackQueue::callAvailable
void callAvailable()
ros::CallbackQueue::disable
void disable()
ros::NodeHandle
gazebo::GazeboRosCameraUtils::OnLoad
event::ConnectionPtr OnLoad(const boost::function< void()> &)
Definition: gazebo_ros_camera_utils.cpp:266
sensor_msgs::image_encodings::RGB16
const std::string RGB16
gazebo::GazeboRosCameraUtils::tf_prefix_
std::string tf_prefix_
tf prefix
Definition: gazebo_ros_camera_utils.h:123
gazebo::GazeboRosCameraUtils::trigger_topic_name_
std::string trigger_topic_name_
ROS trigger topic name.
Definition: gazebo_ros_camera_utils.h:221


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Nov 23 2023 03:50:28