Skip to content

Commit

Permalink
Updated deprecated message filter headers (#1239)
Browse files Browse the repository at this point in the history
Signed-off-by: Alejandro Hernández Cordero <[email protected]>
  • Loading branch information
ahcorde authored Jul 18, 2024
1 parent d390a55 commit 367cf4a
Show file tree
Hide file tree
Showing 3 changed files with 7 additions and 6 deletions.
4 changes: 2 additions & 2 deletions rviz_common/include/rviz_common/message_filter_display.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,11 +30,11 @@
#ifndef RVIZ_COMMON__MESSAGE_FILTER_DISPLAY_HPP_
#define RVIZ_COMMON__MESSAGE_FILTER_DISPLAY_HPP_

#include <message_filters/subscriber.h>
#include <tf2_ros/message_filter.h>

#include <memory>

#include <message_filters/subscriber.hpp>

#include "rviz_common/ros_topic_display.hpp"
#include "rviz_common/properties/int_property.hpp"

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@
# include <OgreRenderTargetListener.h>
# include <OgreSharedPtr.h>

#include <message_filters/cache.h>
#include <message_filters/cache.hpp>

# include "sensor_msgs/msg/camera_info.hpp"
# include "tf2_ros/message_filter.h"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,16 +35,17 @@
#include <QObject> // NOLINT: cpplint cannot handle the include order here
#include <Ogre.h>

#include <message_filters/subscriber.h>
#include <message_filters/synchronizer.h>
#include <message_filters/sync_policies/approximate_time.h>
#include <tf2_ros/message_filter.h>

#include <memory>
#include <mutex>
#include <set>
#include <string>

#include <message_filters/subscriber.hpp>
#include <message_filters/synchronizer.hpp>
#include <message_filters/sync_policies/approximate_time.hpp>

#include <image_transport/image_transport.hpp>
#include <image_transport/subscriber_filter.hpp>

Expand Down

0 comments on commit 367cf4a

Please sign in to comment.