17 : nodeHandle_(nodeHandle),
18 filterChain_(
"grid_map::GridMap")
30 ROS_ERROR(
"Could not configure the filter chain!");
45 ROS_ERROR(
"Could not read parameter `input_topic`.");
57 GridMapRosConverter::fromMessage(message, inputMap);
62 ROS_ERROR(
"Could not update the grid map filter chain!");
67 grid_map_msgs::GridMap outputMessage;
68 GridMapRosConverter::toMessage(outputMap, outputMessage);
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.
ros::Subscriber subscriber_
Grid map subscriber.
ros::Publisher publisher_
Grid map publisher.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
ros::NodeHandle & nodeHandle_
ROS nodehandle.
void callback(const grid_map_msgs::GridMap &message)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
filters::FilterChain< grid_map::GridMap > filterChain_
Filter chain.
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.
std::string outputTopic_
Name of the output grid map topic.