#include <FiltersDemo.hpp>
Public Member Functions | |
void | callback (const grid_map_msgs::GridMap &message) |
FiltersDemo (ros::NodeHandle &nodeHandle, bool &success) | |
bool | readParameters () |
virtual | ~FiltersDemo () |
Private Attributes | |
filters::FilterChain < grid_map::GridMap > | filterChain_ |
Filter chain. | |
std::string | filterChainParametersName_ |
Filter chain parameters name. | |
std::string | inputTopic_ |
Name of the input grid map topic. | |
ros::NodeHandle & | nodeHandle_ |
ROS nodehandle. | |
std::string | outputTopic_ |
Name of the output grid map topic. | |
ros::Publisher | publisher_ |
Grid map publisher. | |
ros::Subscriber | subscriber_ |
Grid map subscriber. |
Applies a chain of grid map filters to a topic and republishes the resulting grid map.
Definition at line 24 of file FiltersDemo.hpp.
grid_map_demos::FiltersDemo::FiltersDemo | ( | ros::NodeHandle & | nodeHandle, |
bool & | success | ||
) |
Constructor.
nodeHandle | the ROS node handle. |
success | signalizes if filter is configured ok or not. |
Definition at line 16 of file FiltersDemo.cpp.
grid_map_demos::FiltersDemo::~FiltersDemo | ( | ) | [virtual] |
Destructor.
Definition at line 38 of file FiltersDemo.cpp.
void grid_map_demos::FiltersDemo::callback | ( | const grid_map_msgs::GridMap & | message | ) |
Callback method for the incoming grid map message.
message | the incoming message. |
Definition at line 53 of file FiltersDemo.cpp.
Reads and verifies the ROS parameters.
Definition at line 42 of file FiltersDemo.cpp.
filters::FilterChain<grid_map::GridMap> grid_map_demos::FiltersDemo::filterChain_ [private] |
Filter chain.
Definition at line 70 of file FiltersDemo.hpp.
std::string grid_map_demos::FiltersDemo::filterChainParametersName_ [private] |
Filter chain parameters name.
Definition at line 73 of file FiltersDemo.hpp.
std::string grid_map_demos::FiltersDemo::inputTopic_ [private] |
Name of the input grid map topic.
Definition at line 58 of file FiltersDemo.hpp.
ros::NodeHandle& grid_map_demos::FiltersDemo::nodeHandle_ [private] |
ROS nodehandle.
Definition at line 55 of file FiltersDemo.hpp.
std::string grid_map_demos::FiltersDemo::outputTopic_ [private] |
Name of the output grid map topic.
Definition at line 61 of file FiltersDemo.hpp.
ros::Publisher grid_map_demos::FiltersDemo::publisher_ [private] |
Grid map publisher.
Definition at line 67 of file FiltersDemo.hpp.
ros::Subscriber grid_map_demos::FiltersDemo::subscriber_ [private] |
Grid map subscriber.
Definition at line 64 of file FiltersDemo.hpp.