gazebo_ros_prosilica.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 /*
19  @mainpage
20  Desc: GazeboRosProsilica plugin for simulating Prosilica cameras in Gazebo
21  Author: John Hsu
22  Date: 24 Sept 2008
23 */
24 
25 #include <algorithm>
26 #include <assert.h>
27 
29 
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>
37 
38 #ifdef ENABLE_PROFILER
39 #include <ignition/common/Profiler.hh>
40 #endif
41 
42 #include <sdf/sdf.hh>
43 #include <sdf/Param.hh>
44 
45 #include <sensor_msgs/Image.h>
46 #include <sensor_msgs/CameraInfo.h>
47 #include <sensor_msgs/fill_image.h>
49 #include <sensor_msgs/RegionOfInterest.h>
50 
51 #include <opencv2/highgui.hpp>
52 
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>
58 #include <string>
59 #include <chrono>
60 #include <thread>
61 
62 namespace gazebo
63 {
64 
66 // Constructor
68 {
69 }
70 
72 // Destructor
74 {
75  // Finalize the controller
76  this->poll_srv_.shutdown();
77 }
78 
80 // Load the controller
81 void GazeboRosProsilica::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
82 {
83 
84  CameraPlugin::Load(_parent, _sdf);
85  this->parentSensor_ = this->parentSensor;
86  this->width_ = this->width;
87  this->height_ = this->height;
88  this->depth_ = this->depth;
89  this->format_ = this->format;
90  this->camera_ = this->camera;
91  GazeboRosCameraUtils::Load(_parent, _sdf);
92 
94 }
95 
97 {
98  // camera mode for prosilica:
99  // prosilica::AcquisitionMode mode_; /// @todo Make this property of Camera
100 
101  //ROS_ERROR_NAMED("prosilica", "before trigger_mode %s %s",this->mode_param_name.c_str(),this->mode_.c_str());
102 
103  if (!this->rosnode_->searchParam("trigger_mode",this->mode_param_name))
104  this->mode_param_name = "trigger_mode";
105 
106  if (!this->rosnode_->getParam(this->mode_param_name,this->mode_))
107  this->mode_ = "streaming";
108 
109  ROS_INFO_NAMED("prosilica", "trigger_mode %s %s",this->mode_param_name.c_str(),this->mode_.c_str());
110 
111 
112  if (this->mode_ == "polled")
113  {
115  }
116  else if (this->mode_ == "streaming")
117  {
118  ROS_DEBUG_NAMED("prosilica", "do nothing here,mode: %s",this->mode_.c_str());
119  }
120  else
121  {
122  ROS_ERROR_NAMED("prosilica", "trigger_mode is invalid: %s, using streaming mode",this->mode_.c_str());
123  }
124 }
125 
127 // Update the controller
128 void GazeboRosProsilica::OnNewImageFrame(const unsigned char *_image,
129  unsigned int _width, unsigned int _height, unsigned int _depth,
130  const std::string &_format)
131 {
132 #ifdef ENABLE_PROFILER
133  IGN_PROFILE("GazeboRosProsilica::OnNewImageFrame");
134 #endif
135  if (!this->rosnode_->getParam(this->mode_param_name,this->mode_))
136  this->mode_ = "streaming";
137 
138  // should do nothing except turning camera on/off, as we are using service.
140  common::Time sensor_update_time = this->parentSensor_->LastMeasurementTime();
141 
142  // as long as ros is connected, parent is active
143  //ROS_ERROR_NAMED("prosilica", "debug image count %d",this->image_connect_count_);
144  if (!this->parentSensor->IsActive())
145  {
146  if ((*this->image_connect_count_) > 0)
147  // do this first so there's chance for sensor to run 1 frame after activate
148  this->parentSensor->SetActive(true);
149  }
150  else
151  {
152  //ROS_ERROR_NAMED("prosilica", "camera_ new frame %s %s",this->parentSensor_->Name().c_str(),this->frame_name_.c_str());
153 
154  if (this->mode_ == "streaming")
155  {
156  if ((*this->image_connect_count_) > 0)
157  {
158  if (sensor_update_time - this->last_update_time_ >= this->update_period_)
159  {
160 #ifdef ENABLE_PROFILER
161  IGN_PROFILE_BEGIN("PutCameraData");
162 #endif
163  this->PutCameraData(_image, sensor_update_time);
164 #ifdef ENABLE_PROFILER
165  IGN_PROFILE_END();
166  IGN_PROFILE_BEGIN("PublishCameraInfo");
167 #endif
168  this->PublishCameraInfo(sensor_update_time);
169 #ifdef ENABLE_PROFILER
170  IGN_PROFILE_END();
171 #endif
172  this->last_update_time_ = sensor_update_time;
173  }
174  }
175  }
176 
177  }
178 }
179 
180 
182 // new prosilica interface.
183 void GazeboRosProsilica::pollCallback(polled_camera::GetPolledImage::Request& req,
184  polled_camera::GetPolledImage::Response& rsp,
185  sensor_msgs::Image& image, sensor_msgs::CameraInfo& info)
186 {
187  if (!this->rosnode_->getParam(this->mode_param_name,this->mode_))
188  this->mode_ = "streaming";
189 
193 
194  if (this->mode_ != "polled")
195  {
196  rsp.success = false;
197  rsp.status_message = "Camera is not in triggered mode";
198  return;
199  }
200 
201  if (req.binning_x > 1 || req.binning_y > 1)
202  {
203  rsp.success = false;
204  rsp.status_message = "Gazebo Prosilica plugin does not support binning";
205  return;
206  }
207 
208  // get region from request
209  if (req.roi.x_offset <= 0 || req.roi.y_offset <= 0 || req.roi.width <= 0 || req.roi.height <= 0)
210  {
211  req.roi.x_offset = 0;
212  req.roi.y_offset = 0;
213  req.roi.width = this->width_;
214  req.roi.height = this->height;
215  }
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);
218 
219  // signal sensor to start update
220  (*this->image_connect_count_)++;
221 
222  // wait until an image has been returned
223  while(!src)
224  {
225  {
226  // Get a pointer to image data
227  src = this->parentSensor->Camera()->ImageData(0);
228 
229  if (src)
230  {
231 
232  // fill CameraInfo
233  this->roiCameraInfoMsg = &info;
234  this->roiCameraInfoMsg->header.frame_id = this->frame_name_;
235 
236  common::Time roiLastRenderTime = this->parentSensor_->LastMeasurementTime();
237  this->roiCameraInfoMsg->header.stamp.sec = roiLastRenderTime.sec;
238  this->roiCameraInfoMsg->header.stamp.nsec = roiLastRenderTime.nsec;
239 
240  this->roiCameraInfoMsg->width = req.roi.width; //this->parentSensor->ImageWidth() ;
241  this->roiCameraInfoMsg->height = req.roi.height; //this->parentSensor->ImageHeight();
242  // distortion
243 #if ROS_VERSION_MINIMUM(1, 3, 0)
244  this->roiCameraInfoMsg->distortion_model = "plumb_bob";
245  this->roiCameraInfoMsg->D.resize(5);
246 #endif
247  this->roiCameraInfoMsg->D[0] = this->distortion_k1_;
248  this->roiCameraInfoMsg->D[1] = this->distortion_k2_;
249  this->roiCameraInfoMsg->D[2] = this->distortion_k3_;
250  this->roiCameraInfoMsg->D[3] = this->distortion_t1_;
251  this->roiCameraInfoMsg->D[4] = this->distortion_t2_;
252  // original camera matrix
253  this->roiCameraInfoMsg->K[0] = this->focal_length_;
254  this->roiCameraInfoMsg->K[1] = 0.0;
255  this->roiCameraInfoMsg->K[2] = this->cx_ - req.roi.x_offset;
256  this->roiCameraInfoMsg->K[3] = 0.0;
257  this->roiCameraInfoMsg->K[4] = this->focal_length_;
258  this->roiCameraInfoMsg->K[5] = this->cy_ - req.roi.y_offset;
259  this->roiCameraInfoMsg->K[6] = 0.0;
260  this->roiCameraInfoMsg->K[7] = 0.0;
261  this->roiCameraInfoMsg->K[8] = 1.0;
262  // rectification
263  this->roiCameraInfoMsg->R[0] = 1.0;
264  this->roiCameraInfoMsg->R[1] = 0.0;
265  this->roiCameraInfoMsg->R[2] = 0.0;
266  this->roiCameraInfoMsg->R[3] = 0.0;
267  this->roiCameraInfoMsg->R[4] = 1.0;
268  this->roiCameraInfoMsg->R[5] = 0.0;
269  this->roiCameraInfoMsg->R[6] = 0.0;
270  this->roiCameraInfoMsg->R[7] = 0.0;
271  this->roiCameraInfoMsg->R[8] = 1.0;
272  // camera projection matrix (same as camera matrix due to lack of distortion/rectification) (is this generated?)
273  this->roiCameraInfoMsg->P[0] = this->focal_length_;
274  this->roiCameraInfoMsg->P[1] = 0.0;
275  this->roiCameraInfoMsg->P[2] = this->cx_ - req.roi.x_offset;
276  this->roiCameraInfoMsg->P[3] = -this->focal_length_ * this->hack_baseline_;
277  this->roiCameraInfoMsg->P[4] = 0.0;
278  this->roiCameraInfoMsg->P[5] = this->focal_length_;
279  this->roiCameraInfoMsg->P[6] = this->cy_ - req.roi.y_offset;
280  this->roiCameraInfoMsg->P[7] = 0.0;
281  this->roiCameraInfoMsg->P[8] = 0.0;
282  this->roiCameraInfoMsg->P[9] = 0.0;
283  this->roiCameraInfoMsg->P[10] = 1.0;
284  this->roiCameraInfoMsg->P[11] = 0.0;
286 
287  // copy data into image_msg_, then convert to roiImageMsg(image)
288  this->image_msg_.header.frame_id = this->frame_name_;
289 
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;
293 
294  //unsigned char dst[this->width_*this->height];
295 
297 
298  // copy from src to image_msg_
299  fillImage(this->image_msg_,
300  this->type_,
301  this->height_,
302  this->width_,
303  this->skip_*this->width_,
304  (void*)src );
305 
307 
308  this->image_pub_.publish(this->image_msg_);
309 
310  {
311  // copy data into ROI image
312  this->roiImageMsg = &image;
313  this->roiImageMsg->header.frame_id = this->frame_name_;
314  common::Time roiLastRenderTime = this->parentSensor_->LastMeasurementTime();
315  this->roiImageMsg->header.stamp.sec = roiLastRenderTime.sec;
316  this->roiImageMsg->header.stamp.nsec = roiLastRenderTime.nsec;
317 
318  // convert image_msg_ to a CvImage using cv_bridge
320  img_bridge_ = cv_bridge::toCvCopy(this->image_msg_);
321 
322  // for debug
323  //cvNamedWindow("showme",CV_WINDOW_AUTOSIZE);
324  //cvSetMouseCallback("showme", &GazeboRosProsilica::mouse_cb, this);
325  //cvStartWindowThread();
326  //cvShowImage("showme",img_bridge_.toIpl());
327 
328  // crop image to roi
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;
333 
334  // copy roi'd image into roiImageMsg
335  img_bridge_->toImageMsg(*this->roiImageMsg);
336  }
337  }
338  }
339  std::this_thread::sleep_for(std::chrono::microseconds(100000));
340  }
341  (*this->image_connect_count_)--;
342  rsp.success = true;
343  return;
344 }
345 
346 
347 /*
348 void GazeboRosProsilica::OnStats( const boost::shared_ptr<msgs::WorldStatistics const> &_msg)
349 {
350  this->simTime = msgs::Convert( _msg->sim_time() );
351 
352  ignition::math::Pose3d pose;
353  pose.Pos().X() = 0.5*sin(0.01*this->simTime.Double());
354  gzdbg << "plugin simTime [" << this->simTime.Double() << "] update pose [" << pose.Pos().X() << "]\n";
355 }
356 */
357 
358 // Register this plugin with the simulator
359 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosProsilica)
360 
361 
362 }
gazebo::GazeboRosCameraUtils::image_pub_
image_transport::Publisher image_pub_
Definition: gazebo_ros_camera_utils.h:110
fill_image.h
gazebo::GazeboRosProsilica::pollCallback
void pollCallback(polled_camera::GetPolledImage::Request &req, polled_camera::GetPolledImage::Response &rsp, sensor_msgs::Image &image, sensor_msgs::CameraInfo &info)
Definition: gazebo_ros_prosilica.cpp:183
boost::shared_ptr
gazebo::GazeboRosCameraUtils::parentSensor_
sensors::SensorPtr parentSensor_
Definition: gazebo_ros_camera_utils.h:193
gazebo
gazebo::GazeboRosProsilica::mode_
std::string mode_
Definition: gazebo_ros_prosilica.h:63
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
gazebo::GazeboRosCameraUtils::PutCameraData
void PutCameraData(const unsigned char *_src)
Put camera data to the ROS topic.
Definition: gazebo_ros_camera_utils.cpp:639
gazebo::GazeboRosProsilica::GazeboRosProsilica
GazeboRosProsilica()
Constructor.
Definition: gazebo_ros_prosilica.cpp:67
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::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
gazebo::GazeboRosProsilica::mode_param_name
std::string mode_param_name
Definition: gazebo_ros_prosilica.h:65
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
gazebo::GazeboRosCameraUtils::distortion_t2_
double distortion_t2_
Definition: gazebo_ros_camera_utils.h:157
gazebo::GazeboRosCameraUtils::width_
unsigned int width_
Definition: gazebo_ros_camera_utils.h:190
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
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
diagnostic_updater.h
gazebo::GazeboRosProsilica::Load
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
Load the controller.
Definition: gazebo_ros_prosilica.cpp:81
gazebo::GazeboRosCameraUtils::hack_baseline_
double hack_baseline_
Definition: gazebo_ros_camera_utils.h:152
gazebo::GazeboRosProsilica::pollServiceName
std::string pollServiceName
ROS image topic name.
Definition: gazebo_ros_prosilica.h:84
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::GazeboRosProsilica::Advertise
void Advertise()
Definition: gazebo_ros_prosilica.cpp:96
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,...)
cv_bridge::toCvCopy
CvImagePtr toCvCopy(const sensor_msgs::CompressedImage &source, const std::string &encoding=std::string())
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
gazebo::GazeboRosProsilica
Definition: gazebo_ros_prosilica.h:44
gazebo::GazeboRosCameraUtils::cy_
double cy_
Definition: gazebo_ros_camera_utils.h:150
gazebo::GazeboRosProsilica::poll_srv_
polled_camera::PublicationServer poll_srv_
image_transport
Definition: gazebo_ros_prosilica.h:58
ros::NodeHandle::searchParam
bool searchParam(const std::string &key, std::string &result) const
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_ros_prosilica.h
gazebo::GazeboRosCameraUtils::distortion_k2_
double distortion_k2_
Definition: gazebo_ros_camera_utils.h:154
gazebo::GazeboRosCameraUtils::depth_
unsigned int depth_
Definition: gazebo_ros_camera_utils.h:190
image_transport::Publisher::publish
void publish(const sensor_msgs::Image &message) const
polled_camera::advertise
PublicationServer advertise(ros::NodeHandle &nh, const std::string &service, const PublicationServer::DriverCallback &cb, const ros::VoidPtr &tracked_object=ros::VoidPtr())
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::distortion_k3_
double distortion_k3_
Definition: gazebo_ros_camera_utils.h:155
gazebo::GazeboRosProsilica::load_connection_
event::ConnectionPtr load_connection_
Definition: gazebo_ros_prosilica.h:87
gazebo::GazeboRosProsilica::~GazeboRosProsilica
virtual ~GazeboRosProsilica()
Destructor.
Definition: gazebo_ros_prosilica.cpp:73
gazebo::GazeboRosCameraUtils::skip_
int skip_
Definition: gazebo_ros_camera_utils.h:171
gazebo::GazeboRosProsilica::roiCameraInfoMsg
sensor_msgs::CameraInfo * roiCameraInfoMsg
Definition: gazebo_ros_prosilica.h:81
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
polled_camera::PublicationServer::shutdown
void shutdown()
gazebo::GazeboRosCameraUtils::distortion_k1_
double distortion_k1_
Definition: gazebo_ros_camera_utils.h:153
gazebo::GazeboRosProsilica::OnNewImageFrame
virtual void OnNewImageFrame(const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
Update the controller.
Definition: gazebo_ros_prosilica.cpp:128
gazebo::GazeboRosCameraUtils::distortion_t1_
double distortion_t1_
Definition: gazebo_ros_camera_utils.h:156
assert.h
gazebo::GazeboRosCameraUtils::camera_
rendering::CameraPtr camera_
Definition: gazebo_ros_camera_utils.h:194
gazebo::GazeboRosProsilica::roiImageMsg
sensor_msgs::Image * roiImageMsg
ros message
Definition: gazebo_ros_prosilica.h:80
gazebo::GazeboRosCameraUtils::OnLoad
event::ConnectionPtr OnLoad(const boost::function< void()> &)
Definition: gazebo_ros_camera_utils.cpp:266


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