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 <sensor_msgs/point_cloud2_iterator.hpp> 
   53 #include <tf2_ros/create_timer_interface.h> 
   54 #include <tf2_ros/create_timer_ros.h> 
   60 static const rclcpp::Logger 
LOGGER = rclcpp::get_logger(
"moveit.ros.perception.pointcloud_octomap_updater");
 
   65   , max_range_(std::numeric_limits<double>::infinity())
 
   68   , point_cloud_subscriber_(nullptr)
 
   69   , point_cloud_filter_(nullptr)
 
   81   node_->get_parameter_or(name_space + 
".ns", ns_, std::string());
 
   82   return node_->get_parameter(name_space + 
".point_cloud_topic", point_cloud_topic_) &&
 
   83          node_->get_parameter(name_space + 
".max_range", max_range_) &&
 
   84          node_->get_parameter(name_space + 
".padding_offset", padding_) &&
 
   85          node_->get_parameter(name_space + 
".padding_scale", scale_) &&
 
   86          node_->get_parameter(name_space + 
".point_subsample", point_subsample_) &&
 
   87          node_->get_parameter(name_space + 
".max_update_rate", max_update_rate_) &&
 
   88          node_->get_parameter(name_space + 
".filtered_cloud_topic", filtered_cloud_topic_);
 
   94   tf_buffer_ = std::make_shared<tf2_ros::Buffer>(node_->get_clock());
 
   95   auto create_timer_interface =
 
   96       std::make_shared<tf2_ros::CreateTimerROS>(node->get_node_base_interface(), node->get_node_timers_interface());
 
   97   tf_buffer_->setCreateTimerInterface(create_timer_interface);
 
   98   tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
 
   99   shape_mask_ = std::make_unique<point_containment_filter::ShapeMask>();
 
  100   shape_mask_->setTransformCallback(
 
  101       [
this](
ShapeHandle shape, Eigen::Isometry3d& tf) { 
return getShapeTransform(shape, tf); });
 
  108   std::string prefix = 
"";
 
  112   rclcpp::QoS qos(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_sensor_data));
 
  113   if (!filtered_cloud_topic_.empty())
 
  115     filtered_cloud_publisher_ =
 
  116         node_->create_publisher<sensor_msgs::msg::PointCloud2>(prefix + filtered_cloud_topic_, rclcpp::SensorDataQoS());
 
  119   if (point_cloud_subscriber_)
 
  122   rclcpp::SubscriptionOptions 
options;
 
  123   options.callback_group = node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
 
  125   point_cloud_subscriber_ = 
new message_filters::Subscriber<sensor_msgs::msg::PointCloud2>(
 
  126       node_, point_cloud_topic_, rmw_qos_profile_sensor_data, 
options);
 
  129     point_cloud_filter_ = 
