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 #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>
44 #include <stdint.h>
45 
46 #include <memory>
47 
48 namespace occupancy_map_monitor
49 {
50 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.perception.depth_image_octomap_updater");
51 
53  : OccupancyMapUpdater("DepthImageUpdater")
54  , image_topic_("depth")
55  , queue_size_(5)
56  , near_clipping_plane_distance_(0.3)
57  , far_clipping_plane_distance_(5.0)
58  , shadow_threshold_(0.04)
59  , padding_scale_(0.0)
60  , padding_offset_(0.02)
61  , max_update_rate_(0)
62  , skip_vertical_pixels_(4)
63  , skip_horizontal_pixels_(6)
64  , image_callback_count_(0)
65  , average_callback_dt_(0.0)
66  , good_tf_(5)
67  , // start optimistically, so we do not output warnings right from the beginning
68  failed_tf_(0)
69  , K0_(0.0)
70  , K2_(0.0)
71  , K4_(0.0)
72  , K5_(0.0)
73 {
74 }
75 
77 {
78  stopHelper();
79 }
80 
81 bool DepthImageOctomapUpdater::setParams(const std::string& name_space)
82 {
83  try
84  {
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_);
97  return true;
98  }
99  catch (const rclcpp::exceptions::InvalidParameterTypeException& e)
100  {
101  RCLCPP_ERROR_STREAM(LOGGER, e.what() << '\n');
102  return false;
103  }
104 }
105 
106 bool DepthImageOctomapUpdater::initialize(const rclcpp::Node::SharedPtr& node)
107 {
108  node_ = node;
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_);
113 
114  tf_buffer_ = monitor_->getTFClient();
115  free_space_updater_ = std::make_unique<LazyFreeSpaceUpdater>(tree_);
116 
117  // create our mesh filter
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(
125  [this](mesh_filter::MeshHandle mesh, Eigen::Isometry3d& tf) { return getShapeTransform(mesh, tf); });
126 
127  return true;
128 }
129 
131 {
132  rmw_qos_profile_t custom_qos = rmw_qos_profile_system_default;
133  pub_model_depth_image_ = model_depth_transport_->advertiseCamera("model_depth", 1);
134 
135  std::string prefix = "";
136  if (!ns_.empty())
137  prefix = ns_ + "/";
138 
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);
142  else
143  pub_filtered_depth_image_ = filtered_depth_transport_->advertiseCamera(prefix + "filtered_depth", 1);
144 
145  pub_filtered_label_image_ = filtered_label_transport_->advertiseCamera(prefix + "filtered_label", 1);
146 
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);
152  },
153  "raw", custom_qos);
154 }
155 
157 {
158  stopHelper();
159 }
160 
161 void DepthImageOctomapUpdater::stopHelper()
162 {
163  sub_depth_image_.shutdown();
164 }
165 
167 {
169  if (mesh_filter_)
170  {
171  if (shape->type == shapes::MESH)
172  h = mesh_filter_->addMesh(static_cast<const shapes::Mesh&>(*shape));
173  else
174  {
175  std::unique_ptr<shapes::Mesh> m(shapes::createMeshFromShape(shape.get()));
176  if (m)
177  h = mesh_filter_->addMesh(*m);
178  }
179  }
180  else
181  RCLCPP_ERROR(LOGGER, "Mesh filter not yet initialized!");
182  return h;
183 }
184 
186 {
187  if (mesh_filter_)
188  mesh_filter_->removeMesh(handle);
189 }
190 
191 bool DepthImageOctomapUpdater::getShapeTransform(mesh_filter::MeshHandle h, Eigen::Isometry3d& transform) const
192 {
193  ShapeTransformCache::const_iterator it = transform_cache_.find(h);
194  if (it == transform_cache_.end())
195  {
196  RCLCPP_ERROR(LOGGER, "Internal error. Mesh filter handle %u not found", h);
197  return false;
198  }
199  transform = it->second;
200  return true;
201 }
202 
203 namespace
204 {
205 bool host_is_big_endian()
206 {
207  union
208  {
209  uint32_t i;
210  char c[sizeof(uint32_t)];
211  } bint = { 0x01020304 };
212  return bint.c[0] == 1;
213 }
214 } // namespace
215 
216 static const bool HOST_IS_BIG_ENDIAN = host_is_big_endian();
217 
218 void DepthImageOctomapUpdater::depthImageCallback(const sensor_msgs::msg::Image::ConstSharedPtr& depth_msg,
219  const sensor_msgs::msg::CameraInfo::ConstSharedPtr& info_msg)
220 {
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();
224 
225  if (max_update_rate_ > 0)
226  {
227  // ensure we are not updating the octomap representation too often
228  if (node_->now() - last_update_time_ <= rclcpp::Duration::from_seconds(1.0 / max_update_rate_))
229  return;
230  last_update_time_ = node_->now();
231  }
232 
233  // measure the frequency at which we receive updates
234  if (image_callback_count_ < 1000)
235  {
236  if (image_callback_count_ > 0)
237  {
238  const double dt_start = (start - last_depth_callback_start_).seconds();
239  if (image_callback_count_ < 2)
240  average_callback_dt_ = dt_start;
241  else
242  average_callback_dt_ =
243  ((image_callback_count_ - 1) * average_callback_dt_ + dt_start) / (double)image_callback_count_;
244  }
245  }
246  else
247  // every 1000 updates we reset the counter almost to the beginning (use 2 so we don't have so much of a ripple in
248  // the measured average)
249  image_callback_count_ = 2;
250  last_depth_callback_start_ = start;
251  ++image_callback_count_;
252 
253  if (monitor_->getMapFrame().empty())
254  monitor_->setMapFrame(depth_msg->header.frame_id);
255 
256  /* get transform for cloud into map frame */
257  tf2::Stamped<tf2::Transform> map_h_sensor;
258  if (monitor_->getMapFrame() == depth_msg->header.frame_id)
259  map_h_sensor.setIdentity();
260  else
261  {
262  if (tf_buffer_)
263  {
264  // wait at most 50ms
265  static const double TEST_DT = 0.005;
266  const int nt =
267  static_cast<int>((0.5 + average_callback_dt_ / TEST_DT) * std::max(1, (static_cast<int>(queue_size_) / 2)));
268  bool found = false;
269  std::string err;
270  for (int t = 0; t < nt; ++t)
271  try
272  {
273  tf2::fromMsg(tf_buffer_->lookupTransform(monitor_->getMapFrame(), depth_msg->header.frame_id,
274  depth_msg->header.stamp),
275  map_h_sensor);
276  found = true;
277  break;
278  }
279  catch (tf2::TransformException& ex)
280  {
281  std::chrono::duration<double, std::nano> tmp_duration(TEST_DT);
282  static const rclcpp::Duration D(tmp_duration);
283  err = ex.what();
284  std::this_thread::sleep_for(D.to_chrono<std::chrono::seconds>());
285  }
286  static const unsigned int MAX_TF_COUNTER = 1000; // so we avoid int overflow
287  if (found)
288  {
289  good_tf_++;
290  if (good_tf_ > MAX_TF_COUNTER)
291  {
292  const unsigned int div = MAX_TF_COUNTER / 10;
293  good_tf_ /= div;
294  failed_tf_ /= div;
295  }
296  }
297  else
298  {
299  failed_tf_++;
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());
305  else
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)
309  {
310  const unsigned int div = MAX_TF_COUNTER / 10;
311  good_tf_ /= div;
312  failed_tf_ /= div;
313  }
314  return;
315  }
316  }
317  else
318  return;
319  }
320 
321  if (!updateTransformCache(depth_msg->header.frame_id, depth_msg->header.stamp))
322  return;
323 
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");
326 
327  const int w = depth_msg->width;
328  const int h = depth_msg->height;
329 
330  // call the mesh filter
331  mesh_filter::StereoCameraModel::Parameters& params = mesh_filter_->parameters();
332  params.setCameraParameters(info_msg->k[0], info_msg->k[4], info_msg->k[2], info_msg->k[5]);
333  params.setImageSize(w, h);
334 
335  const bool is_u_short = depth_msg->encoding == sensor_msgs::image_encodings::TYPE_16UC1;
336  if (is_u_short)
337  mesh_filter_->filter(&depth_msg->data[0], GL_UNSIGNED_SHORT);
338  else
339  {
340  if (depth_msg->encoding != sensor_msgs::image_encodings::TYPE_32FC1)
341  {
342  RCLCPP_ERROR_THROTTLE(LOGGER, *node_->get_clock(), 1000, "Unexpected encoding type: '%s'. Ignoring input.",
343  depth_msg->encoding.c_str());
344  return;
345  }
346  mesh_filter_->filter(&depth_msg->data[0], GL_FLOAT);
347  }
348 
349  // the mesh filter runs in background; compute extra things in the meantime
350 
351  // Use correct principal point from calibration
352  const double px = info_msg->k[2];
353  const double py = info_msg->k[5];
354 
355  // if the camera parameters have changed at all, recompute the cache we had
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])
358  {
359  K2_ = px;
360  K5_ = py;
361  K0_ = info_msg->k[0];
362  K4_ = info_msg->k[4];
363 
364  inv_fx_ = 1.0 / K0_;
365  inv_fy_ = 1.0 / K4_;
366 
367  // if there are any NaNs, discard data
368  if (!(px == px && py == py && inv_fx_ == inv_fx_ && inv_fy_ == inv_fy_))
369  return;
370 
371  // Pre-compute some constants
372  if (static_cast<int>(x_cache_.size()) < w)
373  x_cache_.resize(w);
374  if (static_cast<int>(y_cache_.size()) < h)
375  y_cache_.resize(h);
376 
377  for (int x = 0; x < w; ++x)
378  x_cache_[x] = (x - px) * inv_fx_;
379 
380  for (int y = 0; y < h; ++y)
381  y_cache_[y] = (y - py) * inv_fy_;
382  }
383 
384  const octomap::point3d sensor_origin(map_h_sensor.getOrigin().getX(), map_h_sensor.getOrigin().getY(),
385  map_h_sensor.getOrigin().getZ());
386 
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;
391 
392  // allocate memory if needed
393  std::size_t img_size = h * w;
394  if (filtered_labels_.size() < img_size)
395  filtered_labels_.resize(img_size);
396 
397  // get the labels of the filtered data
398  const unsigned int* labels_row = &filtered_labels_[0];
399  mesh_filter_->getFilteredLabels(&filtered_labels_[0]);
400 
401  // publish debug information if needed
402  if (debug_info_)
403  {
404  sensor_msgs::msg::Image debug_msg;
405  debug_msg.header = depth_msg->header;
406  debug_msg.height = h;
407  debug_msg.width = w;
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);
414 
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);
425 
426  sensor_msgs::msg::Image label_msg;
427  label_msg.header = depth_msg->header;
428  label_msg.height = h;
429  label_msg.width = w;
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]));
435 
436  pub_filtered_label_image_.publish(label_msg, *info_msg);
437  }
438 
439  if (!filtered_cloud_topic_.empty())
440  {
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));
449 
450  // reuse float buffer across callbacks
451  static std::vector<float> filtered_data;
452  if (filtered_data.size() < img_size)
453  filtered_data.resize(img_size);
454 
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)
458  {
459  // rescale depth to millimeter to work with `unsigned short`
460  msg_data[i] = static_cast<unsigned short>(filtered_data[i] * 1000 + 0.5);
461  }
462  pub_filtered_depth_image_.publish(filtered_msg, *info_msg);
463  }
464 
465  // figure out occupied cells and model cells
466  tree_->lockRead();
467 
468  try
469  {
470  const int h_bound = h - skip_vertical_pixels_;
471  const int w_bound = w - skip_horizontal_pixels_;
472 
473  if (is_u_short)
474  {
475  const uint16_t* input_row = reinterpret_cast<const uint16_t*>(&depth_msg->data[0]);
476 
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)
479  {
480  // not filtered
481  if (labels_row[x] == mesh_filter::MeshFilterBase::BACKGROUND)
482  {
483  float zz = (float)input_row[x] * 1e-3; // scale from mm to m
484  float yy = y_cache_[y] * zz;
485  float xx = x_cache_[x] * zz;
486  /* transform to map frame */
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()));
489  }
490  // on far plane or a model point -> remove
491  else if (labels_row[x] >= mesh_filter::MeshFilterBase::FAR_CLIP)
492  {
493  float zz = input_row[x] * 1e-3;
494  float yy = y_cache_[y] * zz;
495  float xx = x_cache_[x] * zz;
496  /* transform to map frame */
497  tf2::Vector3 point_tf = map_h_sensor * tf2::Vector3(xx, yy, zz);
498  // add to the list of model cells
499  model_cells.insert(tree_->coordToKey(point_tf.getX(), point_tf.getY(), point_tf.getZ()));
500  }
501  }
502  }
503  else
504  {
505  const float* input_row = reinterpret_cast<const float*>(&depth_msg->data[0]);
506 
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)
509  {
510  if (labels_row[x] == mesh_filter::MeshFilterBase::BACKGROUND)
511  {
512  float zz = input_row[x];
513  float yy = y_cache_[y] * zz;
514  float xx = x_cache_[x] * zz;
515  /* transform to map frame */
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()));
518  }
519  else if (labels_row[x] >= mesh_filter::MeshFilterBase::FAR_CLIP)
520  {
521  float zz = input_row[x];
522  float yy = y_cache_[y] * zz;
523  float xx = x_cache_[x] * zz;
524  /* transform to map frame */
525  tf2::Vector3 point_tf = map_h_sensor * tf2::Vector3(xx, yy, zz);
526  // add to the list of model cells
527  model_cells.insert(tree_->coordToKey(point_tf.getX(), point_tf.getY(), point_tf.getZ()));
528  }
529  }
530  }
531  }
532  catch (...)
533  {
534  tree_->unlockRead();
535  RCLCPP_ERROR(LOGGER, "Internal error while parsing depth data");
536  return;
537  }
538  tree_->unlockRead();
539 
540  /* cells that overlap with the model are not occupied */
541  for (const octomap::OcTreeKey& model_cell : model_cells)
542  occupied_cells.erase(model_cell);
543 
544  // mark occupied cells
545  tree_->lockWrite();
546  try
547  {
548  /* now mark all occupied cells */
549  for (const octomap::OcTreeKey& occupied_cell : occupied_cells)
550  tree_->updateNode(occupied_cell, true);
551  }
552  catch (...)
553  {
554  RCLCPP_ERROR(LOGGER, "Internal error while updating octree");
555  }
556  tree_->unlockWrite();
557  tree_->triggerUpdateCallback();
558 
559  // at this point we still have not freed the space
560  free_space_updater_->pushLazyUpdate(occupied_cells_ptr, model_cells_ptr, sensor_origin);
561 
562  RCLCPP_DEBUG(LOGGER, "Processed depth image in %lf ms", (node_->now() - start).seconds() * 1000.0);
563 }
564 } // 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