moveit2
The MoveIt Motion Planning Framework for ROS 2.
depth_image_octomap_updater.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan, Suat Gedikli */
36 
39 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
40 // TODO: Remove conditional includes when released to all active distros.
41 #if __has_include(<tf2/LinearMath/Vector3.hpp>)
42 #include <tf2/LinearMath/Vector3.hpp>
43 #else
44 #include <tf2/LinearMath/Vector3.h>
45 #endif
46 #if __has_include(<tf2/LinearMath/Transform.hpp>)
47 #include <tf2/LinearMath/Transform.hpp>
48 #else
49 #include <tf2/LinearMath/Transform.h>
50 #endif
51 #include <geometric_shapes/shape_operations.h>
52 #include <sensor_msgs/image_encodings.hpp>
53 #include <stdint.h>
54 
55 #include <memory>
56 
57 namespace occupancy_map_monitor
58 {
59 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.perception.depth_image_octomap_updater");
60 
62  : OccupancyMapUpdater("DepthImageUpdater")
63  , image_topic_("depth")
64  , queue_size_(5)
65  , near_clipping_plane_distance_(0.3)
66  , far_clipping_plane_distance_(5.0)
67  , shadow_threshold_(0.04)
68  , padding_scale_(0.0)
69  , padding_offset_(0.02)
70  , max_update_rate_(0)
71  , skip_vertical_pixels_(4)
72  , skip_horizontal_pixels_(6)
73  , image_callback_count_(0)
74  , average_callback_dt_(0.0)
75  , good_tf_(5)
76  , // start optimistically, so we do not output warnings right from the beginning
77  failed_tf_(0)
78  , K0_(0.0)
79  , K2_(0.0)
80  , K4_(0.0)
81  , K5_(0.0)
82 {
83 }
84 
86 {
87  stopHelper();
88 }
89 
90 bool DepthImageOctomapUpdater::setParams(const std::string& name_space)
91 {
92  try
93  {
94  node_->get_parameter(name_space + ".image_topic", image_topic_) &&
95  node_->get_parameter(name_space + ".queue_size", queue_size_) &&
96  node_->get_parameter(name_space + ".near_clipping_plane_distance", near_clipping_plane_distance_) &&
97  node_->get_parameter(name_space + ".far_clipping_plane_distance", far_clipping_plane_distance_) &&
98  node_->get_parameter(name_space + ".shadow_threshold", shadow_threshold_) &&
99  node_->get_parameter(name_space + ".padding_scale", padding_scale_) &&
100  node_->get_parameter(name_space + ".padding_offset", padding_offset_) &&
101  node_->get_parameter(name_space + ".max_update_rate", max_update_rate_) &&
102  node_->get_parameter(name_space + ".skip_vertical_pixels", skip_vertical_pixels_) &&
103  node_->get_parameter(name_space + ".skip_horizontal_pixels", skip_horizontal_pixels_) &&
104  node_->get_parameter(name_space + ".filtered_cloud_topic", filtered_cloud_topic_) &&
105  node_->get_parameter(name_space + ".ns", ns_);
106  return true;
107  }
108  catch (const rclcpp::exceptions::InvalidParameterTypeException& e)
109  {
110  RCLCPP_ERROR_STREAM(LOGGER, e.what() << '\n');
111  return false;
112  }
113 }
114 
115 bool DepthImageOctomapUpdater::initialize(const rclcpp::Node::SharedPtr& node)
116 {
117  node_ = node;
118  input_depth_transport_ = std::make_unique<image_transport::ImageTransport>(node_);
119  model_depth_transport_ = std::make_unique<image_transport::ImageTransport>(node_);
120  filtered_depth_transport_ = std::make_unique<image_transport::ImageTransport>(node_);
121  filtered_label_transport_ = std::make_unique<image_transport::ImageTransport>(node_);
122 
123  tf_buffer_ = monitor_->getTFClient();
124  free_space_updater_ = std::make_unique<LazyFreeSpaceUpdater>(tree_);
125 
126  // create our mesh filter
127  mesh_filter_ = std::make_unique<mesh_filter::MeshFilter<mesh_filter::StereoCameraModel>>(
129  mesh_filter_->parameters().setDepthRange(near_clipping_plane_distance_, far_clipping_plane_distance_);
130  mesh_filter_->setShadowThreshold(shadow_threshold_);
131  mesh_filter_->setPaddingOffset(padding_offset_);
132  mesh_filter_->setPaddingScale(padding_scale_);
133  mesh_filter_->setTransformCallback(
134  [this](mesh_filter::MeshHandle mesh, Eigen::Isometry3d& tf) { return getShapeTransform(mesh, tf); });
135 
136  return true;
137 }
138 
140 {
141  pub_model_depth_image_ = model_depth_transport_->advertiseCamera("model_depth", 1);
142 
143  std::string prefix = "";
144  if (!ns_.empty())
145  prefix = ns_ + "/";
146 
147  pub_model_depth_image_ = model_depth_transport_->advertiseCamera(prefix + "model_depth", 1);
148  if (!filtered_cloud_topic_.empty())
149  pub_filtered_depth_image_ = filtered_depth_transport_->advertiseCamera(prefix + filtered_cloud_topic_, 1);
150  else
151  pub_filtered_depth_image_ = filtered_depth_transport_->advertiseCamera(prefix + "filtered_depth", 1);
152 
153  pub_filtered_label_image_ = filtered_label_transport_->advertiseCamera(prefix + "filtered_label", 1);
154 
155  sub_depth_image_ = image_transport::create_camera_subscription(
156  node_.get(), image_topic_,
157  [this](const sensor_msgs::msg::Image::ConstSharedPtr& depth_msg,
158  const sensor_msgs::msg::CameraInfo::ConstSharedPtr& info_msg) {
159  return depthImageCallback(depth_msg, info_msg);
160  },
161  "raw", rmw_qos_profile_sensor_data);
162 }
163 
165 {
166  stopHelper();
167 }
168 
169 void DepthImageOctomapUpdater::stopHelper()
170 {
171  sub_depth_image_.shutdown();
172 }
173 
175 {
177  if (mesh_filter_)
178  {
179  if (shape->type == shapes::MESH)
180  h = mesh_filter_->addMesh(static_cast<const shapes::Mesh&>(*shape));
181  else
182  {
183  std::unique_ptr<shapes::Mesh> m(shapes::createMeshFromShape(shape.get()));
184  if (m)
185  h = mesh_filter_->addMesh(*m);
186  }
187  }
188  else
189  RCLCPP_ERROR(LOGGER, "Mesh filter not yet initialized!");
190  return h;
191 }
192 
194 {
195  if (mesh_filter_)
196  mesh_filter_->removeMesh(handle);
197 }
198 
199 bool DepthImageOctomapUpdater::getShapeTransform(mesh_filter::MeshHandle h, Eigen::Isometry3d& transform) const
200 {
201  ShapeTransformCache::const_iterator it = transform_cache_.find(h);
202  if (it == transform_cache_.end())
203  {
204  RCLCPP_ERROR(LOGGER, "Internal error. Mesh filter handle %u not found", h);
205  return false;
206  }
207  transform = it->second;
208  return true;
209 }
210 
211 namespace
212 {
213 bool host_is_big_endian()
214 {
215  union
216  {
217  uint32_t i;
218  char c[sizeof(uint32_t)];
219  } bint = { 0x01020304 };
220  return bint.c[0] == 1;
221 }
222 } // namespace
223 
224 static const bool HOST_IS_BIG_ENDIAN = host_is_big_endian();
225 
226 void DepthImageOctomapUpdater::depthImageCallback(const sensor_msgs::msg::Image::ConstSharedPtr& depth_msg,
227  const sensor_msgs::msg::CameraInfo::ConstSharedPtr& info_msg)
228 {
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();
232 
233  if (max_update_rate_ > 0)
234  {
235  // ensure we are not updating the octomap representation too often
236  if (node_->now() - last_update_time_ <= rclcpp::Duration::from_seconds(1.0 / max_update_rate_))
237  return;
238  last_update_time_ = node_->now();
239  }
240 
241  // measure the frequency at which we receive updates
242  if (image_callback_count_ < 1000)
243  {
244  if (image_callback_count_ > 0)
245  {
246  const double dt_start = (start - last_depth_callback_start_).seconds();
247  if (image_callback_count_ < 2)
248  average_callback_dt_ = dt_start;
249  else
250  average_callback_dt_ =
251  ((image_callback_count_ - 1) * average_callback_dt_ + dt_start) / (double)image_callback_count_;
252  }
253  }
254  else
255  // every 1000 updates we reset the counter almost to the beginning (use 2 so we don't have so much of a ripple in
256  // the measured average)
257  image_callback_count_ = 2;
258  last_depth_callback_start_ = start;
259  ++image_callback_count_;
260 
261  if (monitor_->getMapFrame().empty())
262  monitor_->setMapFrame(depth_msg->header.frame_id);
263 
264  /* get transform for cloud into map frame */
265  tf2::Stamped<tf2::Transform> map_h_sensor;
266  if (monitor_->getMapFrame() == depth_msg->header.frame_id)
267  map_h_sensor.setIdentity();
268  else
269  {
270  if (tf_buffer_)
271  {
272  // wait at most 50ms
273  static const double TEST_DT = 0.005;
274  const int nt =
275  static_cast<int>((0.5 + average_callback_dt_ / TEST_DT) * std::max(1, (static_cast<int>(queue_size_) / 2)));
276  bool found = false;
277  std::string err;
278  for (int t = 0; t < nt; ++t)
279  try
280  {
281  tf2::fromMsg(tf_buffer_->lookupTransform(monitor_->getMapFrame(), depth_msg->header.frame_id,
282  depth_msg->header.stamp),
283  map_h_sensor);
284  found = true;
285  break;
286  }
287  catch (tf2::TransformException& ex)
288  {
289  std::chrono::duration<double, std::nano> tmp_duration(TEST_DT);
290  static const rclcpp::Duration D(tmp_duration);
291  err = ex.what();
292  std::this_thread::sleep_for(D.to_chrono<std::chrono::seconds>());
293  }
294  static const unsigned int MAX_TF_COUNTER = 1000; // so we avoid int overflow
295  if (found)
296  {
297  good_tf_++;
298  if (good_tf_ > MAX_TF_COUNTER)
299  {
300  const unsigned int div = MAX_TF_COUNTER / 10;
301  good_tf_ /= div;
302  failed_tf_ /= div;
303  }
304  }
305  else
306  {
307  failed_tf_++;
308  if (failed_tf_ > good_tf_)
309  RCLCPP_WARN_THROTTLE(LOGGER, *node_->get_clock(), 1000,
310  "More than half of the image messages discarded due to TF being unavailable (%u%%). "
311  "Transform error of sensor data: %s; quitting callback.",
312  (100 * failed_tf_) / (good_tf_ + failed_tf_), err.c_str());
313  else
314  RCLCPP_DEBUG_THROTTLE(LOGGER, *node_->get_clock(), 1000,
315  "Transform error of sensor data: %s; quitting callback", err.c_str());
316  if (failed_tf_ > MAX_TF_COUNTER)
317  {
318  const unsigned int div = MAX_TF_COUNTER / 10;
319  good_tf_ /= div;
320  failed_tf_ /= div;
321  }
322  return;
323  }
324  }
325  else
326  return;
327  }
328 
329  if (!updateTransformCache(depth_msg->header.frame_id, depth_msg->header.stamp))
330  return;
331 
332  if (depth_msg->is_bigendian && !HOST_IS_BIG_ENDIAN)
333  RCLCPP_ERROR_THROTTLE(LOGGER, *node_->get_clock(), 1000, "endian problem: received image data does not match host");
334 
335  const int w = depth_msg->width;
336  const int h = depth_msg->height;
337 
338  // call the mesh filter
339  mesh_filter::StereoCameraModel::Parameters& params = mesh_filter_->parameters();
340  params.setCameraParameters(info_msg->k[0], info_msg->k[4], info_msg->k[2], info_msg->k[5]);
341  params.setImageSize(w, h);
342 
343  const bool is_u_short = depth_msg->encoding == sensor_msgs::image_encodings::TYPE_16UC1;
344  if (is_u_short)
345  mesh_filter_->filter(&depth_msg->data[0], GL_UNSIGNED_SHORT);
346  else
347  {
348  if (depth_msg->encoding != sensor_msgs::image_encodings::TYPE_32FC1)
349  {
350  RCLCPP_ERROR_THROTTLE(LOGGER, *node_->get_clock(), 1000, "Unexpected encoding type: '%s'. Ignoring input.",
351  depth_msg->encoding.c_str());
352  return;
353  }
354  mesh_filter_->filter(&depth_msg->data[0], GL_FLOAT);
355  }
356 
357  // the mesh filter runs in background; compute extra things in the meantime
358 
359  // Use correct principal point from calibration
360  const double px = info_msg->k[2];
361  const double py = info_msg->k[5];
362 
363  // if the camera parameters have changed at all, recompute the cache we had
364  if (w >= static_cast<int>(x_cache_.size()) || h >= static_cast<int>(y_cache_.size()) || K2_ != px || K5_ != py ||
365  K0_ != info_msg->k[0] || K4_ != info_msg->k[4])
366  {
367  K2_ = px;
368  K5_ = py;
369  K0_ = info_msg->k[0];
370  K4_ = info_msg->k[4];
371 
372  inv_fx_ = 1.0 / K0_;
373  inv_fy_ = 1.0 / K4_;
374 
375  // if there are any NaNs, discard data
376  if (!(px == px && py == py && inv_fx_ == inv_fx_ && inv_fy_ == inv_fy_))
377  return;
378 
379  // Pre-compute some constants
380  if (static_cast<int>(x_cache_.size()) < w)
381  x_cache_.resize(w);
382  if (static_cast<int>(y_cache_.size()) < h)
383  y_cache_.resize(h);
384 
385  for (int x = 0; x < w; ++x)
386  x_cache_[x] = (x - px) * inv_fx_;
387 
388  for (int y = 0; y < h; ++y)
389  y_cache_[y] = (y - py) * inv_fy_;
390  }
391 
392  const octomap::point3d sensor_origin(map_h_sensor.getOrigin().getX(), map_h_sensor.getOrigin().getY(),
393  map_h_sensor.getOrigin().getZ());
394 
395  octomap::KeySet* occupied_cells_ptr = new octomap::KeySet();
396  octomap::KeySet* model_cells_ptr = new octomap::KeySet();
397  octomap::KeySet& occupied_cells = *occupied_cells_ptr;
398  octomap::KeySet& model_cells = *model_cells_ptr;
399 
400  // allocate memory if needed
401  std::size_t img_size = h * w;
402  if (filtered_labels_.size() < img_size)
403  filtered_labels_.resize(img_size);
404 
405  // get the labels of the filtered data
406  const unsigned int* labels_row = &filtered_labels_[0];
407  mesh_filter_->getFilteredLabels(&filtered_labels_[0]);
408 
409  // publish debug information if needed
410  if (debug_info_)
411  {
412  sensor_msgs::msg::Image debug_msg;
413  debug_msg.header = depth_msg->header;
414  debug_msg.height = h;
415  debug_msg.width = w;
416  debug_msg.is_bigendian = HOST_IS_BIG_ENDIAN;
417  debug_msg.encoding = sensor_msgs::image_encodings::TYPE_32FC1;
418  debug_msg.step = w * sizeof(float);
419  debug_msg.data.resize(img_size * sizeof(float));
420  mesh_filter_->getModelDepth(reinterpret_cast<float*>(&debug_msg.data[0]));
421  pub_model_depth_image_.publish(debug_msg, *info_msg);
422 
423  sensor_msgs::msg::Image filtered_depth_msg;
424  filtered_depth_msg.header = depth_msg->header;
425  filtered_depth_msg.height = h;
426  filtered_depth_msg.width = w;
427  filtered_depth_msg.is_bigendian = HOST_IS_BIG_ENDIAN;
428  filtered_depth_msg.encoding = sensor_msgs::image_encodings::TYPE_32FC1;
429  filtered_depth_msg.step = w * sizeof(float);
430  filtered_depth_msg.data.resize(img_size * sizeof(float));
431  mesh_filter_->getFilteredDepth(reinterpret_cast<float*>(&filtered_depth_msg.data[0]));
432  pub_filtered_depth_image_.publish(filtered_depth_msg, *info_msg);
433 
434  sensor_msgs::msg::Image label_msg;
435  label_msg.header = depth_msg->header;
436  label_msg.height = h;
437  label_msg.width = w;
438  label_msg.is_bigendian = HOST_IS_BIG_ENDIAN;
439  label_msg.encoding = sensor_msgs::image_encodings::RGBA8;
440  label_msg.step = w * sizeof(unsigned int);
441  label_msg.data.resize(img_size * sizeof(unsigned int));
442  mesh_filter_->getFilteredLabels(reinterpret_cast<unsigned int*>(&label_msg.data[0]));
443 
444  pub_filtered_label_image_.publish(label_msg, *info_msg);
445  }
446 
447  if (!filtered_cloud_topic_.empty())
448  {
449  sensor_msgs::msg::Image filtered_msg;
450  filtered_msg.header = depth_msg->header;
451  filtered_msg.height = h;
452  filtered_msg.width = w;
453  filtered_msg.is_bigendian = HOST_IS_BIG_ENDIAN;
454  filtered_msg.encoding = sensor_msgs::image_encodings::TYPE_16UC1;
455  filtered_msg.step = w * sizeof(unsigned short);
456  filtered_msg.data.resize(img_size * sizeof(unsigned short));
457 
458  // reuse float buffer across callbacks
459  static std::vector<float> filtered_data;
460  if (filtered_data.size() < img_size)
461  filtered_data.resize(img_size);
462 
463  mesh_filter_->getFilteredDepth(reinterpret_cast<float*>(&filtered_data[0]));
464  unsigned short* msg_data = reinterpret_cast<unsigned short*>(&filtered_msg.data[0]);
465  for (std::size_t i = 0; i < img_size; ++i)
466  {
467  // rescale depth to millimeter to work with `unsigned short`
468  msg_data[i] = static_cast<unsigned short>(filtered_data[i] * 1000 + 0.5);
469  }
470  pub_filtered_depth_image_.publish(filtered_msg, *info_msg);
471  }
472 
473  // figure out occupied cells and model cells
474  tree_->lockRead();
475 
476  try
477  {
478  const int h_bound = h - skip_vertical_pixels_;
479  const int w_bound = w - skip_horizontal_pixels_;
480 
481  if (is_u_short)
482  {
483  const uint16_t* input_row = reinterpret_cast<const uint16_t*>(&depth_msg->data[0]);
484 
485  for (int y = skip_vertical_pixels_; y < h_bound; ++y, labels_row += w, input_row += w)
486  for (int x = skip_horizontal_pixels_; x < w_bound; ++x)
487  {
488  // not filtered
489  if (labels_row[x] == mesh_filter::MeshFilterBase::BACKGROUND)
490  {
491  float zz = (float)input_row[x] * 1e-3; // scale from mm to m
492  float yy = y_cache_[y] * zz;
493  float xx = x_cache_[x] * zz;
494  /* transform to map frame */
495  tf2::Vector3 point_tf = map_h_sensor * tf2::Vector3(xx, yy, zz);
496  occupied_cells.insert(tree_->coordToKey(point_tf.getX(), point_tf.getY(), point_tf.getZ()));
497  }
498  // on far plane or a model point -> remove
499  else if (labels_row[x] >= mesh_filter::MeshFilterBase::FAR_CLIP)
500  {
501  float zz = input_row[x] * 1e-3;
502  float yy = y_cache_[y] * zz;
503  float xx = x_cache_[x] * zz;
504  /* transform to map frame */
505  tf2::Vector3 point_tf = map_h_sensor * tf2::Vector3(xx, yy, zz);
506  // add to the list of model cells
507  model_cells.insert(tree_->coordToKey(point_tf.getX(), point_tf.getY(), point_tf.getZ()));
508  }
509  }
510  }
511  else
512  {
513  const float* input_row = reinterpret_cast<const float*>(&depth_msg->data[0]);
514 
515  for (int y = skip_vertical_pixels_; y < h_bound; ++y, labels_row += w, input_row += w)
516  for (int x = skip_horizontal_pixels_; x < w_bound; ++x)
517  {
518  if (labels_row[x] == mesh_filter::MeshFilterBase::BACKGROUND)
519  {
520  float zz = input_row[x];
521  float yy = y_cache_[y] * zz;
522  float xx = x_cache_[x] * zz;
523  /* transform to map frame */
524  tf2::Vector3 point_tf = map_h_sensor * tf2::Vector3(xx, yy, zz);
525  occupied_cells.insert(tree_->coordToKey(point_tf.getX(), point_tf.getY(), point_tf.getZ()));
526  }
527  else if (labels_row[x] >= mesh_filter::MeshFilterBase::FAR_CLIP)
528  {
529  float zz = input_row[x];
530  float yy = y_cache_[y] * zz;
531  float xx = x_cache_[x] * zz;
532  /* transform to map frame */
533  tf2::Vector3 point_tf = map_h_sensor * tf2::Vector3(xx, yy, zz);
534  // add to the list of model cells
535  model_cells.insert(tree_->coordToKey(point_tf.getX(), point_tf.getY(), point_tf.getZ()));
536  }
537  }
538  }
539  }
540  catch (...)
541  {
542  tree_->unlockRead();
543  RCLCPP_ERROR(LOGGER, "Internal error while parsing depth data");
544  return;
545  }
546  tree_->unlockRead();
547 
548  /* cells that overlap with the model are not occupied */
549  for (const octomap::OcTreeKey& model_cell : model_cells)
550  occupied_cells.erase(model_cell);
551 
552  // mark occupied cells
553  tree_->lockWrite();
554  try
555  {
556  /* now mark all occupied cells */
557  for (const octomap::OcTreeKey& occupied_cell : occupied_cells)
558  tree_->updateNode(occupied_cell, true);
559  }
560  catch (...)
561  {
562  RCLCPP_ERROR(LOGGER, "Internal error while updating octree");
563  }
564  tree_->unlockWrite();
565  tree_->triggerUpdateCallback();
566 
567  // at this point we still have not freed the space
568  free_space_updater_->pushLazyUpdate(occupied_cells_ptr, model_cells_ptr, sensor_origin);
569 
570  RCLCPP_DEBUG(LOGGER, "Processed depth image in %lf ms", (node_->now() - start).seconds() * 1000.0);
571 }
572 } // namespace occupancy_map_monitor
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)
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
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.
collision_detection::OccMapTreePtr tree_
bool updateTransformCache(const std::string &target_frame, const rclcpp::Time &target_time)
unsigned int MeshHandle
w
Definition: pick.py:67
x
Definition: pick.py:64
y
Definition: pick.py:65
const rclcpp::Logger LOGGER
Definition: async_test.h:31