Skip to content

Commit ff8b485

Browse files
author
ugol-1
committed
Break circular dependencies by using raw pointers to UAS in plugins
1 parent 1bfdd5a commit ff8b485

File tree

5 files changed

+8
-8
lines changed

5 files changed

+8
-8
lines changed

mavros/include/mavros/plugin.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -44,7 +44,7 @@ namespace plugin
4444
{
4545

4646
using mavros::uas::UAS;
47-
using UASPtr = std::shared_ptr<UAS>;
47+
using UASPtr = UAS *;
4848
using r_unique_lock = std::unique_lock<std::recursive_mutex>;
4949
using s_unique_lock = std::unique_lock<std::shared_timed_mutex>;
5050
using s_shared_lock = std::shared_lock<std::shared_timed_mutex>;

mavros/include/mavros/plugin_filter.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@ namespace filter
3232
{
3333
using mavros::plugin::Filter;
3434
using mavros::uas::UAS;
35-
using UASPtr = UAS::SharedPtr;
35+
using UASPtr = UAS *;
3636
using mavconn::Framing;
3737

3838

mavros/src/lib/mavros_uas.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -84,7 +84,7 @@ UAS::UAS(
8484
this->declare_parameter("odom_frame_id", odom_frame_id);
8585
this->declare_parameter("map_frame_id", map_frame_id);
8686

87-
// NOTE(vooon): we couldn't add_plugin() in constructor because it needs shared_from_this()
87+
// NOTE: we can add_plugin() in constructor because it does not need shared_from_this()
8888
startup_delay_timer = this->create_wall_timer(
8989
10ms, [this]() {
9090
startup_delay_timer->cancel();
@@ -264,7 +264,7 @@ plugin::Plugin::SharedPtr UAS::create_plugin_instance(const std::string & pl_nam
264264
auto plugin_factory = plugin_factory_loader.createSharedInstance(pl_name);
265265

266266
return
267-
plugin_factory->create_plugin_instance(std::static_pointer_cast<UAS>(shared_from_this()));
267+
plugin_factory->create_plugin_instance(this);
268268
}
269269

270270
void UAS::add_plugin(const std::string & pl_name)

mavros/src/plugins/home_position.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -130,7 +130,7 @@ class HomePositionPlugin : public plugin::Plugin
130130
hp.geo.latitude = home_position.latitude / 1E7; // deg
131131
hp.geo.longitude = home_position.longitude / 1E7; // deg
132132
hp.geo.altitude = home_position.altitude / 1E3 +
133-
uas->data.geoid_to_ellipsoid_height(hp.geo); // in meters
133+
uas->data.geoid_to_ellipsoid_height(hp.geo); // in meters
134134
hp.orientation = tf2::toMsg(q);
135135
hp.position = tf2::toMsg(pos);
136136
tf2::toMsg(hp_approach_enu, hp.approach);

mavros/test/test_uas.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -61,7 +61,7 @@ class MockPlugin : public plugin::Plugin
6161
public:
6262
using SharedPtr = std::shared_ptr<MockPlugin>;
6363

64-
explicit MockPlugin(UAS::SharedPtr uas_)
64+
explicit MockPlugin(UASPtr uas_)
6565
: Plugin(uas_, "mock_plugin") {}
6666

6767
MOCK_METHOD0(get_subscriptions, plugin::Plugin::Subscriptions(void));
@@ -208,9 +208,9 @@ TEST_F(TestUAS, is_plugin_allowed)
208208
TEST_F(TestUAS, add_plugin__route_message__filter)
209209
{
210210
auto uas = create_node();
211-
auto plugin1 = std::make_shared<MockPlugin>(uas);
211+
auto plugin1 = std::make_shared<MockPlugin>(uas.get());
212212
auto subs1 = plugin1->allsubs();
213-
auto plugin2 = std::make_shared<MockPlugin>(uas);
213+
auto plugin2 = std::make_shared<MockPlugin>(uas.get());
214214
auto subs2 = plugin2->rawsubs();
215215

216216
// XXX(vooon): silence leak warnings: they work badly with shared_ptr

0 commit comments

Comments
 (0)