25 #include <boost/thread/thread.hpp> 26 #include <boost/bind.hpp> 30 #include <gazebo/sensors/Sensor.hh> 32 #include <gazebo/sensors/SensorTypes.hh> 41 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosDepthCamera)
47 this->point_cloud_connect_count_ = 0;
48 this->depth_image_connect_count_ = 0;
49 this->depth_info_connect_count_ = 0;
50 this->last_depth_image_camera_info_update_time_ = common::Time(0);
63 DepthCameraPlugin::Load(_parent, _sdf);
68 ROS_FATAL_STREAM_NAMED(
"depth_camera",
"A ROS node for Gazebo has not been initialized, unable to load plugin. " 69 <<
"Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
75 this->
width_ = this->width;
77 this->
depth_ = this->depth;
79 this->
camera_ = this->depthCamera;
82 if (!_sdf->HasElement(
"imageTopicName"))
84 if (!_sdf->HasElement(
"cameraInfoTopicName"))
88 if (!_sdf->HasElement(
"pointCloudTopicName"))
94 if (!_sdf->HasElement(
"depthImageTopicName"))
99 if (!_sdf->HasElement(
"depthImageCameraInfoTopicName"))
104 if (!_sdf->HasElement(
"pointCloudCutoff"))
116 ros::AdvertiseOptions::create<sensor_msgs::PointCloud2 >(
124 ros::AdvertiseOptions::create< sensor_msgs::Image >(
132 ros::AdvertiseOptions::create<sensor_msgs::CameraInfo>(
147 this->parentSensor->SetActive(
true);
156 this->parentSensor->SetActive(
false);
164 this->parentSensor->SetActive(
true);
189 unsigned int _width,
unsigned int _height,
unsigned int _depth,
190 const std::string &_format)
197 if (this->parentSensor->IsActive())
203 this->parentSensor->SetActive(
false);
219 this->parentSensor->SetActive(
true);
227 unsigned int _width,
unsigned int _height,
unsigned int _depth,
228 const std::string &_format)
235 if (!this->parentSensor->IsActive())
239 this->parentSensor->SetActive(
true);
255 pcd_modifier.
resize(_width*_height);
264 for (
unsigned int i = 0; i < _width; i++)
266 for (
unsigned int j = 0; j < _height; j++, ++iter_x, ++iter_y, ++iter_z, ++iter_rgb)
268 unsigned int index = (j * _width) + i;
269 *iter_x = _pcd[4 * index];
270 *iter_y = _pcd[4 * index + 1];
271 *iter_z = _pcd[4 * index + 2];
272 *iter_rgb = _pcd[4 * index + 3];
273 if (i == _width /2 && j == _height / 2)
275 uint32_t rgb = *
reinterpret_cast<int*
>(&(*iter_rgb));
276 uint8_t r = (rgb >> 16) & 0x0000ff;
277 uint8_t g = (rgb >> 8) & 0x0000ff;
278 uint8_t b = (rgb) & 0x0000ff;
279 std::cerr << (int)r <<
" " << (
int)g <<
" " << (int)b <<
"\n";
285 this->
lock_.unlock();
293 unsigned int _width,
unsigned int _height,
unsigned int _depth,
294 const std::string &_format)
302 if (!this->parentSensor->IsActive())
306 this->parentSensor->SetActive(
true);
341 this->
lock_.unlock();
363 this->
lock_.unlock();
369 sensor_msgs::PointCloud2 &point_cloud_msg,
370 uint32_t rows_arg, uint32_t cols_arg,
371 uint32_t step_arg,
void* data_arg)
375 pcd_modifier.
resize(rows_arg*cols_arg);
382 point_cloud_msg.is_dense =
true;
384 float* toCopyFrom = (
float*)data_arg;
387 double hfov = this->parentSensor->DepthCamera()->HFOV().Radian();
388 double fl = ((double)this->width) / (2.0 *tan(hfov/2.0));
391 for (uint32_t j=0; j<rows_arg; j++)
394 if (rows_arg>1) pAngle = atan2( (
double)j - 0.5*(
double)(rows_arg-1), fl);
397 for (uint32_t i=0; i<cols_arg; i++, ++iter_x, ++iter_y, ++iter_z, ++iter_rgb)
400 if (cols_arg>1) yAngle = atan2( (
double)i - 0.5*(
double)(cols_arg-1), fl);
403 double depth = toCopyFrom[index++];
409 *iter_x = depth * tan(yAngle);
410 *iter_y = depth * tan(pAngle);
417 *iter_x = *iter_y = *iter_z = std::numeric_limits<float>::quiet_NaN ();
418 point_cloud_msg.is_dense =
false;
422 uint8_t* image_src = (uint8_t*)(&(this->
image_msg_.data[0]));
423 if (this->
image_msg_.data.size() == rows_arg*cols_arg*3)
426 iter_rgb[0] = image_src[i*3+j*cols_arg*3+0];
427 iter_rgb[1] = image_src[i*3+j*cols_arg*3+1];
428 iter_rgb[2] = image_src[i*3+j*cols_arg*3+2];
430 else if (this->
image_msg_.data.size() == rows_arg*cols_arg)
433 iter_rgb[0] = image_src[i+j*cols_arg];
434 iter_rgb[1] = image_src[i+j*cols_arg];
435 iter_rgb[2] = image_src[i+j*cols_arg];
452 sensor_msgs::Image& image_msg,
453 uint32_t rows_arg, uint32_t cols_arg,
454 uint32_t step_arg,
void* data_arg)
457 image_msg.height = rows_arg;
458 image_msg.width = cols_arg;
459 image_msg.step =
sizeof(float) * cols_arg;
460 image_msg.data.resize(rows_arg * cols_arg *
sizeof(
float));
461 image_msg.is_bigendian = 0;
463 const float bad_point = std::numeric_limits<float>::quiet_NaN();
465 float* dest = (
float*)(&(image_msg.data[0]));
466 float* toCopyFrom = (
float*)data_arg;
470 for (uint32_t j = 0; j < rows_arg; j++)
472 for (uint32_t i = 0; i < cols_arg; i++)
474 float depth = toCopyFrom[index++];
478 dest[i + j * cols_arg] = depth;
482 dest[i + j * cols_arg] = bad_point;
491 ROS_DEBUG_NAMED(
"depth_camera",
"publishing default camera info, then depth camera info");
496 common::Time sensor_update_time = this->
parentSensor_->LastMeasurementTime();
double point_cloud_cutoff_
void PointCloudDisconnect()
~GazeboRosDepthCamera()
Destructor.
virtual void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
std::string image_topic_name_
ROS image topic name.
void publish(const boost::shared_ptr< M > &message) const
boost::mutex lock_
A mutex to lock access to fields that are used in ROS message callbacks.
virtual void PublishCameraInfo()
common::Time sensor_update_time_
std::string depth_image_topic_name_
image where each pixel contains the depth information
void DepthImageDisconnect()
ROSCPP_DECL bool isInitialized()
std::string point_cloud_topic_name_
ROS image topic name.
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf, const std::string &_camera_name_suffix="")
Load the plugin.
common::Time last_depth_image_camera_info_update_time_
common::Time depth_sensor_update_time_
ros::CallbackQueue camera_queue_
boost::shared_ptr< int > image_connect_count_
Keep track of number of image connections.
sensor_msgs::Image image_msg_
ROS image message.
#define ROS_DEBUG_NAMED(name,...)
event::ConnectionPtr OnLoad(const boost::function< void()> &)
#define ROS_FATAL_STREAM_NAMED(name, args)
const std::string TYPE_32FC1
bool initialized_
True if camera util is initialized.
int depth_info_connect_count_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::string frame_name_
ROS frame transform name to use in the image message header. This should typically match the link nam...
bool FillDepthImageHelper(sensor_msgs::Image &image_msg, uint32_t rows_arg, uint32_t cols_arg, uint32_t step_arg, void *data_arg)
std::string camera_info_topic_name_
sensor_msgs::PointCloud2 point_cloud_msg_
PointCloud2 point cloud message.
ros::Publisher point_cloud_pub_
A pointer to the ROS node. A node will be instantiated if it does not exist.
void PutCameraData(const unsigned char *_src)
Put camera data to the ROS topic.
rendering::CameraPtr camera_
int point_cloud_connect_count_
Keep track of number of connctions for point clouds.
virtual void OnNewDepthFrame(const float *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
Update the controller.
ros::NodeHandle * rosnode_
A pointer to the ROS node. A node will be instantiated if it does not exist.
void FillPointdCloud(const float *_src)
Put camera data to the ROS topic.
int depth_image_connect_count_
Keep track of number of connctions for point clouds.
void FillDepthImage(const float *_src)
push depth image data into ros topic
event::ConnectionPtr load_connection_
ros::Publisher depth_image_camera_info_pub_
ros::Publisher depth_image_pub_
virtual void Advertise()
Advertise point cloud and depth image.
std::string depth_image_camera_info_topic_name_
void DepthInfoDisconnect()
sensor_msgs::Image depth_image_msg_
sensors::SensorPtr parentSensor_
void setPointCloud2FieldsByString(int n_fields,...)
virtual void OnNewRGBPointCloud(const float *_pcd, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
Update the controller.
boost::shared_ptr< void > VoidPtr
virtual void OnNewImageFrame(const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
Update the controller.
bool FillPointCloudHelper(sensor_msgs::PointCloud2 &point_cloud_msg, uint32_t rows_arg, uint32_t cols_arg, uint32_t step_arg, void *data_arg)