|
12 | 12 | // See the License for the specific language governing permissions and
|
13 | 13 | // limitations under the License.
|
14 | 14 |
|
15 |
| -#include "occupancy_grid_map_outlier_filter/occupancy_grid_map_outlier_filter_nodelet.hpp" |
| 15 | +#include "occupancy_grid_map_outlier_filter_node.hpp" |
| 16 | + |
| 17 | +#include "autoware/universe_utils/geometry/geometry.hpp" |
| 18 | +#include "autoware/universe_utils/ros/debug_publisher.hpp" |
| 19 | +#include "autoware/universe_utils/system/stop_watch.hpp" |
16 | 20 |
|
17 |
| -#include <autoware/universe_utils/geometry/geometry.hpp> |
18 |
| -#include <autoware/universe_utils/ros/debug_publisher.hpp> |
19 |
| -#include <autoware/universe_utils/system/stop_watch.hpp> |
20 | 21 | #include <pcl_ros/transforms.hpp>
|
21 | 22 |
|
22 | 23 | #include <boost/optional.hpp>
|
@@ -101,7 +102,7 @@ boost::optional<char> getCost(
|
101 | 102 |
|
102 | 103 | } // namespace
|
103 | 104 |
|
104 |
| -namespace occupancy_grid_map_outlier_filter |
| 105 | +namespace autoware::occupancy_grid_map_outlier_filter |
105 | 106 | {
|
106 | 107 | RadiusSearch2dFilter::RadiusSearch2dFilter(rclcpp::Node & node)
|
107 | 108 | {
|
@@ -489,8 +490,8 @@ void OccupancyGridMapOutlierFilterComponent::Debugger::transformToBaseLink(
|
489 | 490 | transformPointcloud(ros_input, *(node_.tf2_), node_.base_link_frame_, output);
|
490 | 491 | }
|
491 | 492 |
|
492 |
| -} // namespace occupancy_grid_map_outlier_filter |
| 493 | +} // namespace autoware::occupancy_grid_map_outlier_filter |
493 | 494 |
|
494 | 495 | #include <rclcpp_components/register_node_macro.hpp>
|
495 | 496 | RCLCPP_COMPONENTS_REGISTER_NODE(
|
496 |
| - occupancy_grid_map_outlier_filter::OccupancyGridMapOutlierFilterComponent) |
| 497 | + autoware::occupancy_grid_map_outlier_filter::OccupancyGridMapOutlierFilterComponent) |
0 commit comments