40#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
42#if __has_include(<tf2/LinearMath/Vector3.hpp>)
43#include <tf2/LinearMath/Vector3.hpp>
45#include <tf2/LinearMath/Vector3.h>
47#if __has_include(<tf2/LinearMath/Transform.hpp>)
48#include <tf2/LinearMath/Transform.hpp>
50#include <tf2/LinearMath/Transform.h>
52#include <geometric_shapes/shape_operations.h>
53#include <sensor_msgs/image_encodings.hpp>
64 , image_topic_(
"depth")
66 , near_clipping_plane_distance_(0.3)
67 , far_clipping_plane_distance_(5.0)
68 , shadow_threshold_(0.04)
70 , padding_offset_(0.02)
72 , skip_vertical_pixels_(4)
73 , skip_horizontal_pixels_(6)
74 , image_callback_count_(0)
75 , average_callback_dt_(0.0)
83 , logger_(
moveit::getLogger(
"moveit.ros.depth_image_octomap_updater"))
89 sub_depth_image_.shutdown();
96 node_->get_parameter(name_space +
".image_topic", image_topic_) &&
97 node_->get_parameter(name_space +
".queue_size", queue_size_) &&
98 node_->get_parameter(name_space +
".near_clipping_plane_distance", near_clipping_plane_distance_) &&
99 node_->get_parameter(name_space +
".far_clipping_plane_distance", far_clipping_plane_distance_) &&
100 node_->get_parameter(name_space +
".shadow_threshold", shadow_threshold_) &&
101 node_->get_parameter(name_space +
".padding_scale", padding_scale_) &&
102 node_->get_parameter(name_space +
".padding_offset", padding_offset_) &&
103 node_->get_parameter(name_space +
".max_update_rate", max_update_rate_) &&
104 node_->get_parameter(name_space +
".skip_vertical_pixels", skip_vertical_pixels_) &&
105 node_->get_parameter(name_space +
".skip_horizontal_pixels", skip_horizontal_pixels_) &&
106 node_->get_parameter(name_space +
".filtered_cloud_topic", filtered_cloud_topic_) &&
107 node_->get_parameter(name_space +
".ns", ns_);
110 catch (
const rclcpp::exceptions::InvalidParameterTypeException& e)
112 RCLCPP_ERROR_STREAM(logger_, e.what() <<
'\n');
120 input_depth_transport_ = std::make_unique<image_transport::ImageTransport>(node_);
121 model_depth_transport_ = std::make_unique<image_transport::ImageTransport>(node_);
122 filtered_depth_transport_ = std::make_unique<image_transport::ImageTransport>(node_);
123 filtered_label_transport_ = std::make_unique<image_transport::ImageTransport>(node_);
126 free_space_updater_ = std::make_unique<LazyFreeSpaceUpdater>(
tree_);
129 mesh_filter_ = std::make_unique<mesh_filter::MeshFilter<mesh_filter::StereoCameraModel>>(
131 mesh_filter_->parameters().setDepthRange(near_clipping_plane_distance_, far_clipping_plane_distance_);
132 mesh_filter_->setShadowThreshold(shadow_threshold_);
133 mesh_filter_->setPaddingOffset(padding_offset_);
134 mesh_filter_->setPaddingScale(padding_scale_);
135 mesh_filter_->setTransformCallback(
143 pub_model_depth_image_ = model_depth_transport_->advertiseCamera(
"model_depth", 1);
145 std::string prefix =
"";
149 pub_model_depth_image_ = model_depth_transport_->advertiseCamera(prefix +
"model_depth", 1);
150 if (!filtered_cloud_topic_.empty())
152 pub_filtered_depth_image_ = filtered_depth_transport_->advertiseCamera(prefix + filtered_cloud_topic_, 1);
156 pub_filtered_depth_image_ = filtered_depth_transport_->advertiseCamera(prefix +
"filtered_depth", 1);
159 pub_filtered_label_image_ = filtered_label_transport_->advertiseCamera(prefix +
"filtered_label", 1);
161 sub_depth_image_ = image_transport::create_camera_subscription(
162 node_.get(), image_topic_,
163 [
this](
const sensor_msgs::msg::Image::ConstSharedPtr& depth_msg,
164 const sensor_msgs::msg::CameraInfo::ConstSharedPtr& info_msg) {
165 return depthImageCallback(depth_msg, info_msg);
167 "raw", rmw_qos_profile_sensor_data);
172 sub_depth_image_.shutdown();
180 if (shape->type == shapes::MESH)
182 h = mesh_filter_->addMesh(
static_cast<const shapes::Mesh&
>(*shape));
186 std::unique_ptr<shapes::Mesh> m(shapes::createMeshFromShape(shape.get()));
188 h = mesh_filter_->addMesh(*m);
192 RCLCPP_ERROR(logger_,
"Mesh filter not yet initialized!");
199 mesh_filter_->removeMesh(handle);
207 RCLCPP_ERROR(logger_,
"Internal error. Mesh filter handle %u not found", h);
210 transform = it->second;
216const bool HOST_IS_BIG_ENDIAN = []() {
220 char c[
sizeof(uint32_t)];
221 } bint = { 0x01020304 };
222 return bint.c[0] == 1;
226void DepthImageOctomapUpdater::depthImageCallback(
const sensor_msgs::msg::Image::ConstSharedPtr& depth_msg,
227 const sensor_msgs::msg::CameraInfo::ConstSharedPtr& info_msg)
229 RCLCPP_DEBUG(logger_,
"Received a new depth image message (frame = '%s', encoding='%s')",
230 depth_msg->header.frame_id.c_str(), depth_msg->encoding.c_str());
231 rclcpp::Time
start = node_->now();
233 if (max_update_rate_ > 0)
236 if (node_->now() - last_update_time_ <= rclcpp::Duration::from_seconds(1.0 / max_update_rate_))
238 last_update_time_ = node_->now();
242 if (image_callback_count_ < 1000)
244 if (image_callback_count_ > 0)
246 const double dt_start = (
start - last_depth_callback_start_).seconds();
247 if (image_callback_count_ < 2)
249 average_callback_dt_ = dt_start;
253 average_callback_dt_ = ((image_callback_count_ - 1) * average_callback_dt_ + dt_start) /
254 static_cast<double>(image_callback_count_);
262 image_callback_count_ = 2;
264 last_depth_callback_start_ =
start;
265 ++image_callback_count_;
271 tf2::Stamped<tf2::Transform> map_h_sensor;
274 map_h_sensor.setIdentity();
281 static const double TEST_DT = 0.005;
283 static_cast<int>((0.5 + average_callback_dt_ / TEST_DT) * std::max(1, (
static_cast<int>(queue_size_) / 2)));
286 for (
int t = 0; t < nt; ++t)
290 tf2::fromMsg(tf_buffer_->lookupTransform(
monitor_->
getMapFrame(), depth_msg->header.frame_id,
291 depth_msg->header.stamp),
296 catch (tf2::TransformException& ex)
298 std::chrono::duration<double, std::nano> tmp_duration(TEST_DT);
299 static const rclcpp::Duration D(tmp_duration);
301 std::this_thread::sleep_for(D.to_chrono<std::chrono::seconds>());
304 static const unsigned int MAX_TF_COUNTER = 1000;
308 if (good_tf_ > MAX_TF_COUNTER)
310 const unsigned int div = MAX_TF_COUNTER / 10;
318 if (failed_tf_ > good_tf_)
320#pragma GCC diagnostic push
321#pragma GCC diagnostic ignored "-Wold-style-cast"
322 RCLCPP_WARN_THROTTLE(logger_, *node_->get_clock(), 1000,
323 "More than half of the image messages discarded due to TF being unavailable (%u%%). "
324 "Transform error of sensor data: %s; quitting callback.",
325 (100 * failed_tf_) / (good_tf_ + failed_tf_), err.c_str());
326#pragma GCC diagnostic pop
330#pragma GCC diagnostic push
331#pragma GCC diagnostic ignored "-Wold-style-cast"
332 RCLCPP_DEBUG_THROTTLE(logger_, *node_->get_clock(), 1000,
333 "Transform error of sensor data: %s; quitting callback", err.c_str());
334#pragma GCC diagnostic pop
336 if (failed_tf_ > MAX_TF_COUNTER)
338 const unsigned int div = MAX_TF_COUNTER / 10;
352 if (depth_msg->is_bigendian && !HOST_IS_BIG_ENDIAN)
354#pragma GCC diagnostic push
355#pragma GCC diagnostic ignored "-Wold-style-cast"
356 RCLCPP_ERROR_THROTTLE(logger_, *node_->get_clock(), 1000,
"endian problem: received image data does not match host");
357#pragma GCC diagnostic pop
360 const int w = depth_msg->width;
361 const int h = depth_msg->height;
365 params.
setCameraParameters(info_msg->k[0], info_msg->k[4], info_msg->k[2], info_msg->k[5]);
368 const bool is_u_short = depth_msg->encoding == sensor_msgs::image_encodings::TYPE_16UC1;
371 mesh_filter_->filter(&depth_msg->data[0], GL_UNSIGNED_SHORT);
375 if (depth_msg->encoding != sensor_msgs::image_encodings::TYPE_32FC1)
377#pragma GCC diagnostic push
378#pragma GCC diagnostic ignored "-Wold-style-cast"
379 RCLCPP_ERROR_THROTTLE(logger_, *node_->get_clock(), 1000,
"Unexpected encoding type: '%s'. Ignoring input.",
380 depth_msg->encoding.c_str());
381#pragma GCC diagnostic pop
384 mesh_filter_->filter(&depth_msg->data[0], GL_FLOAT);
390 const double px = info_msg->k[2];
391 const double py = info_msg->k[5];
394 if (w >=
static_cast<int>(x_cache_.size()) || h >=
static_cast<int>(y_cache_.size()) || K2_ != px || K5_ !=
py ||
395 K0_ != info_msg->k[0] || K4_ != info_msg->k[4])
399 K0_ = info_msg->k[0];
400 K4_ = info_msg->k[4];
406 if (isnan(px) || isnan(
py) || isnan(inv_fx_) || isnan(inv_fy_))
410 if (
static_cast<int>(x_cache_.size()) < w)
412 if (
static_cast<int>(y_cache_.size()) < h)
415 for (
int x = 0; x < w; ++x)
416 x_cache_[x] = (x - px) * inv_fx_;
418 for (
int y = 0; y < h; ++y)
419 y_cache_[y] = (y -
py) * inv_fy_;
422 const octomap::point3d sensor_origin(map_h_sensor.getOrigin().getX(), map_h_sensor.getOrigin().getY(),
423 map_h_sensor.getOrigin().getZ());
425 octomap::KeySet* occupied_cells_ptr =
new octomap::KeySet();
426 octomap::KeySet* model_cells_ptr =
new octomap::KeySet();
427 octomap::KeySet& occupied_cells = *occupied_cells_ptr;
428 octomap::KeySet& model_cells = *model_cells_ptr;
431 std::size_t img_size = h * w;
432 if (filtered_labels_.size() < img_size)
433 filtered_labels_.resize(img_size);
436 const unsigned int* labels_row = &filtered_labels_[0];
437 mesh_filter_->getFilteredLabels(&filtered_labels_[0]);
442 sensor_msgs::msg::Image debug_msg;
443 debug_msg.header = depth_msg->header;
444 debug_msg.height = h;
446 debug_msg.is_bigendian = HOST_IS_BIG_ENDIAN;
447 debug_msg.encoding = sensor_msgs::image_encodings::TYPE_32FC1;
448 debug_msg.step = w *
sizeof(float);
449 debug_msg.data.resize(img_size *
sizeof(
float));
450 mesh_filter_->getModelDepth(
reinterpret_cast<float*
>(&debug_msg.data[0]));
451 pub_model_depth_image_.publish(debug_msg, *info_msg);
453 sensor_msgs::msg::Image filtered_depth_msg;
454 filtered_depth_msg.header = depth_msg->header;
455 filtered_depth_msg.height = h;
456 filtered_depth_msg.width = w;
457 filtered_depth_msg.is_bigendian = HOST_IS_BIG_ENDIAN;
458 filtered_depth_msg.encoding = sensor_msgs::image_encodings::TYPE_32FC1;
459 filtered_depth_msg.step = w *
sizeof(float);
460 filtered_depth_msg.data.resize(img_size *
sizeof(
float));
461 mesh_filter_->getFilteredDepth(
reinterpret_cast<float*
>(&filtered_depth_msg.data[0]));
462 pub_filtered_depth_image_.publish(filtered_depth_msg, *info_msg);
464 sensor_msgs::msg::Image label_msg;
465 label_msg.header = depth_msg->header;
466 label_msg.height = h;
468 label_msg.is_bigendian = HOST_IS_BIG_ENDIAN;
469 label_msg.encoding = sensor_msgs::image_encodings::RGBA8;
470 label_msg.step = w *
sizeof(
unsigned int);
471 label_msg.data.resize(img_size *
sizeof(
unsigned int));
472 mesh_filter_->getFilteredLabels(
reinterpret_cast<unsigned int*
>(&label_msg.data[0]));
474 pub_filtered_label_image_.publish(label_msg, *info_msg);
477 if (!filtered_cloud_topic_.empty())
479 sensor_msgs::msg::Image filtered_msg;
480 filtered_msg.header = depth_msg->header;
481 filtered_msg.height = h;
482 filtered_msg.width = w;
483 filtered_msg.is_bigendian = HOST_IS_BIG_ENDIAN;
484 filtered_msg.encoding = sensor_msgs::image_encodings::TYPE_16UC1;
485 filtered_msg.step = w *
sizeof(
unsigned short);
486 filtered_msg.data.resize(img_size *
sizeof(
unsigned short));
489 static std::vector<float> filtered_data;
490 if (filtered_data.size() < img_size)
491 filtered_data.resize(img_size);
493 mesh_filter_->getFilteredDepth(
reinterpret_cast<float*
>(&filtered_data[0]));
494 unsigned short* msg_data =
reinterpret_cast<unsigned short*
>(&filtered_msg.data[0]);
495 for (std::size_t i = 0; i < img_size; ++i)
498 msg_data[i] =
static_cast<unsigned short>(filtered_data[i] * 1000 + 0.5);
500 pub_filtered_depth_image_.publish(filtered_msg, *info_msg);
508 const int h_bound = h - skip_vertical_pixels_;
509 const int w_bound = w - skip_horizontal_pixels_;
513 const uint16_t* input_row =
reinterpret_cast<const uint16_t*
>(&depth_msg->data[0]);
515 for (
int y = skip_vertical_pixels_; y < h_bound; ++y, labels_row += w, input_row += w)
517 for (
int x = skip_horizontal_pixels_; x < w_bound; ++x)
522 float zz =
static_cast<float>(input_row[x]) * 1e-3;
523 float yy = y_cache_[y] * zz;
524 float xx = x_cache_[x] * zz;
526 tf2::Vector3 point_tf = map_h_sensor * tf2::Vector3(xx, yy, zz);
527 occupied_cells.insert(
tree_->coordToKey(point_tf.getX(), point_tf.getY(), point_tf.getZ()));
532 float zz = input_row[x] * 1e-3;
533 float yy = y_cache_[y] * zz;
534 float xx = x_cache_[x] * zz;
536 tf2::Vector3 point_tf = map_h_sensor * tf2::Vector3(xx, yy, zz);
538 model_cells.insert(
tree_->coordToKey(point_tf.getX(), point_tf.getY(), point_tf.getZ()));
545 const float* input_row =
reinterpret_cast<const float*
>(&depth_msg->data[0]);
547 for (
int y = skip_vertical_pixels_; y < h_bound; ++y, labels_row += w, input_row += w)
549 for (
int x = skip_horizontal_pixels_; x < w_bound; ++x)
553 float zz = input_row[x];
554 float yy = y_cache_[y] * zz;
555 float xx = x_cache_[x] * zz;
557 tf2::Vector3 point_tf = map_h_sensor * tf2::Vector3(xx, yy, zz);
558 occupied_cells.insert(
tree_->coordToKey(point_tf.getX(), point_tf.getY(), point_tf.getZ()));
562 float zz = input_row[x];
563 float yy = y_cache_[y] * zz;
564 float xx = x_cache_[x] * zz;
566 tf2::Vector3 point_tf = map_h_sensor * tf2::Vector3(xx, yy, zz);
568 model_cells.insert(
tree_->coordToKey(point_tf.getX(), point_tf.getY(), point_tf.getZ()));
577 RCLCPP_ERROR(logger_,
"Internal error while parsing depth data");
583 for (
const octomap::OcTreeKey& model_cell : model_cells)
584 occupied_cells.erase(model_cell);
591 for (
const octomap::OcTreeKey& occupied_cell : occupied_cells)
592 tree_->updateNode(occupied_cell, true);
596 RCLCPP_ERROR(logger_,
"Internal error while updating octree");
598 tree_->unlockWrite();
599 tree_->triggerUpdateCallback();
602 free_space_updater_->pushLazyUpdate(occupied_cells_ptr, model_cells_ptr, sensor_origin);
604 RCLCPP_DEBUG(logger_,
"Processed depth image in %lf ms", (node_->now() -
start).seconds() * 1000.0);
std::function< bool(MeshHandle, Eigen::Isometry3d &)> TransformCallback
void setImageSize(unsigned width, unsigned height)
sets the image size
Parameters for Stereo-like devices.
void setCameraParameters(float fx, float fy, float cx, float cy)
sets the camera parameters of the pinhole camera where the disparities were obtained....
static const StereoCameraModel::Parameters & REGISTERED_PSDK_PARAMS
predefined sensor model for OpenNI compatible devices (e.g., PrimeSense, Kinect, Asus Xtion)
void forgetShape(ShapeHandle handle) override
DepthImageOctomapUpdater()
bool initialize(const rclcpp::Node::SharedPtr &node) override
Do any necessary setup (subscribe to ros topics, etc.). This call assumes setMonitor() and setParams(...
ShapeHandle excludeShape(const shapes::ShapeConstPtr &shape) override
~DepthImageOctomapUpdater() override
bool setParams(const std::string &name_space) override
Set updater params using struct that comes from parsing a yaml string. This must be called after setM...
const std::shared_ptr< tf2_ros::Buffer > & getTFClient() const
Gets the tf client.
const std::string & getMapFrame() const
Gets the map frame (this is set either by the constor or a parameter).
void setMapFrame(const std::string &frame)
Sets the map frame.
Base class for classes which update the occupancy map.
OccupancyMapMonitor * monitor_
collision_detection::OccMapTreePtr tree_
ShapeTransformCache transform_cache_
bool updateTransformCache(const std::string &target_frame, const rclcpp::Time &target_time)
Main namespace for MoveIt.