SdfDemo.cpp
Go to the documentation of this file.
1 /*
2 * SdfDemo.cpp
3 *
4 * Created on: May 3, 2022
5 * Author: Ruben Grandia
6 * Institute: ETH Zurich
7  */
8 
10 
11 #include <sensor_msgs/PointCloud2.h>
12 
15 
16 namespace grid_map_demos {
17 
18 SdfDemo::SdfDemo(ros::NodeHandle& nodeHandle, const std::string& mapTopic, std::string elevationLayer, const std::string& pointcloudTopic)
19  : elevationLayer_(std::move(elevationLayer)) {
20  pointcloudPublisher_ = nodeHandle.advertise<sensor_msgs::PointCloud2>(pointcloudTopic + "/full_sdf", 1);
21  freespacePublisher_ = nodeHandle.advertise<sensor_msgs::PointCloud2>(pointcloudTopic + "/free_space", 1);
22  occupiedPublisher_ = nodeHandle.advertise<sensor_msgs::PointCloud2>(pointcloudTopic + "/occupied_space", 1);
23  gridmapSubscriber_ = nodeHandle.subscribe(mapTopic, 1, &SdfDemo::callback, this);
24 }
25 
26 void SdfDemo::callback(const grid_map_msgs::GridMap& message) {
27  // Convert message to map.
29  std::vector<std::string> layers{elevationLayer_};
30  grid_map::GridMapRosConverter::fromMessage(message, map, layers, false, false);
31  auto& elevationData = map.get(elevationLayer_);
32 
33  // Inpaint if needed.
34  if (elevationData.hasNaN()) {
35  const float inpaint{elevationData.minCoeffOfFinites()};
36  ROS_WARN("[SdfDemo] Map contains NaN values. Will apply inpainting with min value.");
37  elevationData = elevationData.unaryExpr([=](float v) { return std::isfinite(v)? v : inpaint; });
38  }
39 
40  // Generate SDF.
41  const float heightMargin{0.1};
42  const float minValue{elevationData.minCoeffOfFinites() - heightMargin};
43  const float maxValue{elevationData.maxCoeffOfFinites() + heightMargin};
44  grid_map::SignedDistanceField sdf(map, elevationLayer_, minValue, maxValue);
45 
46  // Extract as point clouds.
47  sensor_msgs::PointCloud2 pointCloud2Msg;
49  pointcloudPublisher_.publish(pointCloud2Msg);
50 
51  grid_map::GridMapRosConverter::toPointCloud(sdf, pointCloud2Msg, 1, [](float sdfValue) { return sdfValue > 0.0; });
52  freespacePublisher_.publish(pointCloud2Msg);
53 
54  grid_map::GridMapRosConverter::toPointCloud(sdf, pointCloud2Msg, 1, [](float sdfValue) { return sdfValue <= 0.0; });
55  occupiedPublisher_.publish(pointCloud2Msg);
56 }
57 
58 } // namespace grid_map_demos
std::string elevationLayer_
Elevation layer in the received grid map.
Definition: SdfDemo.hpp:53
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void callback(const grid_map_msgs::GridMap &message)
Definition: SdfDemo.cpp:26
const Matrix & get(const std::string &layer) const
SdfDemo(ros::NodeHandle &nodeHandle, const std::string &mapTopic, std::string elevationLayer, const std::string &pointcloudTopic)
Definition: SdfDemo.cpp:18
static void toPointCloud(const grid_map::GridMap &gridMap, const std::string &pointLayer, sensor_msgs::PointCloud2 &pointCloud)
#define ROS_WARN(...)
static bool fromMessage(const grid_map_msgs::GridMap &message, grid_map::GridMap &gridMap, const std::vector< std::string > &layers, bool copyBasicLayers=true, bool copyAllNonBasicLayers=true)
void publish(const boost::shared_ptr< M > &message) const
ros::Publisher freespacePublisher_
Free space publisher.
Definition: SdfDemo.hpp:47
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher occupiedPublisher_
Occupied space publisher.
Definition: SdfDemo.hpp:50
ros::Subscriber gridmapSubscriber_
Grid map subscriber.
Definition: SdfDemo.hpp:41
ros::Publisher pointcloudPublisher_
Pointcloud publisher.
Definition: SdfDemo.hpp:44


grid_map_demos
Author(s): Péter Fankhauser
autogenerated on Wed Jul 5 2023 02:24:01