Skip to content

Commit

Permalink
Fix rolling build issue: message filter to hpp from h (ros-navigation…
Browse files Browse the repository at this point in the history
…#4642)

* Fix rolling build issue: message filter to hpp from h

Signed-off-by: Steve Macenski <[email protected]>

* Update amcl_node.hpp

Signed-off-by: Steve Macenski <[email protected]>

* Update static_layer.hpp

Signed-off-by: Steve Macenski <[email protected]>

* Update obstacle_layer.hpp

Signed-off-by: Steve Macenski <[email protected]>

* Update range_sensor_layer.hpp

Signed-off-by: Steve Macenski <[email protected]>

* Update voxel_layer.hpp

Signed-off-by: Steve Macenski <[email protected]>

---------

Signed-off-by: Steve Macenski <[email protected]>
Signed-off-by: Joseph Duchesne <[email protected]>
  • Loading branch information
SteveMacenski authored and josephduchesne committed Dec 10, 2024
1 parent 4163ec6 commit ab55fdc
Show file tree
Hide file tree
Showing 6 changed files with 6 additions and 6 deletions.
2 changes: 1 addition & 1 deletion nav2_amcl/include/nav2_amcl/amcl_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@
#include <vector>

#include "geometry_msgs/msg/pose_stamped.hpp"
#include "message_filters/subscriber.h"
#include "message_filters/subscriber.hpp"
#include "nav2_util/lifecycle_node.hpp"
#include "nav2_amcl/motion_model/motion_model.hpp"
#include "nav2_amcl/sensors/laser/laser.hpp"
Expand Down
2 changes: 1 addition & 1 deletion nav2_amcl/src/amcl_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@
#include <utility>
#include <vector>

#include "message_filters/subscriber.h"
#include "message_filters/subscriber.hpp"
#include "nav2_amcl/angleutils.hpp"
#include "nav2_util/geometry_utils.hpp"
#include "nav2_amcl/pf/pf.hpp"
Expand Down
2 changes: 1 addition & 1 deletion nav2_costmap_2d/include/nav2_costmap_2d/obstacle_layer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@
#pragma GCC diagnostic ignored "-Wreorder"
#include "tf2_ros/message_filter.h"
#pragma GCC diagnostic pop
#include "message_filters/subscriber.h"
#include "message_filters/subscriber.hpp"
#include "nav_msgs/msg/occupancy_grid.hpp"
#include "sensor_msgs/msg/laser_scan.hpp"
#include "sensor_msgs/msg/point_cloud.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@
#include <mutex>

#include "map_msgs/msg/occupancy_grid_update.hpp"
#include "message_filters/subscriber.h"
#include "message_filters/subscriber.hpp"
#include "nav2_costmap_2d/costmap_layer.hpp"
#include "nav2_costmap_2d/layered_costmap.hpp"
#include "nav_msgs/msg/occupancy_grid.hpp"
Expand Down
2 changes: 1 addition & 1 deletion nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@
#include <vector>

#include "map_msgs/msg/occupancy_grid_update.hpp"
#include "message_filters/subscriber.h"
#include "message_filters/subscriber.hpp"
#include "nav2_costmap_2d/costmap_layer.hpp"
#include "nav2_costmap_2d/layered_costmap.hpp"
#include "nav_msgs/msg/occupancy_grid.hpp"
Expand Down
2 changes: 1 addition & 1 deletion nav2_costmap_2d/include/nav2_costmap_2d/voxel_layer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@
#define NAV2_COSTMAP_2D__VOXEL_LAYER_HPP_

#include <vector>
#include "message_filters/subscriber.h"
#include "message_filters/subscriber.hpp"

#include <rclcpp/rclcpp.hpp>
#include <nav2_costmap_2d/layer.hpp>
Expand Down

0 comments on commit ab55fdc

Please sign in to comment.