-
Notifications
You must be signed in to change notification settings - Fork 776
/
gazebo_ros_depth_camera.cpp
538 lines (463 loc) · 18.3 KB
/
gazebo_ros_depth_camera.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
/*
* Copyright 2013 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/
/*
Desc: GazeboRosDepthCamera plugin for simulating cameras in Gazebo
Author: John Hsu
Date: 24 Sept 2008
*/
#include <algorithm>
#include <assert.h>
#include <boost/thread/thread.hpp>
#include <boost/bind.hpp>
#include <gazebo_plugins/gazebo_ros_depth_camera.h>
#include <gazebo/sensors/Sensor.hh>
#include <sdf/sdf.hh>
#include <gazebo/sensors/SensorTypes.hh>
#include <sensor_msgs/point_cloud2_iterator.h>
#include <tf/tf.h>
namespace gazebo
{
// Register this plugin with the simulator
GZ_REGISTER_SENSOR_PLUGIN(GazeboRosDepthCamera)
////////////////////////////////////////////////////////////////////////////////
// Constructor
GazeboRosDepthCamera::GazeboRosDepthCamera()
{
this->point_cloud_connect_count_ = 0;
this->depth_image_connect_count_ = 0;
this->depth_info_connect_count_ = 0;
this->last_depth_image_camera_info_update_time_ = common::Time(0);
}
////////////////////////////////////////////////////////////////////////////////
// Destructor
GazeboRosDepthCamera::~GazeboRosDepthCamera()
{
}
////////////////////////////////////////////////////////////////////////////////
// Load the controller
void GazeboRosDepthCamera::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
{
DepthCameraPlugin::Load(_parent, _sdf);
// Make sure the ROS node for Gazebo has already been initialized
if (!ros::isInitialized())
{
ROS_FATAL_STREAM_NAMED("depth_camera", "A ROS node for Gazebo has not been initialized, unable to load plugin. "
<< "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
return;
}
// copying from DepthCameraPlugin into GazeboRosCameraUtils
this->parentSensor_ = this->parentSensor;
this->width_ = this->width;
this->height_ = this->height;
this->depth_ = this->depth;
this->format_ = this->format;
this->camera_ = this->depthCamera;
// using a different default
if (!_sdf->HasElement("imageTopicName"))
this->image_topic_name_ = "ir/image_raw";
if (!_sdf->HasElement("cameraInfoTopicName"))
this->camera_info_topic_name_ = "ir/camera_info";
// point cloud stuff
if (!_sdf->HasElement("pointCloudTopicName"))
this->point_cloud_topic_name_ = "points";
else
this->point_cloud_topic_name_ = _sdf->GetElement("pointCloudTopicName")->Get<std::string>();
// depth image stuff
if (!_sdf->HasElement("depthImageTopicName"))
this->depth_image_topic_name_ = "depth/image_raw";
else
this->depth_image_topic_name_ = _sdf->GetElement("depthImageTopicName")->Get<std::string>();
if (!_sdf->HasElement("depthImageCameraInfoTopicName"))
this->depth_image_camera_info_topic_name_ = "depth/camera_info";
else
this->depth_image_camera_info_topic_name_ = _sdf->GetElement("depthImageCameraInfoTopicName")->Get<std::string>();
if (!_sdf->HasElement("pointCloudCutoff"))
this->point_cloud_cutoff_ = 0.4;
else
this->point_cloud_cutoff_ = _sdf->GetElement("pointCloudCutoff")->Get<double>();
load_connection_ = GazeboRosCameraUtils::OnLoad(boost::bind(&GazeboRosDepthCamera::Advertise, this));
GazeboRosCameraUtils::Load(_parent, _sdf);
}
void GazeboRosDepthCamera::Advertise()
{
ros::AdvertiseOptions point_cloud_ao =
ros::AdvertiseOptions::create<sensor_msgs::PointCloud2 >(
this->point_cloud_topic_name_,1,
boost::bind( &GazeboRosDepthCamera::PointCloudConnect,this),
boost::bind( &GazeboRosDepthCamera::PointCloudDisconnect,this),
ros::VoidPtr(), &this->camera_queue_);
this->point_cloud_pub_ = this->rosnode_->advertise(point_cloud_ao);
ros::AdvertiseOptions depth_image_ao =
ros::AdvertiseOptions::create< sensor_msgs::Image >(
this->depth_image_topic_name_,1,
boost::bind( &GazeboRosDepthCamera::DepthImageConnect,this),
boost::bind( &GazeboRosDepthCamera::DepthImageDisconnect,this),
ros::VoidPtr(), &this->camera_queue_);
this->depth_image_pub_ = this->rosnode_->advertise(depth_image_ao);
ros::AdvertiseOptions depth_image_camera_info_ao =
ros::AdvertiseOptions::create<sensor_msgs::CameraInfo>(
this->depth_image_camera_info_topic_name_,1,
boost::bind( &GazeboRosDepthCamera::DepthInfoConnect,this),
boost::bind( &GazeboRosDepthCamera::DepthInfoDisconnect,this),
ros::VoidPtr(), &this->camera_queue_);
this->depth_image_camera_info_pub_ = this->rosnode_->advertise(depth_image_camera_info_ao);
}
////////////////////////////////////////////////////////////////////////////////
// Increment count
void GazeboRosDepthCamera::PointCloudConnect()
{
this->point_cloud_connect_count_++;
(*this->image_connect_count_)++;
this->parentSensor->SetActive(true);
}
////////////////////////////////////////////////////////////////////////////////
// Decrement count
void GazeboRosDepthCamera::PointCloudDisconnect()
{
this->point_cloud_connect_count_--;
(*this->image_connect_count_)--;
if (this->point_cloud_connect_count_ <= 0)
this->parentSensor->SetActive(false);
}
////////////////////////////////////////////////////////////////////////////////
// Increment count
void GazeboRosDepthCamera::DepthImageConnect()
{
this->depth_image_connect_count_++;
this->parentSensor->SetActive(true);
}
////////////////////////////////////////////////////////////////////////////////
// Decrement count
void GazeboRosDepthCamera::DepthImageDisconnect()
{
this->depth_image_connect_count_--;
}
////////////////////////////////////////////////////////////////////////////////
// Increment count
void GazeboRosDepthCamera::DepthInfoConnect()
{
this->depth_info_connect_count_++;
}
////////////////////////////////////////////////////////////////////////////////
// Decrement count
void GazeboRosDepthCamera::DepthInfoDisconnect()
{
this->depth_info_connect_count_--;
}
////////////////////////////////////////////////////////////////////////////////
// Update the controller
void GazeboRosDepthCamera::OnNewDepthFrame(const float *_image,
unsigned int _width, unsigned int _height, unsigned int _depth,
const std::string &_format)
{
if (!this->initialized_ || this->height_ <=0 || this->width_ <=0)
return;
this->depth_sensor_update_time_ = this->parentSensor->LastMeasurementTime();
if (this->parentSensor->IsActive())
{
if (this->point_cloud_connect_count_ <= 0 &&
this->depth_image_connect_count_ <= 0 &&
(*this->image_connect_count_) <= 0)
{
this->parentSensor->SetActive(false);
}
else
{
if (this->point_cloud_connect_count_ > 0)
this->FillPointdCloud(_image);
if (this->depth_image_connect_count_ > 0)
this->FillDepthImage(_image);
}
}
else
{
if (this->point_cloud_connect_count_ > 0 ||
this->depth_image_connect_count_ <= 0)
// do this first so there's chance for sensor to run 1 frame after activate
this->parentSensor->SetActive(true);
}
PublishCameraInfo();
}
///////////////////////////////////////////////////////////////////////////////
// Update the controller
void GazeboRosDepthCamera::OnNewRGBPointCloud(const float *_pcd,
unsigned int _width, unsigned int _height, unsigned int _depth,
const std::string &_format)
{
if (!this->initialized_ || this->height_ <=0 || this->width_ <=0)
return;
this->depth_sensor_update_time_ = this->parentSensor->LastMeasurementTime();
if (!this->parentSensor->IsActive())
{
if (this->point_cloud_connect_count_ > 0)
// do this first so there's chance for sensor to run 1 frame after activate
this->parentSensor->SetActive(true);
}
else
{
if (this->point_cloud_connect_count_ > 0)
{
this->lock_.lock();
this->point_cloud_msg_.header.frame_id = this->frame_name_;
this->point_cloud_msg_.header.stamp.sec = this->depth_sensor_update_time_.sec;
this->point_cloud_msg_.header.stamp.nsec = this->depth_sensor_update_time_.nsec;
this->point_cloud_msg_.width = this->width;
this->point_cloud_msg_.height = this->height;
this->point_cloud_msg_.row_step = this->point_cloud_msg_.point_step * this->width;
sensor_msgs::PointCloud2Modifier pcd_modifier(point_cloud_msg_);
pcd_modifier.setPointCloud2FieldsByString(2, "xyz", "rgb");
pcd_modifier.resize(_width*_height);
point_cloud_msg_.is_dense = true;
sensor_msgs::PointCloud2Iterator<float> iter_x(point_cloud_msg_, "x");
sensor_msgs::PointCloud2Iterator<float> iter_y(point_cloud_msg_, "y");
sensor_msgs::PointCloud2Iterator<float> iter_z(point_cloud_msg_, "z");
sensor_msgs::PointCloud2Iterator<float> iter_rgb(point_cloud_msg_, "rgb");
for (unsigned int i = 0; i < _width; i++)
{
for (unsigned int j = 0; j < _height; j++, ++iter_x, ++iter_y, ++iter_z, ++iter_rgb)
{
unsigned int index = (j * _width) + i;
*iter_x = _pcd[4 * index];
*iter_y = _pcd[4 * index + 1];
*iter_z = _pcd[4 * index + 2];
*iter_rgb = _pcd[4 * index + 3];
if (i == _width /2 && j == _height / 2)
{
uint32_t rgb = *reinterpret_cast<int*>(&(*iter_rgb));
uint8_t r = (rgb >> 16) & 0x0000ff;
uint8_t g = (rgb >> 8) & 0x0000ff;
uint8_t b = (rgb) & 0x0000ff;
std::cerr << (int)r << " " << (int)g << " " << (int)b << "\n";
}
}
}
this->point_cloud_pub_.publish(this->point_cloud_msg_);
this->lock_.unlock();
}
}
}
////////////////////////////////////////////////////////////////////////////////
// Update the controller
void GazeboRosDepthCamera::OnNewImageFrame(const unsigned char *_image,
unsigned int _width, unsigned int _height, unsigned int _depth,
const std::string &_format)
{
if (!this->initialized_ || this->height_ <=0 || this->width_ <=0)
return;
//ROS_ERROR_NAMED("depth_camera", "camera_ new frame %s %s",this->parentSensor_->GetName().c_str(),this->frame_name_.c_str());
this->sensor_update_time_ = this->parentSensor->LastMeasurementTime();
if (!this->parentSensor->IsActive())
{
if ((*this->image_connect_count_) > 0)
// do this first so there's chance for sensor to run 1 frame after activate
this->parentSensor->SetActive(true);
}
else
{
if ((*this->image_connect_count_) > 0)
{
this->PutCameraData(_image);
// TODO(lucasw) publish camera info with depth image
// this->PublishCameraInfo(sensor_update_time);
}
}
}
////////////////////////////////////////////////////////////////////////////////
// Put camera data to the interface
void GazeboRosDepthCamera::FillPointdCloud(const float *_src)
{
this->lock_.lock();
this->point_cloud_msg_.header.frame_id = this->frame_name_;
this->point_cloud_msg_.header.stamp.sec = this->depth_sensor_update_time_.sec;
this->point_cloud_msg_.header.stamp.nsec = this->depth_sensor_update_time_.nsec;
this->point_cloud_msg_.width = this->width;
this->point_cloud_msg_.height = this->height;
this->point_cloud_msg_.row_step = this->point_cloud_msg_.point_step * this->width;
///copy from depth to point cloud message
FillPointCloudHelper(this->point_cloud_msg_,
this->height,
this->width,
this->skip_,
(void*)_src );
this->point_cloud_pub_.publish(this->point_cloud_msg_);
this->lock_.unlock();
}
////////////////////////////////////////////////////////////////////////////////
// Put depth image data to the interface
void GazeboRosDepthCamera::FillDepthImage(const float *_src)
{
this->lock_.lock();
// copy data into image
this->depth_image_msg_.header.frame_id = this->frame_name_;
this->depth_image_msg_.header.stamp.sec = this->depth_sensor_update_time_.sec;
this->depth_image_msg_.header.stamp.nsec = this->depth_sensor_update_time_.nsec;
///copy from depth to depth image message
FillDepthImageHelper(this->depth_image_msg_,
this->height,
this->width,
this->skip_,
(void*)_src );
this->depth_image_pub_.publish(this->depth_image_msg_);
this->lock_.unlock();
}
// Fill depth information
bool GazeboRosDepthCamera::FillPointCloudHelper(
sensor_msgs::PointCloud2 &point_cloud_msg,
uint32_t rows_arg, uint32_t cols_arg,
uint32_t step_arg, void* data_arg)
{
sensor_msgs::PointCloud2Modifier pcd_modifier(point_cloud_msg);
pcd_modifier.setPointCloud2FieldsByString(2, "xyz", "rgb");
pcd_modifier.resize(rows_arg*cols_arg);
sensor_msgs::PointCloud2Iterator<float> iter_x(point_cloud_msg_, "x");
sensor_msgs::PointCloud2Iterator<float> iter_y(point_cloud_msg_, "y");
sensor_msgs::PointCloud2Iterator<float> iter_z(point_cloud_msg_, "z");
sensor_msgs::PointCloud2Iterator<uint8_t> iter_rgb(point_cloud_msg_, "rgb");
point_cloud_msg.is_dense = true;
float* toCopyFrom = (float*)data_arg;
int index = 0;
double hfov = this->parentSensor->DepthCamera()->HFOV().Radian();
double fl = ((double)this->width) / (2.0 *tan(hfov/2.0));
// convert depth to point cloud
for (uint32_t j=0; j<rows_arg; j++)
{
double pAngle;
if (rows_arg>1) pAngle = atan2( (double)j - 0.5*(double)(rows_arg-1), fl);
else pAngle = 0.0;
for (uint32_t i=0; i<cols_arg; i++, ++iter_x, ++iter_y, ++iter_z, ++iter_rgb)
{
double yAngle;
if (cols_arg>1) yAngle = atan2( (double)i - 0.5*(double)(cols_arg-1), fl);
else yAngle = 0.0;
double depth = toCopyFrom[index++];
// in optical frame
// hardcoded rotation rpy(-M_PI/2, 0, -M_PI/2) is built-in
// to urdf, where the *_optical_frame should have above relative
// rotation from the physical camera *_frame
*iter_x = depth * tan(yAngle);
*iter_y = depth * tan(pAngle);
if(depth > this->point_cloud_cutoff_)
{
*iter_z = depth;
}
else //point in the unseeable range
{
*iter_x = *iter_y = *iter_z = std::numeric_limits<float>::quiet_NaN ();
point_cloud_msg.is_dense = false;
}
// put image color data for each point
uint8_t* image_src = (uint8_t*)(&(this->image_msg_.data[0]));
if (this->image_msg_.data.size() == rows_arg*cols_arg*3)
{
// color
iter_rgb[0] = image_src[i*3+j*cols_arg*3+0];
iter_rgb[1] = image_src[i*3+j*cols_arg*3+1];
iter_rgb[2] = image_src[i*3+j*cols_arg*3+2];
}
else if (this->image_msg_.data.size() == rows_arg*cols_arg)
{
// mono (or bayer? @todo; fix for bayer)
iter_rgb[0] = image_src[i+j*cols_arg];
iter_rgb[1] = image_src[i+j*cols_arg];
iter_rgb[2] = image_src[i+j*cols_arg];
}
else
{
// no image
iter_rgb[0] = 0;
iter_rgb[1] = 0;
iter_rgb[2] = 0;
}
}
}
return true;
}
// Fill depth information
bool GazeboRosDepthCamera::FillDepthImageHelper(
sensor_msgs::Image& image_msg,
uint32_t rows_arg, uint32_t cols_arg,
uint32_t step_arg, void* data_arg)
{
image_msg.encoding = sensor_msgs::image_encodings::TYPE_32FC1;
image_msg.height = rows_arg;
image_msg.width = cols_arg;
image_msg.step = sizeof(float) * cols_arg;
image_msg.data.resize(rows_arg * cols_arg * sizeof(float));
image_msg.is_bigendian = 0;
const float bad_point = std::numeric_limits<float>::quiet_NaN();
float* dest = (float*)(&(image_msg.data[0]));
float* toCopyFrom = (float*)data_arg;
int index = 0;
// convert depth to point cloud
for (uint32_t j = 0; j < rows_arg; j++)
{
for (uint32_t i = 0; i < cols_arg; i++)
{
float depth = toCopyFrom[index++];
if (depth > this->point_cloud_cutoff_)
{
dest[i + j * cols_arg] = depth;
}
else //point in the unseeable range
{
dest[i + j * cols_arg] = bad_point;
}
}
}
return true;
}
void GazeboRosDepthCamera::PublishCameraInfo()
{
ROS_DEBUG_NAMED("depth_camera", "publishing default camera info, then depth camera info");
GazeboRosCameraUtils::PublishCameraInfo();
if (this->depth_info_connect_count_ > 0)
{
common::Time sensor_update_time = this->parentSensor_->LastMeasurementTime();
this->sensor_update_time_ = sensor_update_time;
if (sensor_update_time - this->last_depth_image_camera_info_update_time_ >= this->update_period_)
{
this->PublishCameraInfo(this->depth_image_camera_info_pub_); // , sensor_update_time);
this->last_depth_image_camera_info_update_time_ = sensor_update_time;
}
}
}
//@todo: publish disparity similar to openni_camera_deprecated/src/nodelets/openni_nodelet.cpp.
/*
#include <stereo_msgs/DisparityImage.h>
pub_disparity_ = comm_nh.advertise<stereo_msgs::DisparityImage > ("depth/disparity", 5, subscriberChanged2, subscriberChanged2);
void GazeboRosDepthCamera::PublishDisparityImage(const DepthImage& depth, ros::Time time)
{
stereo_msgs::DisparityImagePtr disp_msg = boost::make_shared<stereo_msgs::DisparityImage > ();
disp_msg->header.stamp = time;
disp_msg->header.frame_id = device_->isDepthRegistered () ? rgb_frame_id_ : depth_frame_id_;
disp_msg->image.header = disp_msg->header;
disp_msg->image.encoding = sensor_msgs::image_encodings::TYPE_32FC1;
disp_msg->image.height = depth_height_;
disp_msg->image.width = depth_width_;
disp_msg->image.step = disp_msg->image.width * sizeof (float);
disp_msg->image.data.resize (disp_msg->image.height * disp_msg->image.step);
disp_msg->T = depth.getBaseline ();
disp_msg->f = depth.getFocalLength () * depth_width_ / depth.getWidth ();
/// @todo Compute these values from DepthGenerator::GetDeviceMaxDepth() and the like
disp_msg->min_disparity = 0.0;
disp_msg->max_disparity = disp_msg->T * disp_msg->f / 0.3;
disp_msg->delta_d = 0.125;
depth.fillDisparityImage (depth_width_, depth_height_, reinterpret_cast<float*>(&disp_msg->image.data[0]), disp_msg->image.step);
pub_disparity_.publish (disp_msg);
}
*/
}