30 #include <gazebo/physics/World.hh>
31 #include <gazebo/physics/HingeJoint.hh>
32 #include <gazebo/sensors/Sensor.hh>
33 #include <gazebo/common/Exception.hh>
34 #include <gazebo/sensors/CameraSensor.hh>
35 #include <gazebo/sensors/SensorTypes.hh>
36 #include <gazebo/rendering/Camera.hh>
38 #ifdef ENABLE_PROFILER
39 #include <ignition/common/Profiler.hh>
43 #include <sdf/Param.hh>
45 #include <sensor_msgs/Image.h>
46 #include <sensor_msgs/CameraInfo.h>
49 #include <sensor_msgs/RegionOfInterest.h>
51 #include <opencv2/highgui.hpp>
53 #include <boost/scoped_ptr.hpp>
54 #include <boost/bind.hpp>
55 #include <boost/tokenizer.hpp>
56 #include <boost/thread.hpp>
57 #include <boost/thread/recursive_mutex.hpp>
84 CameraPlugin::Load(_parent, _sdf);
86 this->
width_ = this->width;
88 this->
depth_ = this->depth;
107 this->
mode_ =
"streaming";
112 if (this->
mode_ ==
"polled")
116 else if (this->
mode_ ==
"streaming")
122 ROS_ERROR_NAMED(
"prosilica",
"trigger_mode is invalid: %s, using streaming mode",this->
mode_.c_str());
129 unsigned int _width,
unsigned int _height,
unsigned int _depth,
130 const std::string &_format)
132 #ifdef ENABLE_PROFILER
133 IGN_PROFILE(
"GazeboRosProsilica::OnNewImageFrame");
136 this->
mode_ =
"streaming";
140 common::Time sensor_update_time = this->
parentSensor_->LastMeasurementTime();
144 if (!this->parentSensor->IsActive())
148 this->parentSensor->SetActive(
true);
154 if (this->
mode_ ==
"streaming")
160 #ifdef ENABLE_PROFILER
161 IGN_PROFILE_BEGIN(
"PutCameraData");
164 #ifdef ENABLE_PROFILER
166 IGN_PROFILE_BEGIN(
"PublishCameraInfo");
169 #ifdef ENABLE_PROFILER
184 polled_camera::GetPolledImage::Response& rsp,
185 sensor_msgs::Image& image, sensor_msgs::CameraInfo& info)
188 this->
mode_ =
"streaming";
194 if (this->
mode_ !=
"polled")
197 rsp.status_message =
"Camera is not in triggered mode";
201 if (req.binning_x > 1 || req.binning_y > 1)
204 rsp.status_message =
"Gazebo Prosilica plugin does not support binning";
209 if (req.roi.x_offset <= 0 || req.roi.y_offset <= 0 || req.roi.width <= 0 || req.roi.height <= 0)
211 req.roi.x_offset = 0;
212 req.roi.y_offset = 0;
213 req.roi.width = this->
width_;
214 req.roi.height = this->height;
216 const unsigned char *src = NULL;
217 ROS_ERROR_NAMED(
"prosilica",
"roidebug %d %d %d %d", req.roi.x_offset, req.roi.y_offset, req.roi.width, req.roi.height);
227 src = this->parentSensor->Camera()->ImageData(0);
236 common::Time roiLastRenderTime = this->
parentSensor_->LastMeasurementTime();
243 #if ROS_VERSION_MINIMUM(1, 3, 0)
290 common::Time lastRenderTime = this->
parentSensor_->LastMeasurementTime();
291 this->
image_msg_.header.stamp.sec = lastRenderTime.sec;
292 this->
image_msg_.header.stamp.nsec = lastRenderTime.nsec;
314 common::Time roiLastRenderTime = this->
parentSensor_->LastMeasurementTime();
315 this->
roiImageMsg->header.stamp.sec = roiLastRenderTime.sec;
316 this->
roiImageMsg->header.stamp.nsec = roiLastRenderTime.nsec;
329 cv::Mat roi(img_bridge_->image,
330 cv::Rect(req.roi.x_offset, req.roi.y_offset,
331 req.roi.width, req.roi.height));
332 img_bridge_->image = roi;
339 std::this_thread::sleep_for(std::chrono::microseconds(100000));