new tf2_ros::MessageFilter<sensor_msgs::msg::PointCloud2>(
 
  131     point_cloud_filter_->registerCallback(
 
  132         [
this](
const sensor_msgs::msg::PointCloud2::ConstSharedPtr& cloud) { cloudMsgCallback(cloud); });
 
  133     RCLCPP_INFO(LOGGER, 
"Listening to '%s' using message filter with target frame '%s'", point_cloud_topic_.c_str(),
 
  134                 point_cloud_filter_->getTargetFramesString().c_str());
 
  138     point_cloud_subscriber_->registerCallback(
 
  139         [
this](
const sensor_msgs::msg::PointCloud2::ConstSharedPtr& cloud) { cloudMsgCallback(cloud); });
 
  140     RCLCPP_INFO(LOGGER, 
"Listening to '%s'", point_cloud_topic_.c_str());
 
  144 void PointCloudOctomapUpdater::stopHelper()
 
  146   delete point_cloud_filter_;
 
  147   delete point_cloud_subscriber_;
 
  153   point_cloud_filter_ = 
nullptr;
 
  154   point_cloud_subscriber_ = 
nullptr;
 
  161     h = shape_mask_->addShape(shape, scale_, padding_);
 
  163     RCLCPP_ERROR(LOGGER, 
"Shape filter not yet initialized!");
 
  170     shape_mask_->removeShape(handle);
 
  173 bool PointCloudOctomapUpdater::getShapeTransform(
ShapeHandle h, Eigen::Isometry3d& transform)
 const 
  178     transform = it->second;
 
  188 void PointCloudOctomapUpdater::cloudMsgCallback(
const sensor_msgs::msg::PointCloud2::ConstSharedPtr& cloud_msg)
 
  190   RCLCPP_DEBUG(LOGGER, 
"Received a new point cloud message");
 
  191   rclcpp::Time 
start = rclcpp::Clock(RCL_ROS_TIME).now();
 
  193   if (max_update_rate_ > 0)
 
  196     if ((node_->now() - last_update_time_) <= rclcpp::Duration::from_seconds(1.0 / max_update_rate_))
 
  198     last_update_time_ = node_->now();
 
  205   tf2::Stamped<tf2::Transform> map_h_sensor;
 
  207     map_h_sensor.setIdentity();
 
  214         tf2::fromMsg(tf_buffer_->lookupTransform(
monitor_->
getMapFrame(), cloud_msg->header.frame_id,
 
  215                                                  cloud_msg->header.stamp),
 
  218       catch (tf2::TransformException& ex)
 
  220         RCLCPP_ERROR_STREAM(LOGGER, 
"Transform error of sensor data: " << ex.what() << 
"; quitting callback");
 
  229   const tf2::Vector3& sensor_origin_tf = map_h_sensor.getOrigin();
 
  230   octomap::point3d sensor_origin(sensor_origin_tf.getX(), sensor_origin_tf.getY(), sensor_origin_tf.getZ());
 
  231   Eigen::Vector3d sensor_origin_eigen(sensor_origin_tf.getX(), sensor_origin_tf.getY(), sensor_origin_tf.getZ());
 
  237   shape_mask_->maskContainment(*cloud_msg, sensor_origin_eigen, 0.0, max_range_, mask_);
 
  238   updateMask(*cloud_msg, sensor_origin_eigen, mask_);
 
  240   octomap::KeySet free_cells, occupied_cells, model_cells, clip_cells;
 
  241   std::unique_ptr<sensor_msgs::msg::PointCloud2> filtered_cloud;
 
  246   std::unique_ptr<sensor_msgs::PointCloud2Iterator<float>> iter_filtered_x;
 
  247   std::unique_ptr<sensor_msgs::PointCloud2Iterator<float>> iter_filtered_y;
 
  248   std::unique_ptr<sensor_msgs::PointCloud2Iterator<float>> iter_filtered_z;
 
  250   if (!filtered_cloud_topic_.empty())
 
  252     filtered_cloud = std::make_unique<sensor_msgs::msg::PointCloud2>();
 
  253     filtered_cloud->header = cloud_msg->header;
 
  254     sensor_msgs::PointCloud2Modifier pcd_modifier(*filtered_cloud);
 
  255     pcd_modifier.setPointCloud2FieldsByString(1, 
"xyz");
 
  256     pcd_modifier.resize(cloud_msg->width * cloud_msg->height);
 
  259     iter_filtered_x = std::make_unique<sensor_msgs::PointCloud2Iterator<float>>(*filtered_cloud, 
"x");
 
  260     iter_filtered_y = std::make_unique<sensor_msgs::PointCloud2Iterator<float>>(*filtered_cloud, 
"y");
 
  261     iter_filtered_z = std::make_unique<sensor_msgs::PointCloud2Iterator<float>>(*filtered_cloud, 
"z");
 
  263   size_t filtered_cloud_size = 0;
 
  271     for (
unsigned int row = 0; row < cloud_msg->height; row += point_subsample_)
 
  273       unsigned int row_c = row * cloud_msg->width;
 
  274       sensor_msgs::PointCloud2ConstIterator<float> pt_iter(*cloud_msg, 
"x");
 
  278       for (
unsigned int col = 0; col < cloud_msg->width; col += point_subsample_, pt_iter += point_subsample_)
 
  284         if (!std::isnan(pt_iter[0]) && !std::isnan(pt_iter[1]) && !std::isnan(pt_iter[2]))
 
  291             tf2::Vector3 point_tf = map_h_sensor * tf2::Vector3(pt_iter[0], pt_iter[1], pt_iter[2]);
 
  292             model_cells.insert(
tree_->coordToKey(point_tf.getX(), point_tf.getY(), point_tf.getZ()));
 
  296             tf2::Vector3 clipped_point_tf =
 
  297                 map_h_sensor * (tf2::Vector3(pt_iter[0], pt_iter[1], pt_iter[2]).normalize() * max_range_);
 
  299                 tree_->coordToKey(clipped_point_tf.getX(), clipped_point_tf.getY(), clipped_point_tf.getZ()));
 
  303             tf2::Vector3 point_tf = map_h_sensor * tf2::Vector3(pt_iter[0], pt_iter[1], pt_iter[2]);
 
  304             occupied_cells.insert(
tree_->coordToKey(point_tf.getX(), point_tf.getY(), point_tf.getZ()));
 
  308               **iter_filtered_x = pt_iter[0];
 
  309               **iter_filtered_y = pt_iter[1];
 
  310               **iter_filtered_z = pt_iter[2];
 
  311               ++filtered_cloud_size;
 
  322     for (
const octomap::OcTreeKey& occupied_cell : occupied_cells)
 
  323       if (
tree_->computeRayKeys(sensor_origin, 
tree_->keyToCoord(occupied_cell), key_ray_))
 
  324         free_cells.insert(key_ray_.begin(), key_ray_.end());
 
  327     for (
const octomap::OcTreeKey& model_cell : model_cells)
 
  328       if (
tree_->computeRayKeys(sensor_origin, 
tree_->keyToCoord(model_cell), key_ray_))
 
  329         free_cells.insert(key_ray_.begin(), key_ray_.end());
 
  332     for (
const octomap::OcTreeKey& clip_cell : clip_cells)
 
  334       free_cells.insert(clip_cell);
 
  335       if (
tree_->computeRayKeys(sensor_origin, 
tree_->keyToCoord(clip_cell), key_ray_))
 
  336         free_cells.insert(key_ray_.begin(), key_ray_.end());
 
  348   for (
const octomap::OcTreeKey& model_cell : model_cells)
 
  349     occupied_cells.erase(model_cell);
 
  352   for (
const octomap::OcTreeKey& occupied_cell : occupied_cells)
 
  353     free_cells.erase(occupied_cell);
 
  360     for (
const octomap::OcTreeKey& free_cell : free_cells)
 
  361       tree_->updateNode(free_cell, 
false);
 
  364     for (
const octomap::OcTreeKey& occupied_cell : occupied_cells)
 
  365       tree_->updateNode(occupied_cell, 
true);
 
  368     const float lg = 
tree_->getClampingThresMinLog() - 
tree_->getClampingThresMaxLog();
 
  369     for (
const octomap::OcTreeKey& model_cell : model_cells)
 
  370       tree_->updateNode(model_cell, lg);
 
  374     RCLCPP_ERROR(LOGGER, 
"Internal error while updating octree");
 
  376   tree_->unlockWrite();
 
  377   RCLCPP_DEBUG(LOGGER, 
"Processed point cloud in %lf ms", (node_->now() - 
start).seconds() * 1000.0);
 
  378   tree_->triggerUpdateCallback();
 
  382     sensor_msgs::PointCloud2Modifier pcd_modifier(*filtered_cloud);
 
  383     pcd_modifier.resize(filtered_cloud_size);
 
  384     filtered_cloud_publisher_->publish(*filtered_cloud);
 
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)
 
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...
 
PointCloudOctomapUpdater()
 
virtual void updateMask(const sensor_msgs::msg::PointCloud2 &cloud, const Eigen::Vector3d &sensor_origin, std::vector< int > &mask)
 
bool initialize(const rclcpp::Node::SharedPtr &node) override
Do any necessary setup (subscribe to ros topics, etc.). This call assumes setMonitor() and setParams(...
 
void forgetShape(ShapeHandle handle) override
 
ShapeHandle excludeShape(const shapes::ShapeConstPtr &shape) override
 
~PointCloudOctomapUpdater() override
 
Vec3fX< details::Vec3Data< double > > Vector3d
 
const rclcpp::Logger LOGGER