21 #include <boost/thread/thread.hpp>
22 #include <boost/bind.hpp>
26 #include <sensor_msgs/Image.h>
29 #include <geometry_msgs/Point32.h>
30 #include <sensor_msgs/ChannelFloat32.h>
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>
62 gazebo_plugins::GazeboRosCameraConfig &config, uint32_t level)
66 ROS_INFO_NAMED(
"camera_utils",
"Reconfigure request for the gazebo ros camera_: %s. New rate: %.2f",
88 const std::string &_camera_name_suffix,
89 double _hack_baseline)
95 this->
Load(_parent, _sdf, _camera_name_suffix);
105 sdf::ElementPtr _sdf,
106 const std::string &_camera_name_suffix)
109 std::string world_name = _parent->WorldName();
112 this->
world_ = physics::get_world(world_name);
121 std::stringstream ss;
125 if (this->
sdf->HasElement(
"imageTopicName"))
129 if (this->
sdf->HasElement(
"triggerTopicName"))
130 this->trigger_topic_name_ = this->
sdf->Get<std::string>(
"triggerTopicName");
133 if (this->
sdf->HasElement(
"cameraInfoTopicName"))
135 this->
sdf->Get<std::string>(
"cameraInfoTopicName");
137 if (!this->
sdf->HasElement(
"cameraName"))
138 ROS_DEBUG_NAMED(
"camera_utils",
"Camera plugin missing <cameraName>, default to empty");
146 if (!this->
sdf->HasElement(
"frameName"))
147 ROS_DEBUG_NAMED(
"camera_utils",
"Camera plugin missing <frameName>, defaults to /world");
151 if (!this->
sdf->HasElement(
"updateRate"))
153 ROS_DEBUG_NAMED(
"camera_utils",
"Camera plugin missing <updateRate>, defaults to unlimited (0).");
159 if (!this->
sdf->HasElement(
"CxPrime"))
161 ROS_DEBUG_NAMED(
"camera_utils",
"Camera plugin missing <CxPrime>, defaults to 0");
167 if (!this->
sdf->HasElement(
"Cx"))
169 ROS_DEBUG_NAMED(
"camera_utils",
"Camera plugin missing <Cx>, defaults to 0");
173 this->
cx_ = this->
sdf->Get<
double>(
"Cx");
175 if (!this->
sdf->HasElement(
"Cy"))
177 ROS_DEBUG_NAMED(
"camera_utils",
"Camera plugin missing <Cy>, defaults to 0");
181 this->
cy_ = this->
sdf->Get<
double>(
"Cy");
183 if (!this->
sdf->HasElement(
"focalLength"))
185 ROS_DEBUG_NAMED(
"camera_utils",
"Camera plugin missing <focalLength>, defaults to 0");
191 if (!this->
sdf->HasElement(
"hackBaseline"))
193 ROS_DEBUG_NAMED(
"camera_utils",
"Camera plugin missing <hackBaseline>, defaults to 0");
199 if (!this->
sdf->HasElement(
"distortionK1"))
201 ROS_DEBUG_NAMED(
"camera_utils",
"Camera plugin missing <distortionK1>, defaults to 0");
207 if (!this->
sdf->HasElement(
"distortionK2"))
209 ROS_DEBUG_NAMED(
"camera_utils",
"Camera plugin missing <distortionK2>, defaults to 0");
215 if (!this->
sdf->HasElement(
"distortionK3"))
217 ROS_DEBUG_NAMED(
"camera_utils",
"Camera plugin missing <distortionK3>, defaults to 0");
223 if (!this->
sdf->HasElement(
"distortionT1"))
225 ROS_DEBUG_NAMED(
"camera_utils",
"Camera plugin missing <distortionT1>, defaults to 0");
231 if (!this->
sdf->HasElement(
"distortionT2"))
233 ROS_DEBUG_NAMED(
"camera_utils",
"Camera plugin missing <distortionT2>, defaults to 0");
240 if (!this->
sdf->HasElement(
"autoDistortion"))
242 ROS_DEBUG_NAMED(
"camera_utils",
"Camera plugin missing <autoDistortion>, defaults to false");
248 if (!this->
sdf->HasElement(
"borderCrop"))
250 ROS_DEBUG_NAMED(
"camera_utils",
"Camera plugin missing <borderCrop>, defaults to true");
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";
300 ROS_INFO_NAMED(
"camera_utils",
"Camera Plugin (ns = %s) <tf_prefix_>, set to \"%s\"",
307 new dynamic_reconfigure::Server<gazebo_plugins::GazeboRosCameraConfig>
309 dynamic_reconfigure::Server<gazebo_plugins::GazeboRosCameraConfig>
316 ROS_WARN_NAMED(
"camera_utils",
"dynamic reconfigure is not enabled for this image topic [%s]"
317 " becuase <cameraName> is not specified",
335 ros::AdvertiseOptions::create<sensor_msgs::CameraInfo>(
361 ros::SubscribeOptions::create<std_msgs::Empty>(
381 const std_msgs::Empty::ConstPtr &dummy)
390 #if GAZEBO_MAJOR_VERSION >= 7
391 this->
camera_->SetHFOV(ignition::math::Angle(hfov->data));
393 this->
camera_->SetHFOV(gazebo::math::Angle(hfov->data));
400 const std_msgs::Float64::ConstPtr& update_rate)
457 else if (this->
format_ ==
"R8G8B8" || this->
format_ ==
"RGB_INT8")
462 else if (this->
format_ ==
"B8G8R8" || this->
format_ ==
"BGR_INT8")
467 else if (this->
format_ ==
"R16G16B16" || this->
format_ ==
"RGB_INT16")
472 else if (this->
format_ ==
"BAYER_RGGB8")
474 ROS_INFO_NAMED(
"camera_utils",
"bayer simulation maybe computationally expensive.");
478 else if (this->
format_ ==
"BAYER_BGGR8")
480 ROS_INFO_NAMED(
"camera_utils",
"bayer simulation maybe computationally expensive.");
484 else if (this->
format_ ==
"BAYER_GBRG8")
486 ROS_INFO_NAMED(
"camera_utils",
"bayer simulation maybe computationally expensive.");
490 else if (this->
format_ ==
"BAYER_GRBG8")
492 ROS_INFO_NAMED(
"camera_utils",
"bayer simulation maybe computationally expensive.");
507 this->
cx_ = (
static_cast<double>(this->
width_) + 1.0) /2.0;
509 this->
cy_ = (
static_cast<double>(this->
height_) + 1.0) /2.0;
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));
524 if (!ignition::math::equal(this->
focal_length_, computed_focal_length))
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.",
534 computed_focal_length);
539 sensor_msgs::CameraInfo camera_info_msg;
541 camera_info_msg.header.frame_id = this->
frame_name_;
543 camera_info_msg.height = this->
height_;
544 camera_info_msg.width = this->
width_;
546 #if ROS_VERSION_MINIMUM(1, 3, 0)
547 camera_info_msg.distortion_model =
"plumb_bob";
548 camera_info_msg.D.resize(5);
553 if(this->
camera_->LensDistortion())
561 #if GAZEBO_MAJOR_VERSION >= 8
587 camera_info_msg.K[1] = 0.0;
588 camera_info_msg.K[2] = this->
cx_;
589 camera_info_msg.K[3] = 0.0;
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;
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;
608 camera_info_msg.P[1] = 0.0;
609 camera_info_msg.P[2] = this->
cx_;
611 camera_info_msg.P[4] = 0.0;
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;
633 common::Time &last_update_time)
647 boost::mutex::scoped_lock lock(this->
lock_);
656 this->
skip_*this->
width_,
reinterpret_cast<const void*
>(_src));
698 camera_info_publisher.
publish(camera_info_msg);
706 static const double timeout = 0.001;