Skip to content

Commit 83c4349

Browse files
committed
Address Warnings
Signed-off-by: Michael Carlstrom <rmc@carlstrom.com>
1 parent eac7b21 commit 83c4349

File tree

2 files changed

+23
-8
lines changed

2 files changed

+23
-8
lines changed

mavros/src/plugins/setpoint_attitude.cpp

Lines changed: 18 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -16,10 +16,15 @@
1616
* @{
1717
*/
1818

19-
#include <message_filters/subscriber.h>
20-
#include <message_filters/synchronizer.h>
21-
#include <message_filters/sync_policies/approximate_time.h>
22-
19+
#if __has_include(<message_filters/subscriber.hpp>)
20+
#include <message_filters/subscriber.hpp>
21+
#include <message_filters/synchronizer.hpp>
22+
#include <message_filters/sync_policies/approximate_time.hpp>
23+
#else
24+
#include <message_filters/subscriber.h>
25+
#include <message_filters/synchronizer.h>
26+
#include <message_filters/sync_policies/approximate_time.h>
27+
#endif
2328
#include <memory>
2429

2530
#include "tf2_eigen/tf2_eigen.hpp"
@@ -64,6 +69,12 @@ class SetpointAttitudePlugin : public plugin::Plugin,
6469

6570
auto qos = rclcpp::QoS(10);
6671

72+
#ifdef USE_OLD_RMW_QOS
73+
auto subscriber_qos = qos.get_rmw_qos_profile();
74+
#else
75+
auto subscriber_qos = qos;
76+
#endif
77+
6778
node_declare_and_watch_parameter(
6879
"reverse_thrust", false, [&](const rclcpp::Parameter & p) {
6980
reverse_thrust = p.as_bool();
@@ -82,13 +93,13 @@ class SetpointAttitudePlugin : public plugin::Plugin,
8293
/**
8394
* @brief Use message_filters to sync attitude and thrust msg coming from different topics
8495
*/
85-
pose_sub.subscribe(node, "~/attitude", qos.get_rmw_qos_profile());
96+
pose_sub.subscribe(node, "~/attitude", subscriber_qos);
8697

8798
sync_pose = std::make_unique<SyncPoseThrust>(SyncPoseThrustPolicy(10), pose_sub, th_sub);
8899
sync_pose->registerCallback(&SetpointAttitudePlugin::attitude_pose_cb, this);
89100

90101
} else {
91-
twist_sub.subscribe(node, "~/cmd_vel", qos.get_rmw_qos_profile());
102+
twist_sub.subscribe(node, "~/cmd_vel", subscriber_qos);
92103

93104
sync_twist =
94105
std::make_unique<SyncTwistThrust>(SyncTwistThrustPolicy(10), twist_sub, th_sub);
@@ -97,7 +108,7 @@ class SetpointAttitudePlugin : public plugin::Plugin,
97108
});
98109

99110
// thrust msg subscriber to sync
100-
th_sub.subscribe(node, "~/thrust", qos.get_rmw_qos_profile());
111+
th_sub.subscribe(node, "~/thrust", subscriber_qos);
101112
}
102113

103114
Subscriptions get_subscriptions() override

mavros_extras/include/mavros_extras/servo_state_publisher.hpp

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,11 @@
1717
#define MAVROS_EXTRAS__SERVO_STATE_PUBLISHER_HPP_
1818

1919
#include <yaml-cpp/yaml.h>
20-
#include <urdf/model.h>
20+
#if __has_include(<urdf/model.hpp>)
21+
#include <urdf/model.hpp>
22+
#else
23+
#include <urdf/model.h>
24+
#endif
2125

2226
#include <algorithm>
2327
#include <memory>

0 commit comments

Comments
 (0)