FiltersDemo.cpp
Go to the documentation of this file.
1 /*
2  * FiltersDemo.cpp
3  *
4  * Created on: Aug 16, 2017
5  * Author: Peter Fankhauser
6  * Institute: ETH Zurich, ANYbotics
7  *
8  */
9 
11 
12 using namespace grid_map;
13 
14 namespace grid_map_demos {
15 
16 FiltersDemo::FiltersDemo(ros::NodeHandle& nodeHandle, bool& success)
17  : nodeHandle_(nodeHandle),
18  filterChain_("grid_map::GridMap")
19 {
20  if (!readParameters()) {
21  success = false;
22  return;
23  }
24 
26  publisher_ = nodeHandle_.advertise<grid_map_msgs::GridMap>(outputTopic_, 1, true);
27 
28  // Setup filter chain.
30  ROS_ERROR("Could not configure the filter chain!");
31  success = false;
32  return;
33  }
34 
35  success = true;
36 }
37 
39 {
40 }
41 
43 {
44  if (!nodeHandle_.getParam("input_topic", inputTopic_)) {
45  ROS_ERROR("Could not read parameter `input_topic`.");
46  return false;
47  }
48  nodeHandle_.param("output_topic", outputTopic_, std::string("output"));
49  nodeHandle_.param("filter_chain_parameter_name", filterChainParametersName_, std::string("grid_map_filters"));
50  return true;
51 }
52 
53 void FiltersDemo::callback(const grid_map_msgs::GridMap& message)
54 {
55  // Convert message to map.
56  GridMap inputMap;
57  GridMapRosConverter::fromMessage(message, inputMap);
58 
59  // Apply filter chain.
60  grid_map::GridMap outputMap;
61  if (!filterChain_.update(inputMap, outputMap)) {
62  ROS_ERROR("Could not update the grid map filter chain!");
63  return;
64  }
65 
66  // Publish filtered output grid map.
67  grid_map_msgs::GridMap outputMessage;
68  GridMapRosConverter::toMessage(outputMap, outputMessage);
69  publisher_.publish(outputMessage);
70 }
71 
72 } /* namespace */
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::string inputTopic_
Name of the input grid map topic.
Definition: FiltersDemo.hpp:58
ros::Subscriber subscriber_
Grid map subscriber.
Definition: FiltersDemo.hpp:64
ros::Publisher publisher_
Grid map publisher.
Definition: FiltersDemo.hpp:67
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ros::NodeHandle & nodeHandle_
ROS nodehandle.
Definition: FiltersDemo.hpp:55
void callback(const grid_map_msgs::GridMap &message)
Definition: FiltersDemo.cpp:53
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
filters::FilterChain< grid_map::GridMap > filterChain_
Filter chain.
Definition: FiltersDemo.hpp:70
bool getParam(const std::string &key, std::string &s) const
bool update(const T &data_in, T &data_out)
bool configure(std::string param_name, ros::NodeHandle node=ros::NodeHandle())
std::string filterChainParametersName_
Filter chain parameters name.
Definition: FiltersDemo.hpp:73
std::string outputTopic_
Name of the output grid map topic.
Definition: FiltersDemo.hpp:61
#define ROS_ERROR(...)


grid_map_demos
Author(s): Péter Fankhauser
autogenerated on Tue Jun 25 2019 20:02:37