#include <SdfDemo.hpp>
Public Member Functions | |
SdfDemo (ros::NodeHandle &nodeHandle, const std::string &mapTopic, std::string elevationLayer, const std::string &pointcloudTopic) | |
Private Member Functions | |
void | callback (const grid_map_msgs::GridMap &message) |
Private Attributes | |
std::string | elevationLayer_ |
Elevation layer in the received grid map. More... | |
ros::Publisher | freespacePublisher_ |
Free space publisher. More... | |
ros::Subscriber | gridmapSubscriber_ |
Grid map subscriber. More... | |
ros::Publisher | occupiedPublisher_ |
Occupied space publisher. More... | |
ros::Publisher | pointcloudPublisher_ |
Pointcloud publisher. More... | |
Subscribes to a gridmap, converts it to a signed distance field, and publishes the signed distance field as a pointcloud.
Definition at line 25 of file SdfDemo.hpp.
grid_map_demos::SdfDemo::SdfDemo | ( | ros::NodeHandle & | nodeHandle, |
const std::string & | mapTopic, | ||
std::string | elevationLayer, | ||
const std::string & | pointcloudTopic | ||
) |
Constructor.
nodeHandle | : the ROS node handle. |
mapTopic | : grid map topic to subscribe to |
elevationLayer | : name of the elevation layer |
pointcloudTopic | : point cloud topic to publish the result to |
Definition at line 18 of file SdfDemo.cpp.
|
private |
Definition at line 26 of file SdfDemo.cpp.
|
private |
Elevation layer in the received grid map.
Definition at line 53 of file SdfDemo.hpp.
|
private |
Free space publisher.
Definition at line 47 of file SdfDemo.hpp.
|
private |
Grid map subscriber.
Definition at line 41 of file SdfDemo.hpp.
|
private |
Occupied space publisher.
Definition at line 50 of file SdfDemo.hpp.
|
private |
Pointcloud publisher.
Definition at line 44 of file SdfDemo.hpp.