39 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
40 #include <tf2/LinearMath/Vector3.h>
41 #include <tf2/LinearMath/Transform.h>
42 #include <geometric_shapes/shape_operations.h>
43 #include <sensor_msgs/image_encodings.hpp>
50 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit.ros.perception.depth_image_octomap_updater");
54 , image_topic_(
"depth")
56 , near_clipping_plane_distance_(0.3)
57 , far_clipping_plane_distance_(5.0)
58 , shadow_threshold_(0.04)
60 , padding_offset_(0.02)
62 , skip_vertical_pixels_(4)
63 , skip_horizontal_pixels_(6)
64 , image_callback_count_(0)
65 , average_callback_dt_(0.0)
85 node_->get_parameter(name_space +
".image_topic", image_topic_) &&
86 node_->get_parameter(name_space +
".queue_size", queue_size_) &&
87 node_->get_parameter(name_space +
".near_clipping_plane_distance", near_clipping_plane_distance_) &&
88 node_->get_parameter(name_space +
".far_clipping_plane_distance", far_clipping_plane_distance_) &&
89 node_->get_parameter(name_space +
".shadow_threshold", shadow_threshold_) &&
90 node_->get_parameter(name_space +
".padding_scale", padding_scale_) &&
91 node_->get_parameter(name_space +
".padding_offset", padding_offset_) &&
92 node_->get_parameter(name_space +
".max_update_rate", max_update_rate_) &&
93 node_->get_parameter(name_space +
".skip_vertical_pixels", skip_vertical_pixels_) &&
94 node_->get_parameter(name_space +
".skip_horizontal_pixels", skip_horizontal_pixels_) &&
95 node_->get_parameter(name_space +
".filtered_cloud_topic", filtered_cloud_topic_) &&
96 node_->get_parameter(name_space +
".ns", ns_);
99 catch (
const rclcpp::exceptions::InvalidParameterTypeException& e)
101 RCLCPP_ERROR_STREAM(LOGGER, e.what() <<
'\n');
109 input_depth_transport_ = std::make_unique<image_transport::ImageTransport>(node_);
110 model_depth_transport_ = std::make_unique<image_transport::ImageTransport>(node_);
111 filtered_depth_transport_ = std::make_unique<image_transport::ImageTransport>(node_);
112 filtered_label_transport_ = std::make_unique<image_transport::ImageTransport>(node_);
115 free_space_updater_ = std::make_unique<LazyFreeSpaceUpdater>(
tree_);
118 mesh_filter_ = std::make_unique<mesh_filter::MeshFilter<mesh_filter::StereoCameraModel>>(
120 mesh_filter_->parameters().setDepthRange(near_clipping_plane_distance_, far_clipping_plane_distance_);
121 mesh_filter_->setShadowThreshold(shadow_threshold_);
122 mesh_filter_->setPaddingOffset(padding_offset_);
123 mesh_filter_->setPaddingScale(padding_scale_);
124 mesh_filter_->setTransformCallback(
132 rmw_qos_profile_t custom_qos = rmw_qos_profile_system_default;
133 pub_model_depth_image_ = model_depth_transport_->advertiseCamera(
"model_depth", 1);
135 std::string prefix =
"";
139 pub_model_depth_image_ = model_depth_transport_->advertiseCamera(prefix +
"model_depth", 1);
140 if (!filtered_cloud_topic_.empty())
141 pub_filtered_depth_image_ = filtered_depth_transport_->advertiseCamera(prefix + filtered_cloud_topic_, 1);
143 pub_filtered_depth_image_ = filtered_depth_transport_->advertiseCamera(prefix +
"filtered_depth", 1);
145 pub_filtered_label_image_ = filtered_label_transport_->advertiseCamera(prefix +
"filtered_label", 1);
147 sub_depth_image_ = image_transport::create_camera_subscription(
148 node_.get(), image_topic_,
149 [
this](
const sensor_msgs::msg::Image::ConstSharedPtr& depth_msg,
150 const sensor_msgs::msg::CameraInfo::ConstSharedPtr& info_msg) {
151 return depthImageCallback(depth_msg, info_msg);
161 void DepthImageOctomapUpdater::stopHelper()
163 sub_depth_image_.shutdown();
171 if (shape->type == shapes::MESH)
172 h = mesh_filter_->addMesh(
static_cast<const shapes::Mesh&
>(*shape));
175 std::unique_ptr<shapes::Mesh> m(shapes::createMeshFromShape(shape.get()));
177 h = mesh_filter_->addMesh(*m);
181 RCLCPP_ERROR(LOGGER,
"Mesh filter not yet initialized!");
188 mesh_filter_->removeMesh(handle);
191 bool DepthImageOctomapUpdater::getShapeTransform(
mesh_filter::MeshHandle h, Eigen::Isometry3d& transform)
const
196 RCLCPP_ERROR(LOGGER,
"Internal error. Mesh filter handle %u not found", h);
199 transform = it->second;
205 bool host_is_big_endian()
210 char c[
sizeof(uint32_t)];
211 } bint = { 0x01020304 };
212 return bint.c[0] == 1;
216 static const bool HOST_IS_BIG_ENDIAN = host_is_big_endian();
218 void DepthImageOctomapUpdater::depthImageCallback(
const sensor_msgs::msg::Image::ConstSharedPtr& depth_msg,
219 const sensor_msgs::msg::CameraInfo::ConstSharedPtr& info_msg)
221 RCLCPP_DEBUG(LOGGER,
"Received a new depth image message (frame = '%s', encoding='%s')",
222 depth_msg->header.frame_id.c_str(), depth_msg->encoding.c_str());
223 rclcpp::Time
start = node_->now();
225 if (max_update_rate_ > 0)
228 if (node_->now() - last_update_time_ <= rclcpp::Duration::from_seconds(1.0 / max_update_rate_))
230 last_update_time_ = node_->now();
234 if (image_callback_count_ < 1000)
236 if (image_callback_count_ > 0)
238 const double dt_start = (
start - last_depth_callback_start_).seconds();
239 if (image_callback_count_ < 2)
240 average_callback_dt_ = dt_start;
242 average_callback_dt_ =
243 ((image_callback_count_ - 1) * average_callback_dt_ + dt_start) / (double)image_callback_count_;
249 image_callback_count_ = 2;
250 last_depth_callback_start_ =
start;
251 ++image_callback_count_;
257 tf2::Stamped<tf2::Transform> map_h_sensor;
259 map_h_sensor.setIdentity();
265 static const double TEST_DT = 0.005;
267 static_cast<int>((0.5 + average_callback_dt_ / TEST_DT) * std::max(1, (
static_cast<int>(queue_size_) / 2)));
270 for (
int t = 0; t < nt; ++t)
273 tf2::fromMsg(tf_buffer_->lookupTransform(
monitor_->
getMapFrame(), depth_msg->header.frame_id,
274 depth_msg->header.stamp),
279 catch (tf2::TransformException& ex)
281 std::chrono::duration<double, std::nano> tmp_duration(TEST_DT);
282 static const rclcpp::Duration D(tmp_duration);
284 std::this_thread::sleep_for(D.to_chrono<std::chrono::seconds>());
286 static const unsigned int MAX_TF_COUNTER = 1000;
290 if (good_tf_ > MAX_TF_COUNTER)
292 const unsigned int div = MAX_TF_COUNTER / 10;
300 if (failed_tf_ > good_tf_)
301 RCLCPP_WARN_THROTTLE(LOGGER, *node_->get_clock(), 1000,
302 "More than half of the image messages discarded due to TF being unavailable (%u%%). "
303 "Transform error of sensor data: %s; quitting callback.",
304 (100 * failed_tf_) / (good_tf_ + failed_tf_), err.c_str());
306 RCLCPP_DEBUG_THROTTLE(LOGGER, *node_->get_clock(), 1000,
307 "Transform error of sensor data: %s; quitting callback", err.c_str());
308 if (failed_tf_ > MAX_TF_COUNTER)
310 const unsigned int div = MAX_TF_COUNTER / 10;
324 if (depth_msg->is_bigendian && !HOST_IS_BIG_ENDIAN)
325 RCLCPP_ERROR_THROTTLE(LOGGER, *node_->get_clock(), 1000,
"endian problem: received image data does not match host");
327 const int w = depth_msg->width;
328 const int h = depth_msg->height;
332 params.
setCameraParameters(info_msg->k[0], info_msg->k[4], info_msg->k[2], info_msg->k[5]);
335 const bool is_u_short = depth_msg->encoding == sensor_msgs::image_encodings::TYPE_16UC1;
337 mesh_filter_->filter(&depth_msg->data[0], GL_UNSIGNED_SHORT);
340 if (depth_msg->encoding != sensor_msgs::image_encodings::TYPE_32FC1)
342 RCLCPP_ERROR_THROTTLE(LOGGER, *node_->get_clock(), 1000,
"Unexpected encoding type: '%s'. Ignoring input.",
343 depth_msg->encoding.c_str());
346 mesh_filter_->filter(&depth_msg->data[0], GL_FLOAT);
352 const double px = info_msg->k[2];
353 const double py = info_msg->k[5];
356 if (
w >=
static_cast<int>(x_cache_.size()) || h >=
static_cast<int>(y_cache_.size()) || K2_ != px || K5_ !=
py ||
357 K0_ != info_msg->k[0] || K4_ != info_msg->k[4])
361 K0_ = info_msg->k[0];
362 K4_ = info_msg->k[4];
368 if (!(px == px &&
py ==
py && inv_fx_ == inv_fx_ && inv_fy_ == inv_fy_))
372 if (
static_cast<int>(x_cache_.size()) <
w)
374 if (
static_cast<int>(y_cache_.size()) < h)
377 for (
int x = 0;
x <
w; ++
x)
378 x_cache_[
x] = (
x - px) * inv_fx_;
380 for (
int y = 0;
y < h; ++
y)
381 y_cache_[
y] = (
y -
py) * inv_fy_;
384 const octomap::point3d sensor_origin(map_h_sensor.getOrigin().getX(), map_h_sensor.getOrigin().getY(),
385 map_h_sensor.getOrigin().getZ());
387 octomap::KeySet* occupied_cells_ptr =
new octomap::KeySet();
388 octomap::KeySet* model_cells_ptr =
new octomap::KeySet();
389 octomap::KeySet& occupied_cells = *occupied_cells_ptr;
390 octomap::KeySet& model_cells = *model_cells_ptr;
393 std::size_t img_size = h *
w;
394 if (filtered_labels_.size() < img_size)
395 filtered_labels_.resize(img_size);
398 const unsigned int* labels_row = &filtered_labels_[0];
399 mesh_filter_->getFilteredLabels(&filtered_labels_[0]);
404 sensor_msgs::msg::Image debug_msg;
405 debug_msg.header = depth_msg->header;
406 debug_msg.height = h;
408 debug_msg.is_bigendian = HOST_IS_BIG_ENDIAN;
409 debug_msg.encoding = sensor_msgs::image_encodings::TYPE_32FC1;
410 debug_msg.step =
w *
sizeof(float);
411 debug_msg.data.resize(img_size *
sizeof(
float));
412 mesh_filter_->getModelDepth(
reinterpret_cast<float*
>(&debug_msg.data[0]));
413 pub_model_depth_image_.publish(debug_msg, *info_msg);
415 sensor_msgs::msg::Image filtered_depth_msg;
416 filtered_depth_msg.header = depth_msg->header;
417 filtered_depth_msg.height = h;
418 filtered_depth_msg.width =
w;
419 filtered_depth_msg.is_bigendian = HOST_IS_BIG_ENDIAN;
420 filtered_depth_msg.encoding = sensor_msgs::image_encodings::TYPE_32FC1;
421 filtered_depth_msg.step =
w *
sizeof(float);
422 filtered_depth_msg.data.resize(img_size *
sizeof(
float));
423 mesh_filter_->getFilteredDepth(
reinterpret_cast<float*
>(&filtered_depth_msg.data[0]));
424 pub_filtered_depth_image_.publish(filtered_depth_msg, *info_msg);
426 sensor_msgs::msg::Image label_msg;
427 label_msg.header = depth_msg->header;
428 label_msg.height = h;
430 label_msg.is_bigendian = HOST_IS_BIG_ENDIAN;
431 label_msg.encoding = sensor_msgs::image_encodings::RGBA8;
432 label_msg.step =
w *
sizeof(
unsigned int);
433 label_msg.data.resize(img_size *
sizeof(
unsigned int));
434 mesh_filter_->getFilteredLabels(
reinterpret_cast<unsigned int*
>(&label_msg.data[0]));
436 pub_filtered_label_image_.publish(label_msg, *info_msg);
439 if (!filtered_cloud_topic_.empty())
441 sensor_msgs::msg::Image filtered_msg;
442 filtered_msg.header = depth_msg->header;
443 filtered_msg.height = h;
444 filtered_msg.width =
w;
445 filtered_msg.is_bigendian = HOST_IS_BIG_ENDIAN;
446 filtered_msg.encoding = sensor_msgs::image_encodings::TYPE_16UC1;
447 filtered_msg.step =
w *
sizeof(
unsigned short);
448 filtered_msg.data.resize(img_size *
sizeof(
unsigned short));
451 static std::vector<float> filtered_data;
452 if (filtered_data.size() < img_size)
453 filtered_data.resize(img_size);
455 mesh_filter_->getFilteredDepth(
reinterpret_cast<float*
>(&filtered_data[0]));
456 unsigned short* msg_data =
reinterpret_cast<unsigned short*
>(&filtered_msg.data[0]);
457 for (std::size_t i = 0; i < img_size; ++i)
460 msg_data[i] =
static_cast<unsigned short>(filtered_data[i] * 1000 + 0.5);
462 pub_filtered_depth_image_.publish(filtered_msg, *info_msg);
470 const int h_bound = h - skip_vertical_pixels_;
471 const int w_bound =
w - skip_horizontal_pixels_;
475 const uint16_t* input_row =
reinterpret_cast<const uint16_t*
>(&depth_msg->data[0]);
477 for (
int y = skip_vertical_pixels_;
y < h_bound; ++
y, labels_row +=
w, input_row +=
w)
478 for (
int x = skip_horizontal_pixels_;
x < w_bound; ++
x)
483 float zz = (float)input_row[
x] * 1e-3;
484 float yy = y_cache_[
y] * zz;
485 float xx = x_cache_[
x] * zz;
487 tf2::Vector3 point_tf = map_h_sensor * tf2::Vector3(xx, yy, zz);
488 occupied_cells.insert(
tree_->coordToKey(point_tf.getX(), point_tf.getY(), point_tf.getZ()));
493 float zz = input_row[
x] * 1e-3;
494 float yy = y_cache_[
y] * zz;
495 float xx = x_cache_[
x] * zz;
497 tf2::Vector3 point_tf = map_h_sensor * tf2::Vector3(xx, yy, zz);
499 model_cells.insert(
tree_->coordToKey(point_tf.getX(), point_tf.getY(), point_tf.getZ()));
505 const float* input_row =
reinterpret_cast<const float*
>(&depth_msg->data[0]);
507 for (
int y = skip_vertical_pixels_;
y < h_bound; ++
y, labels_row +=
w, input_row +=
w)
508 for (
int x = skip_horizontal_pixels_;
x < w_bound; ++
x)
512 float zz = input_row[
x];
513 float yy = y_cache_[
y] * zz;
514 float xx = x_cache_[
x] * zz;
516 tf2::Vector3 point_tf = map_h_sensor * tf2::Vector3(xx, yy, zz);
517 occupied_cells.insert(
tree_->coordToKey(point_tf.getX(), point_tf.getY(), point_tf.getZ()));
521 float zz = input_row[
x];
522 float yy = y_cache_[
y] * zz;
523 float xx = x_cache_[
x] * zz;
525 tf2::Vector3 point_tf = map_h_sensor * tf2::Vector3(xx, yy, zz);
527 model_cells.insert(
tree_->coordToKey(point_tf.getX(), point_tf.getY(), point_tf.getZ()));
535 RCLCPP_ERROR(LOGGER,
"Internal error while parsing depth data");
541 for (
const octomap::OcTreeKey& model_cell : model_cells)
542 occupied_cells.erase(model_cell);
549 for (
const octomap::OcTreeKey& occupied_cell : occupied_cells)
550 tree_->updateNode(occupied_cell,
true);
554 RCLCPP_ERROR(LOGGER,
"Internal error while updating octree");
556 tree_->unlockWrite();
557 tree_->triggerUpdateCallback();
560 free_space_updater_->pushLazyUpdate(occupied_cells_ptr, model_cells_ptr, sensor_origin);
562 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)
const rclcpp::Logger LOGGER