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_info_connect_count_ = 0;
49 this->last_depth_image_camera_info_update_time_ = common::Time(0);
62 DepthCameraPlugin::Load(_parent, _sdf);
67 ROS_FATAL_STREAM_NAMED(
"depth_camera",
"A ROS node for Gazebo has not been initialized, unable to load plugin. " 68 <<
"Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
74 this->
width_ = this->width;
76 this->
depth_ = this->depth;
78 this->
camera_ = this->depthCamera;
81 if (!_sdf->HasElement(
"imageTopicName"))
83 if (!_sdf->HasElement(
"cameraInfoTopicName"))
87 if (!_sdf->HasElement(
"pointCloudTopicName"))
93 if (!_sdf->HasElement(
"depthImageTopicName"))
98 if (!_sdf->HasElement(
"depthImageCameraInfoTopicName"))
103 if (!_sdf->HasElement(
"pointCloudCutoff"))
115 ros::AdvertiseOptions::create<sensor_msgs::PointCloud2 >(
123 ros::AdvertiseOptions::create< sensor_msgs::Image >(
131 ros::AdvertiseOptions::create<sensor_msgs::CameraInfo>(
146 this->parentSensor->SetActive(
true);
155 this->parentSensor->SetActive(
false);
163 this->parentSensor->SetActive(
true);
188 unsigned int _width,
unsigned int _height,
unsigned int _depth,
189 const std::string &_format)
194 # if GAZEBO_MAJOR_VERSION >= 7 200 if (this->parentSensor->IsActive())
206 this->parentSensor->SetActive(
false);
222 this->parentSensor->SetActive(
true);
229 unsigned int _width,
unsigned int _height,
unsigned int _depth,
230 const std::string &_format)
235 # if GAZEBO_MAJOR_VERSION >= 7 241 if (!this->parentSensor->IsActive())
245 this->parentSensor->SetActive(
true);
261 pcd_modifier.
resize(_width*_height);
270 for (
unsigned int i = 0; i < _width; i++)
272 for (
unsigned int j = 0; j < _height; j++, ++iter_x, ++iter_y, ++iter_z, ++iter_rgb)
274 unsigned int index = (j * _width) + i;
275 *iter_x = _pcd[4 * index];
276 *iter_y = _pcd[4 * index + 1];
277 *iter_z = _pcd[4 * index + 2];
278 *iter_rgb = _pcd[4 * index + 3];
279 if (i == _width /2 && j == _height / 2)
281 uint32_t rgb = *
reinterpret_cast<int*
>(&(*iter_rgb));
282 uint8_t r = (rgb >> 16) & 0x0000ff;
283 uint8_t g = (rgb >> 8) & 0x0000ff;
284 uint8_t b = (rgb) & 0x0000ff;
285 std::cerr << (int)r <<
" " << (
int)g <<
" " << (int)b <<
"\n";
291 this->
lock_.unlock();
299 unsigned int _width,
unsigned int _height,
unsigned int _depth,
300 const std::string &_format)
306 # if GAZEBO_MAJOR_VERSION >= 7 312 if (!this->parentSensor->IsActive())
316 this->parentSensor->SetActive(
true);
351 this->
lock_.unlock();
373 this->
lock_.unlock();
379 sensor_msgs::PointCloud2 &point_cloud_msg,
380 uint32_t rows_arg, uint32_t cols_arg,
381 uint32_t step_arg,
void* data_arg)
385 pcd_modifier.
resize(rows_arg*cols_arg);
392 point_cloud_msg.is_dense =
true;
394 float* toCopyFrom = (
float*)data_arg;
397 double hfov = this->parentSensor->DepthCamera()->HFOV().Radian();
398 double fl = ((double)this->width) / (2.0 *tan(hfov/2.0));
401 for (uint32_t j=0; j<rows_arg; j++)
404 if (rows_arg>1) pAngle = atan2( (
double)j - 0.5*(
double)(rows_arg-1), fl);
407 for (uint32_t i=0; i<cols_arg; i++, ++iter_x, ++iter_y, ++iter_z, ++iter_rgb)
410 if (cols_arg>1) yAngle = atan2( (
double)i - 0.5*(
double)(cols_arg-1), fl);
413 double depth = toCopyFrom[index++];
419 *iter_x = depth * tan(yAngle);
420 *iter_y = depth * tan(pAngle);
427 *iter_x = *iter_y = *iter_z = std::numeric_limits<float>::quiet_NaN ();
428 point_cloud_msg.is_dense =
false;
432 uint8_t* image_src = (uint8_t*)(&(this->
image_msg_.data[0]));
433 if (this->
image_msg_.data.size() == rows_arg*cols_arg*3)
436 iter_rgb[0] = image_src[i*3+j*cols_arg*3+0];
437 iter_rgb[1] = image_src[i*3+j*cols_arg*3+1];
438 iter_rgb[2] = image_src[i*3+j*cols_arg*3+2];
440 else if (this->
image_msg_.data.size() == rows_arg*cols_arg)
443 iter_rgb[0] = image_src[i+j*cols_arg];
444 iter_rgb[1] = image_src[i+j*cols_arg];
445 iter_rgb[2] = image_src[i+j*cols_arg];
462 sensor_msgs::Image& image_msg,
463 uint32_t rows_arg, uint32_t cols_arg,
464 uint32_t step_arg,
void* data_arg)
467 image_msg.height = rows_arg;
468 image_msg.width = cols_arg;
469 image_msg.step =
sizeof(float) * cols_arg;
470 image_msg.data.resize(rows_arg * cols_arg *
sizeof(
float));
471 image_msg.is_bigendian = 0;
473 const float bad_point = std::numeric_limits<float>::quiet_NaN();
475 float* dest = (
float*)(&(image_msg.data[0]));
476 float* toCopyFrom = (
float*)data_arg;
480 for (uint32_t j = 0; j < rows_arg; j++)
482 for (uint32_t i = 0; i < cols_arg; i++)
484 float depth = toCopyFrom[index++];
488 dest[i + j * cols_arg] = depth;
492 dest[i + j * cols_arg] = bad_point;
501 ROS_DEBUG_NAMED(
"depth_camera",
"publishing default camera info, then depth camera info");
506 # if GAZEBO_MAJOR_VERSION >= 7 507 common::Time sensor_update_time = this->
parentSensor_->LastMeasurementTime();
509 common::Time sensor_update_time = this->
parentSensor_->GetLastMeasurementTime();
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)