Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -36,14 +36,14 @@

#include <sensor_msgs/msg/magnetic_field.hpp>
#include <geometry_msgs/msg/vector3_stamped.hpp>
#include <message_filters/subscriber.h>
#include <message_filters/sync_policies/approximate_time.h>
#include <message_filters/synchronizer.h>
#include <message_filters/subscriber.hpp>
#include <message_filters/sync_policies/approximate_time.hpp>
#include <message_filters/synchronizer.hpp>
#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/imu.hpp>
#include <std_msgs/msg/bool.hpp>
#include <tf2/transform_datatypes.h>
#include <tf2/LinearMath/Quaternion.h>
#include <tf2/transform_datatypes.hpp>
#include <tf2/LinearMath/Quaternion.hpp>
#include <tf2_ros/transform_broadcaster.h>
#include <memory>

Expand Down
14 changes: 7 additions & 7 deletions imu_complementary_filter/src/complementary_filter_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,11 +33,11 @@

#include "imu_complementary_filter/complementary_filter_ros.h"

#include <geometry_msgs/msg/transform_stamped.h>
#include <tf2/convert.h>
#include <tf2/LinearMath/Matrix3x3.h>
#include <tf2/LinearMath/Transform.h>
#include <tf2/LinearMath/Vector3.h>
#include <geometry_msgs/msg/transform_stamped.hpp>
#include <tf2/convert.hpp>
#include <tf2/LinearMath/Matrix3x3.hpp>
#include <tf2/LinearMath/Transform.hpp>
#include <tf2/LinearMath/Vector3.hpp>

namespace imu_tools {

Expand Down Expand Up @@ -78,13 +78,13 @@ ComplementaryFilterROS::ComplementaryFilterROS()
}};

imu_subscriber_.reset(new ImuSubscriber(this, "imu/data_raw",
rmw_qos_profile_default, sub_opts));
rclcpp::QoS(queue_size), sub_opts));

// Register magnetic data subscriber.
if (use_mag_)
{
mag_subscriber_.reset(new MagSubscriber(
this, "imu/mag", rmw_qos_profile_default, sub_opts));
this, "imu/mag", rclcpp::QoS(queue_size), sub_opts));

sync_.reset(new Synchronizer(SyncPolicy(queue_size), *imu_subscriber_,
*mag_subscriber_));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,12 +28,12 @@

#include "tf2_ros/transform_broadcaster.h"
#include <geometry_msgs/msg/vector3_stamped.hpp>
#include <message_filters/subscriber.h>
#include <message_filters/sync_policies/approximate_time.h>
#include <message_filters/synchronizer.h>
#include <message_filters/subscriber.hpp>
#include <message_filters/sync_policies/approximate_time.hpp>
#include <message_filters/synchronizer.hpp>
#include <sensor_msgs/msg/imu.hpp>
#include <sensor_msgs/msg/magnetic_field.hpp>
#include <tf2/LinearMath/Quaternion.h>
#include <tf2/LinearMath/Quaternion.hpp>

#include "imu_filter_madgwick/imu_filter.h"
#include "imu_filter_madgwick/base_node.hpp"
Expand Down
6 changes: 3 additions & 3 deletions imu_filter_madgwick/src/imu_filter_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,8 @@
#include "imu_filter_madgwick/stateless_orientation.h"
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
#include <tf2/LinearMath/Matrix3x3.h>
#include <tf2/LinearMath/Quaternion.h>
#include <tf2/LinearMath/Matrix3x3.hpp>
#include <tf2/LinearMath/Quaternion.hpp>

using namespace std::chrono_literals;
using namespace rclcpp;
Expand Down Expand Up @@ -200,7 +200,7 @@ ImuFilterMadgwickRos::ImuFilterMadgwickRos(const rclcpp::NodeOptions &options)
// Synchronize inputs. Topic subscriptions happen on demand in the
// connection callback.
const int queue_size = 5;
rmw_qos_profile_t qos = rmw_qos_profile_sensor_data;
auto qos = rclcpp::QoS(rclcpp::SensorDataQoS());
imu_subscriber_.reset(new ImuSubscriber(this, "imu/data_raw", qos));

if (use_mag_)
Expand Down
4 changes: 2 additions & 2 deletions imu_filter_madgwick/src/stateless_orientation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,8 @@
*/

#include "imu_filter_madgwick/stateless_orientation.h"
#include <tf2/LinearMath/Matrix3x3.h>
#include <tf2/convert.h>
#include <tf2/LinearMath/Matrix3x3.hpp>
#include <tf2/convert.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>

template <typename T>
Expand Down
2 changes: 1 addition & 1 deletion imu_filter_madgwick/test/test_helpers.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
#define TEST_TEST_HELPERS_H_

#include <gtest/gtest.h>
#include <tf2/LinearMath/Quaternion.h>
#include <tf2/LinearMath/Quaternion.hpp>

#define MAX_DIFF 0.05

Expand Down
2 changes: 1 addition & 1 deletion rviz_imu_plugin/src/imu_display.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@
#ifndef RVIZ_IMU_PLUGIN_IMU_DISPLAY_H
#define RVIZ_IMU_PLUGIN_IMU_DISPLAY_H

#include <message_filters/subscriber.h>
#include <message_filters/subscriber.hpp>
#include <tf2_ros/message_filter.h>
#include <sensor_msgs/msg/imu.hpp>
#include <rviz_common/display.hpp>
Expand Down
2 changes: 1 addition & 1 deletion rviz_imu_plugin/src/mag_display.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@
#ifndef RVIZ_IMU_PLUGIN_MAG_DISPLAY_H
#define RVIZ_IMU_PLUGIN_MAG_DISPLAY_H

#include <message_filters/subscriber.h>
#include <message_filters/subscriber.hpp>
#include <tf2_ros/message_filter.h>
#include <sensor_msgs/msg/magnetic_field.hpp>
#include <rviz_common/display.hpp>
Expand Down