17#ifndef EASYNAV_PLANNER__FILTERS__OCTOMAPFILTER_HPP_
18#define EASYNAV_PLANNER__FILTERS__OCTOMAPFILTER_HPP_
22#include "octomap/octomap.h"
23#include "easynav_common/types/NavState.hpp"
24#include "rclcpp_lifecycle/lifecycle_node.hpp"
38 const std::shared_ptr<rclcpp_lifecycle::LifecycleNode> parent_node,
39 const std::string & plugin_name);
42 virtual void update(::easynav::NavState & nav_state) = 0;
48 std::shared_ptr<rclcpp_lifecycle::LifecycleNode>
get_node()
const;
53 std::shared_ptr<rclcpp_lifecycle::LifecycleNode>
parent_node_ {
nullptr};
std::string plugin_name_
Definition OctomapFilter.hpp:54
void initialize(const std::shared_ptr< rclcpp_lifecycle::LifecycleNode > parent_node, const std::string &plugin_name)
Definition OctomapFilter.cpp:34
std::shared_ptr< rclcpp_lifecycle::LifecycleNode > parent_node_
Definition OctomapFilter.hpp:53
float map_resolution_
Definition OctomapFilter.hpp:56
virtual void on_initialize()=0
float get_map_resolution()
Definition OctomapFilter.hpp:44
void set_map_resolution(float resolution)
Definition OctomapFilter.hpp:45
virtual void update(::easynav::NavState &nav_state)=0
const std::string & get_plugin_name() const
Definition OctomapFilter.cpp:50
std::shared_ptr< rclcpp_lifecycle::LifecycleNode > get_node() const
Definition OctomapFilter.cpp:44
OctomapFilter()
Definition OctomapFilter.cpp:28
Definition InflationFilter.hpp:32
Provides a mapping for often used cost values.
Definition cost_values.hpp:41