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  if(this->tf_prefix_.empty()) {
299  this->tf_prefix_ = this->robot_namespace_;
300  boost::trim_right_if(this->tf_prefix_,boost::is_any_of("/"));
301  }
302  this->frame_name_ = tf::resolve(this->tf_prefix_, this->frame_name_);
303 
304  ROS_INFO_NAMED("camera_utils", "Camera Plugin (ns = %s) <tf_prefix_>, set to \"%s\"",
305  this->robot_namespace_.c_str(), this->tf_prefix_.c_str());
306 
307 
308  if (!this->camera_name_.empty())
309  {
310  dyn_srv_ =
311  new dynamic_reconfigure::Server<gazebo_plugins::GazeboRosCameraConfig>
312  (*this->rosnode_);
313  dynamic_reconfigure::Server<gazebo_plugins::GazeboRosCameraConfig>
314  ::CallbackType f =
315  boost::bind(&GazeboRosCameraUtils::configCallback, this, _1, _2);
316  dyn_srv_->setCallback(f);
317  }
318  else
319  {
320  ROS_WARN_NAMED("camera_utils", "dynamic reconfigure is not enabled for this image topic [%s]"
321  " becuase <cameraName> is not specified",
322  this->image_topic_name_.c_str());
323  }
324 
325  this->image_pub_ = this->itnode_->advertise(
326  this->image_topic_name_, 2,
327  boost::bind(&GazeboRosCameraUtils::ImageConnect, this),
328  boost::bind(&GazeboRosCameraUtils::ImageDisconnect, this),
329  ros::VoidPtr(), true);
330 
331  // camera info publish rate will be synchronized to image sensor
332  // publish rates.
333  // If someone connects to camera_info, sensor will be activated
334  // and camera_info will be published alongside image_raw with the
335  // same timestamps. This incurrs additional computational cost when
336  // there are subscribers to camera_info, but better mimics behavior
337  // of image_pipeline.
339  ros::AdvertiseOptions::create<sensor_msgs::CameraInfo>(
340  this->camera_info_topic_name_, 2,
341  boost::bind(&GazeboRosCameraUtils::ImageConnect, this),
342  boost::bind(&GazeboRosCameraUtils::ImageDisconnect, this),
343  ros::VoidPtr(), &this->camera_queue_);
344  this->camera_info_pub_ = this->rosnode_->advertise(cio);
345 
346  /* disabling fov and rate setting for each camera
347  ros::SubscribeOptions zoom_so =
348  ros::SubscribeOptions::create<std_msgs::Float64>(
349  "set_hfov", 1,
350  boost::bind(&GazeboRosCameraUtils::SetHFOV, this, _1),
351  ros::VoidPtr(), &this->camera_queue_);
352  this->cameraHFOVSubscriber_ = this->rosnode_->subscribe(zoom_so);
353 
354  ros::SubscribeOptions rate_so =
355  ros::SubscribeOptions::create<std_msgs::Float64>(
356  "set_update_rate", 1,
357  boost::bind(&GazeboRosCameraUtils::SetUpdateRate, this, _1),
358  ros::VoidPtr(), &this->camera_queue_);
359  this->cameraUpdateRateSubscriber_ = this->rosnode_->subscribe(rate_so);
360  */
361 
362  if (this->CanTriggerCamera())
363  {
364  ros::SubscribeOptions trigger_so =
365  ros::SubscribeOptions::create<std_msgs::Empty>(
366  this->trigger_topic_name_, 1,
367  boost::bind(&GazeboRosCameraUtils::TriggerCameraInternal, this, _1),
368  ros::VoidPtr(), &this->camera_queue_);
369  this->trigger_subscriber_ = this->rosnode_->subscribe(trigger_so);
370  }
371 
372  this->Init();
373 }
374 
376 {
377 }
378 
380 {
381  return false;
382 }
383 
385  const std_msgs::Empty::ConstPtr &dummy)
386 {
387  TriggerCamera();
388 }
389 
391 // Set Horizontal Field of View
392 void GazeboRosCameraUtils::SetHFOV(const std_msgs::Float64::ConstPtr& hfov)
393 {
394 #if GAZEBO_MAJOR_VERSION >= 7
395  this->camera_->SetHFOV(ignition::math::Angle(hfov->data));
396 #else
397  this->camera_->SetHFOV(gazebo::math::Angle(hfov->data));
398 #endif
399 }
400 
402 // Set Update Rate
404  const std_msgs::Float64::ConstPtr& update_rate)
405 {
406  this->parentSensor_->SetUpdateRate(update_rate->data);
407 }
408 
410 // Increment count
412 {
413  boost::mutex::scoped_lock lock(*this->image_connect_count_lock_);
414 
415  // upon first connection, remember if camera was active.
416  if ((*this->image_connect_count_) == 0)
417  *this->was_active_ = this->parentSensor_->IsActive();
418 
419  (*this->image_connect_count_)++;
420 
421  this->parentSensor_->SetActive(true);
422 }
424 // Decrement count
426 {
427  boost::mutex::scoped_lock lock(*this->image_connect_count_lock_);
428 
429  (*this->image_connect_count_)--;
430 
431  // if there are no more subscribers, but camera was active to begin with,
432  // leave it active. Use case: this could be a multicamera, where
433  // each camera shares the same parentSensor_.
434  if ((*this->image_connect_count_) <= 0 && !*this->was_active_)
435  this->parentSensor_->SetActive(false);
436 }
437 
439 // Initialize the controller
441 {
442  // prepare to throttle this plugin at the same rate
443  // ideally, we should invoke a plugin update when the sensor updates,
444  // have to think about how to do that properly later
445  if (this->update_rate_ > 0.0)
446  this->update_period_ = 1.0/this->update_rate_;
447  else
448  this->update_period_ = 0.0;
449 
450  // set buffer size
451  if (this->format_ == "L8" || this->format_ == "L_INT8")
452  {
454  this->skip_ = 1;
455  }
456  else if (this->format_ == "L16" || this->format_ == "L_INT16")
457  {
459  this->skip_ = 2;
460  }
461  else if (this->format_ == "R8G8B8" || this->format_ == "RGB_INT8")
462  {
464  this->skip_ = 3;
465  }
466  else if (this->format_ == "B8G8R8" || this->format_ == "BGR_INT8")
467  {
469  this->skip_ = 3;
470  }
471  else if (this->format_ == "R16G16B16" || this->format_ == "RGB_INT16")
472  {
474  this->skip_ = 6;
475  }
476  else if (this->format_ == "BAYER_RGGB8")
477  {
478  ROS_INFO_NAMED("camera_utils", "bayer simulation maybe computationally expensive.");
480  this->skip_ = 1;
481  }
482  else if (this->format_ == "BAYER_BGGR8")
483  {
484  ROS_INFO_NAMED("camera_utils", "bayer simulation maybe computationally expensive.");
486  this->skip_ = 1;
487  }
488  else if (this->format_ == "BAYER_GBRG8")
489  {
490  ROS_INFO_NAMED("camera_utils", "bayer simulation maybe computationally expensive.");
492  this->skip_ = 1;
493  }
494  else if (this->format_ == "BAYER_GRBG8")
495  {
496  ROS_INFO_NAMED("camera_utils", "bayer simulation maybe computationally expensive.");
498  this->skip_ = 1;
499  }
500  else
501  {
502  ROS_ERROR_NAMED("camera_utils", "Unsupported Gazebo ImageFormat\n");
504  this->skip_ = 3;
505  }
506 
508  if (this->cx_prime_ == 0)
509  this->cx_prime_ = (static_cast<double>(this->width_) + 1.0) /2.0;
510  if (this->cx_ == 0)
511  this->cx_ = (static_cast<double>(this->width_) + 1.0) /2.0;
512  if (this->cy_ == 0)
513  this->cy_ = (static_cast<double>(this->height_) + 1.0) /2.0;
514 
515 
516  double hfov = this->camera_->HFOV().Radian();
517  double computed_focal_length =
518  (static_cast<double>(this->width_)) /
519  (2.0 * tan(hfov / 2.0));
520 
521  if (this->focal_length_ == 0)
522  {
523  this->focal_length_ = computed_focal_length;
524  }
525  else
526  {
527  // check against float precision
528  if (!ignition::math::equal(this->focal_length_, computed_focal_length))
529  {
530  ROS_WARN_NAMED("camera_utils", "The <focal_length>[%f] you have provided for camera_ [%s]"
531  " is inconsistent with specified image_width [%d] and"
532  " HFOV [%f]. Please double check to see that"
533  " focal_length = width_ / (2.0 * tan(HFOV/2.0)),"
534  " the explected focal_lengtth value is [%f],"
535  " please update your camera_ model description accordingly.",
536  this->focal_length_, this->parentSensor_->Name().c_str(),
537  this->width_, hfov,
538  computed_focal_length);
539  }
540  }
541 
542  // fill CameraInfo
543  sensor_msgs::CameraInfo camera_info_msg;
544 
545  camera_info_msg.header.frame_id = this->frame_name_;
546 
547  camera_info_msg.height = this->height_;
548  camera_info_msg.width = this->width_;
549  // distortion
550 #if ROS_VERSION_MINIMUM(1, 3, 0)
551  camera_info_msg.distortion_model = "plumb_bob";
552  camera_info_msg.D.resize(5);
553 #endif
554  // Allow the user to disable automatic cropping (used to remove barrel
555  // distortion black border. The crop can be useful, but also skewes
556  // the lens distortion, making the supplied k and t values incorrect.
557  if(this->camera_->LensDistortion())
558  {
559  this->camera_->LensDistortion()->SetCrop(this->border_crop_);
560  }
561 
562  // Get distortion parameters from gazebo sensor if auto_distortion is true
563  if(this->auto_distortion_)
564  {
565 #if GAZEBO_MAJOR_VERSION >= 8
566  this->distortion_k1_ = this->camera_->LensDistortion()->K1();
567  this->distortion_k2_ = this->camera_->LensDistortion()->K2();
568  this->distortion_k3_ = this->camera_->LensDistortion()->K3();
569  this->distortion_t1_ = this->camera_->LensDistortion()->P1();
570  this->distortion_t2_ = this->camera_->LensDistortion()->P2();
571 #else
572  // TODO: remove version gaurd once gazebo7 is not supported
573  this->distortion_k1_ = this->camera_->LensDistortion()->GetK1();
574  this->distortion_k2_ = this->camera_->LensDistortion()->GetK2();
575  this->distortion_k3_ = this->camera_->LensDistortion()->GetK3();
576  this->distortion_t1_ = this->camera_->LensDistortion()->GetP1();
577  this->distortion_t2_ = this->camera_->LensDistortion()->GetP2();
578 #endif
579  }
580 
581  // D = {k1, k2, t1, t2, k3}, as specified in:
582  // - sensor_msgs/CameraInfo: http://docs.ros.org/api/sensor_msgs/html/msg/CameraInfo.html
583  // - OpenCV: http://docs.opencv.org/2.4/modules/calib3d/doc/camera_calibration_and_3d_reconstruction.html
584  camera_info_msg.D[0] = this->distortion_k1_;
585  camera_info_msg.D[1] = this->distortion_k2_;
586  camera_info_msg.D[2] = this->distortion_t1_;
587  camera_info_msg.D[3] = this->distortion_t2_;
588  camera_info_msg.D[4] = this->distortion_k3_;
589  // original camera_ matrix
590  camera_info_msg.K[0] = this->focal_length_;
591  camera_info_msg.K[1] = 0.0;
592  camera_info_msg.K[2] = this->cx_;
593  camera_info_msg.K[3] = 0.0;
594  camera_info_msg.K[4] = this->focal_length_;
595  camera_info_msg.K[5] = this->cy_;
596  camera_info_msg.K[6] = 0.0;
597  camera_info_msg.K[7] = 0.0;
598  camera_info_msg.K[8] = 1.0;
599  // rectification
600  camera_info_msg.R[0] = 1.0;
601  camera_info_msg.R[1] = 0.0;
602  camera_info_msg.R[2] = 0.0;
603  camera_info_msg.R[3] = 0.0;
604  camera_info_msg.R[4] = 1.0;
605  camera_info_msg.R[5] = 0.0;
606  camera_info_msg.R[6] = 0.0;
607  camera_info_msg.R[7] = 0.0;
608  camera_info_msg.R[8] = 1.0;
609  // camera_ projection matrix (same as camera_ matrix due
610  // to lack of distortion/rectification) (is this generated?)
611  camera_info_msg.P[0] = this->focal_length_;
612  camera_info_msg.P[1] = 0.0;
613  camera_info_msg.P[2] = this->cx_;
614  camera_info_msg.P[3] = -this->focal_length_ * this->hack_baseline_;
615  camera_info_msg.P[4] = 0.0;
616  camera_info_msg.P[5] = this->focal_length_;
617  camera_info_msg.P[6] = this->cy_;
618  camera_info_msg.P[7] = 0.0;
619  camera_info_msg.P[8] = 0.0;
620  camera_info_msg.P[9] = 0.0;
621  camera_info_msg.P[10] = 1.0;
622  camera_info_msg.P[11] = 0.0;
623 
624  this->camera_info_manager_->setCameraInfo(camera_info_msg);
625 
626  // start custom queue for camera_
627  this->callback_queue_thread_ = boost::thread(
628  boost::bind(&GazeboRosCameraUtils::CameraQueueThread, this));
629 
630  load_event_();
631  this->initialized_ = true;
632 }
633 
635 // Put camera_ data to the interface
636 void GazeboRosCameraUtils::PutCameraData(const unsigned char *_src,
637  common::Time &last_update_time)
638 {
639  this->sensor_update_time_ = last_update_time;
640  this->PutCameraData(_src);
641 }
642 
643 void GazeboRosCameraUtils::PutCameraData(const unsigned char *_src)
644 {
645  if (!this->initialized_ || this->height_ <=0 || this->width_ <=0)
646  return;
647 
649  if ((*this->image_connect_count_) > 0)
650  {
651  boost::mutex::scoped_lock lock(this->lock_);
652 
653  // copy data into image
654  this->image_msg_.header.frame_id = this->frame_name_;
655  this->image_msg_.header.stamp.sec = this->sensor_update_time_.sec;
656  this->image_msg_.header.stamp.nsec = this->sensor_update_time_.nsec;
657 
658  // copy from src to image_msg_
659  fillImage(this->image_msg_, this->type_, this->height_, this->width_,
660  this->skip_*this->width_, reinterpret_cast<const void*>(_src));
661 
662  // publish to ros
663  this->image_pub_.publish(this->image_msg_);
664  }
665 }
666 
668 // Put camera_ data to the interface
669 void GazeboRosCameraUtils::PublishCameraInfo(common::Time &last_update_time)
670 {
671  if (!this->initialized_ || this->height_ <=0 || this->width_ <=0)
672  return;
673 
674  this->sensor_update_time_ = last_update_time;
675  this->PublishCameraInfo();
676 }
677 
679 {
680  if (!this->initialized_ || this->height_ <=0 || this->width_ <=0)
681  return;
682 
683  if (this->camera_info_pub_.getNumSubscribers() > 0)
684  {
685  this->sensor_update_time_ = this->parentSensor_->LastMeasurementTime();
686  if (this->sensor_update_time_ - this->last_info_update_time_ >= this->update_period_)
687  {
688  this->PublishCameraInfo(this->camera_info_pub_);
690  }
691  }
692 }
693 
695  ros::Publisher camera_info_publisher)
696 {
697  sensor_msgs::CameraInfo camera_info_msg = camera_info_manager_->getCameraInfo();
698 
699  camera_info_msg.header.stamp.sec = this->sensor_update_time_.sec;
700  camera_info_msg.header.stamp.nsec = this->sensor_update_time_.nsec;
701 
702  camera_info_publisher.publish(camera_info_msg);
703 }
704 
705 
707 // Put camera_ data to the interface
709 {
710  static const double timeout = 0.001;
711 
712  while (this->rosnode_->ok())
713  {
716  }
717 }
718 }
const std::string BAYER_GRBG8
std::string image_topic_name_
ROS image topic name.
#define ROS_INFO_NAMED(name,...)
boost::mutex lock_
A mutex to lock access to fields that are used in ROS message callbacks.
std::string getPrefixParam(ros::NodeHandle &nh)
#define ROS_WARN_NAMED(name,...)
f
dynamic_reconfigure::Server< gazebo_plugins::GazeboRosCameraConfig > * dyn_srv_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
boost::shared_ptr< camera_info_manager::CameraInfoManager > camera_info_manager_
std::string robot_namespace_
for setting ROS name space
ROSCPP_DECL bool isInitialized()
boost::shared_ptr< bool > was_active_
Keep track when we activate this camera through ros subscription, was it already active? resume state when unsubscribed.
image_transport::ImageTransport * itnode_
image_transport::Publisher image_pub_
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf, const std::string &_camera_name_suffix="")
Load the plugin.
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
std::string camera_name_
ROS camera name.
void SetHFOV(const std_msgs::Float64::ConstPtr &hfov)
: Camera modification functions
boost::shared_ptr< int > image_connect_count_
Keep track of number of image connections.
const std::string BAYER_GBRG8
void TriggerCameraInternal(const std_msgs::Empty::ConstPtr &dummy)
std::string resolve(const std::string &prefix, const std::string &frame_name)
sensor_msgs::Image image_msg_
ROS image message.
#define ROS_DEBUG_NAMED(name,...)
ros::Publisher camera_info_pub_
camera info
void publish(const boost::shared_ptr< M > &message) const
event::ConnectionPtr OnLoad(const boost::function< void()> &)
bool initialized_
True if camera util is initialized.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
double update_rate_
update rate of this sensor
const std::string MONO16
std::string frame_name_
ROS frame transform name to use in the image message header. This should typically match the link nam...
void publish(const sensor_msgs::Image &message) const
void PutCameraData(const unsigned char *_src)
Put camera data to the ROS topic.
const std::string BAYER_BGGR8
void SetUpdateRate(const std_msgs::Float64::ConstPtr &update_rate)
ros::NodeHandle * rosnode_
A pointer to the ROS node. A node will be instantiated if it does not exist.
std::string trigger_topic_name_
ROS trigger topic name.
#define ROS_ERROR_NAMED(name,...)
void configCallback(gazebo_plugins::GazeboRosCameraConfig &config, uint32_t level)
const std::string BAYER_RGGB8
std::string GetRobotNamespace(const sensors::SensorPtr &parent, const sdf::ElementPtr &sdf, const char *pInfo=NULL)
Reads the name space tag of a sensor plugin.
uint32_t getNumSubscribers() const
bool ok() const
std::string type_
size of image buffer
boost::shared_ptr< void > VoidPtr
boost::shared_ptr< boost::mutex > image_connect_count_lock_
A mutex to lock access to image_connect_count_.


gazebo_plugins
Author(s): John Hsu
autogenerated on Wed Aug 24 2022 02:47:52