11 #include <sensor_msgs/PointCloud2.h> 19 : elevationLayer_(
std::move(elevationLayer)) {
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; });
41 const float heightMargin{0.1};
42 const float minValue{elevationData.minCoeffOfFinites() - heightMargin};
43 const float maxValue{elevationData.maxCoeffOfFinites() + heightMargin};
47 sensor_msgs::PointCloud2 pointCloud2Msg;
std::string elevationLayer_
Elevation layer in the received grid map.
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)
const Matrix & get(const std::string &layer) const
SdfDemo(ros::NodeHandle &nodeHandle, const std::string &mapTopic, std::string elevationLayer, const std::string &pointcloudTopic)
static void toPointCloud(const grid_map::GridMap &gridMap, const std::string &pointLayer, sensor_msgs::PointCloud2 &pointCloud)
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.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher occupiedPublisher_
Occupied space publisher.
ros::Subscriber gridmapSubscriber_
Grid map subscriber.
ros::Publisher pointcloudPublisher_
Pointcloud publisher.