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>
54#if RCLCPP_VERSION_GTE(29, 6, 0)
55#include <tf2_ros/create_timer_interface.hpp>
56#include <tf2_ros/create_timer_ros.hpp>
59#include <tf2_ros/create_timer_interface.h>
60#include <tf2_ros/create_timer_ros.h>
63#include <rclcpp/version.h>
73 , max_range_(std::numeric_limits<double>::infinity())
76 , point_cloud_subscriber_(nullptr)
77 , point_cloud_filter_(nullptr)
78 , logger_(
moveit::getLogger(
"moveit.ros.pointcloud_octomap_updater"))
84 auto check_required = [
this, &name_space](
const std::string& key,
auto& target,
85 std::vector<std::string>& missing_keys) {
86 if (!this->node_->get_parameter(name_space +
"." + key, target))
88 missing_keys.push_back(key);
92 node_->get_parameter_or(name_space +
".ns", ns_, std::string());
94 std::vector<std::string> missing_keys;
96 check_required(
"point_cloud_topic", point_cloud_topic_, missing_keys);
97 check_required(
"max_range", max_range_, missing_keys);
98 check_required(
"padding_offset", padding_, missing_keys);
99 check_required(
"padding_scale", scale_, missing_keys);
100 check_required(
"point_subsample", point_subsample_, missing_keys);
101 check_required(
"max_update_rate", max_update_rate_, missing_keys);
102 check_required(
"filtered_cloud_topic", filtered_cloud_topic_, missing_keys);
104 if (missing_keys.empty())
108 std::ostringstream oss;
109 for (
const auto& name : missing_keys)
112 <<
"'" << name <<
"'";
114 RCLCPP_ERROR(node_->get_logger(),
"Missing parameters under '%s': %s", name_space.c_str(), oss.str().c_str());
121 tf_buffer_ = std::make_shared<tf2_ros::Buffer>(node_->get_clock());
122 auto create_timer_interface =
123 std::make_shared<tf2_ros::CreateTimerROS>(node->get_node_base_interface(), node->get_node_timers_interface());
124 tf_buffer_->setCreateTimerInterface(create_timer_interface);
125 tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
126 shape_mask_ = std::make_unique<point_containment_filter::ShapeMask>();
127 shape_mask_->setTransformCallback(
128 [
this](
ShapeHandle shape, Eigen::Isometry3d& tf) {
return getShapeTransform(shape, tf); });
135 std::string prefix =
"";
139 if (!filtered_cloud_topic_.empty())
141 filtered_cloud_publisher_ =
142 node_->create_publisher<sensor_msgs::msg::PointCloud2>(prefix + filtered_cloud_topic_, rclcpp::SensorDataQoS());
145 if (point_cloud_subscriber_)
148 rclcpp::SubscriptionOptions options;
149 options.callback_group = node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
152#if RCLCPP_VERSION_GTE(28, 3, 0)
153 rclcpp::SensorDataQoS();
155 rmw_qos_profile_sensor_data;
157 point_cloud_subscriber_ =
158 new message_filters::Subscriber<sensor_msgs::msg::PointCloud2>(node_, point_cloud_topic_, qos_profile, options);
162#if RCLCPP_VERSION_GTE(30, 0, 0)
163 using MessageFilterPointCloud2 = tf2_ros::MessageFilter<sensor_msgs::msg::PointCloud2>;
165 MessageFilterPointCloud2::RequiredInterfaces required_interfaces{ node_->get_node_logging_interface(),
166 node_->get_node_clock_interface() };
168 point_cloud_filter_ =
new tf2_ros::MessageFilter<sensor_msgs::msg::PointCloud2>(
169 *point_cloud_subscriber_, *tf_buffer_,
monitor_->
getMapFrame(), 5, std::move(required_interfaces));
171 point_cloud_filter_ =
new tf2_ros::MessageFilter<sensor_msgs::msg::PointCloud2>(
174 point_cloud_filter_->registerCallback(
175 [
this](
const sensor_msgs::msg::PointCloud2::ConstSharedPtr& cloud) { cloudMsgCallback(cloud); });
176 RCLCPP_INFO(logger_,
"Listening to '%s' using message filter with target frame '%s'", point_cloud_topic_.c_str(),
177 point_cloud_filter_->getTargetFramesString().c_str());
181 point_cloud_subscriber_->registerCallback(
182 [
this](
const sensor_msgs::msg::PointCloud2::ConstSharedPtr& cloud) { cloudMsgCallback(cloud); });
183 RCLCPP_INFO(logger_,
"Listening to '%s'", point_cloud_topic_.c_str());
189 delete point_cloud_filter_;
190 delete point_cloud_subscriber_;
191 point_cloud_filter_ =
nullptr;
192 point_cloud_subscriber_ =
nullptr;
200 h = shape_mask_->addShape(shape, scale_, padding_);
204 RCLCPP_ERROR(logger_,
"Shape filter not yet initialized!");
212 shape_mask_->removeShape(handle);
215bool PointCloudOctomapUpdater::getShapeTransform(
ShapeHandle h, Eigen::Isometry3d& transform)
const
220 transform = it->second;
226 const Eigen::Vector3d& , std::vector<int>& )
230void PointCloudOctomapUpdater::cloudMsgCallback(
const sensor_msgs::msg::PointCloud2::ConstSharedPtr& cloud_msg)
232 RCLCPP_DEBUG(logger_,
"Received a new point cloud message");
233 rclcpp::Time
start = rclcpp::Clock(RCL_ROS_TIME).now();
235 if (max_update_rate_ > 0)
238 if ((node_->now() - last_update_time_) <= rclcpp::Duration::from_seconds(1.0 / max_update_rate_))
240 last_update_time_ = node_->now();
247 tf2::Stamped<tf2::Transform> map_h_sensor;
250 map_h_sensor.setIdentity();
258 tf2::fromMsg(tf_buffer_->lookupTransform(
monitor_->
getMapFrame(), cloud_msg->header.frame_id,
259 cloud_msg->header.stamp),
262 catch (tf2::TransformException& ex)
264 RCLCPP_ERROR_STREAM(logger_,
"Transform error of sensor data: " << ex.what() <<
"; quitting callback");
273 const tf2::Vector3& sensor_origin_tf = map_h_sensor.getOrigin();
274 octomap::point3d sensor_origin(sensor_origin_tf.getX(), sensor_origin_tf.getY(), sensor_origin_tf.getZ());
275 Eigen::Vector3d sensor_origin_eigen(sensor_origin_tf.getX(), sensor_origin_tf.getY(), sensor_origin_tf.getZ());
281 shape_mask_->maskContainment(*cloud_msg, sensor_origin_eigen, 0.0, max_range_, mask_);
282 updateMask(*cloud_msg, sensor_origin_eigen, mask_);
284 octomap::KeySet free_cells, occupied_cells, model_cells, clip_cells;
285 std::unique_ptr<sensor_msgs::msg::PointCloud2> filtered_cloud;
290 std::unique_ptr<sensor_msgs::PointCloud2Iterator<float>> iter_filtered_x;
291 std::unique_ptr<sensor_msgs::PointCloud2Iterator<float>> iter_filtered_y;
292 std::unique_ptr<sensor_msgs::PointCloud2Iterator<float>> iter_filtered_z;
294 if (!filtered_cloud_topic_.empty())
296 filtered_cloud = std::make_unique<sensor_msgs::msg::PointCloud2>();
297 filtered_cloud->header = cloud_msg->header;
298 sensor_msgs::PointCloud2Modifier pcd_modifier(*filtered_cloud);
299 pcd_modifier.setPointCloud2FieldsByString(1,
"xyz");
300 pcd_modifier.resize(cloud_msg->width * cloud_msg->height);
303 iter_filtered_x = std::make_unique<sensor_msgs::PointCloud2Iterator<float>>(*filtered_cloud,
"x");
304 iter_filtered_y = std::make_unique<sensor_msgs::PointCloud2Iterator<float>>(*filtered_cloud,
"y");
305 iter_filtered_z = std::make_unique<sensor_msgs::PointCloud2Iterator<float>>(*filtered_cloud,
"z");
307 size_t filtered_cloud_size = 0;
315 for (
unsigned int row = 0; row < cloud_msg->height; row += point_subsample_)
317 unsigned int row_c = row * cloud_msg->width;
318 sensor_msgs::PointCloud2ConstIterator<float> pt_iter(*cloud_msg,
"x");
322 for (
unsigned int col = 0; col < cloud_msg->width; col += point_subsample_, pt_iter += point_subsample_)
328 if (!std::isnan(pt_iter[0]) && !std::isnan(pt_iter[1]) && !std::isnan(pt_iter[2]))
335 tf2::Vector3 point_tf = map_h_sensor * tf2::Vector3(pt_iter[0], pt_iter[1], pt_iter[2]);
336 model_cells.insert(
tree_->coordToKey(point_tf.getX(), point_tf.getY(), point_tf.getZ()));
340 tf2::Vector3 clipped_point_tf =
341 map_h_sensor * (tf2::Vector3(pt_iter[0], pt_iter[1], pt_iter[2]).normalize() * max_range_);
343 tree_->coordToKey(clipped_point_tf.getX(), clipped_point_tf.getY(), clipped_point_tf.getZ()));
347 tf2::Vector3 point_tf = map_h_sensor * tf2::Vector3(pt_iter[0], pt_iter[1], pt_iter[2]);
348 occupied_cells.insert(
tree_->coordToKey(point_tf.getX(), point_tf.getY(), point_tf.getZ()));
352 **iter_filtered_x = pt_iter[0];
353 **iter_filtered_y = pt_iter[1];
354 **iter_filtered_z = pt_iter[2];
355 ++filtered_cloud_size;
366 for (
const octomap::OcTreeKey& occupied_cell : occupied_cells)
368 if (
tree_->computeRayKeys(sensor_origin,
tree_->keyToCoord(occupied_cell), key_ray_))
369 free_cells.insert(key_ray_.begin(), key_ray_.end());
373 for (
const octomap::OcTreeKey& model_cell : model_cells)
375 if (
tree_->computeRayKeys(sensor_origin,
tree_->keyToCoord(model_cell), key_ray_))
376 free_cells.insert(key_ray_.begin(), key_ray_.end());
380 for (
const octomap::OcTreeKey& clip_cell : clip_cells)
382 free_cells.insert(clip_cell);
383 if (
tree_->computeRayKeys(sensor_origin,
tree_->keyToCoord(clip_cell), key_ray_))
384 free_cells.insert(key_ray_.begin(), key_ray_.end());
396 for (
const octomap::OcTreeKey& model_cell : model_cells)
397 occupied_cells.erase(model_cell);
400 for (
const octomap::OcTreeKey& occupied_cell : occupied_cells)
401 free_cells.erase(occupied_cell);
408 for (
const octomap::OcTreeKey& free_cell : free_cells)
409 tree_->updateNode(free_cell, false);
412 for (
const octomap::OcTreeKey& occupied_cell : occupied_cells)
413 tree_->updateNode(occupied_cell, true);
416 const float lg =
tree_->getClampingThresMinLog() -
tree_->getClampingThresMaxLog();
417 for (
const octomap::OcTreeKey& model_cell : model_cells)
418 tree_->updateNode(model_cell, lg);
422 RCLCPP_ERROR(logger_,
"Internal error while updating octree");
424 tree_->unlockWrite();
425 RCLCPP_DEBUG(logger_,
"Processed point cloud in %lf ms", (node_->now() -
start).seconds() * 1000.0);
426 tree_->triggerUpdateCallback();
430 sensor_msgs::PointCloud2Modifier pcd_modifier(*filtered_cloud);
431 pcd_modifier.resize(filtered_cloud_size);
432 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
Main namespace for MoveIt.