diff --git a/mavros/include/mavros/plugin.hpp b/mavros/include/mavros/plugin.hpp index 17725ae0f..37fda8025 100644 --- a/mavros/include/mavros/plugin.hpp +++ b/mavros/include/mavros/plugin.hpp @@ -44,7 +44,7 @@ namespace plugin { using mavros::uas::UAS; -using UASPtr = std::shared_ptr; +using UASPtr = UAS *; using r_unique_lock = std::unique_lock; using s_unique_lock = std::unique_lock; using s_shared_lock = std::shared_lock; diff --git a/mavros/include/mavros/plugin_filter.hpp b/mavros/include/mavros/plugin_filter.hpp index 3d3b28a17..b89e0192c 100644 --- a/mavros/include/mavros/plugin_filter.hpp +++ b/mavros/include/mavros/plugin_filter.hpp @@ -32,7 +32,7 @@ namespace filter { using mavros::plugin::Filter; using mavros::uas::UAS; -using UASPtr = UAS::SharedPtr; +using UASPtr = UAS *; using mavconn::Framing; diff --git a/mavros/src/lib/mavros_uas.cpp b/mavros/src/lib/mavros_uas.cpp index e185df6a4..424d92404 100644 --- a/mavros/src/lib/mavros_uas.cpp +++ b/mavros/src/lib/mavros_uas.cpp @@ -84,7 +84,7 @@ UAS::UAS( this->declare_parameter("odom_frame_id", odom_frame_id); this->declare_parameter("map_frame_id", map_frame_id); - // NOTE(vooon): we couldn't add_plugin() in constructor because it needs shared_from_this() + // NOTE: we can add_plugin() in constructor because it does not need shared_from_this() startup_delay_timer = this->create_wall_timer( 10ms, [this]() { startup_delay_timer->cancel(); @@ -264,7 +264,7 @@ plugin::Plugin::SharedPtr UAS::create_plugin_instance(const std::string & pl_nam auto plugin_factory = plugin_factory_loader.createSharedInstance(pl_name); return - plugin_factory->create_plugin_instance(std::static_pointer_cast(shared_from_this())); + plugin_factory->create_plugin_instance(this); } void UAS::add_plugin(const std::string & pl_name) diff --git a/mavros/src/plugins/global_position.cpp b/mavros/src/plugins/global_position.cpp index 77a741359..9c6ca85fe 100644 --- a/mavros/src/plugins/global_position.cpp +++ b/mavros/src/plugins/global_position.cpp @@ -548,7 +548,7 @@ class GlobalPositionPlugin : public plugin::Plugin gpo.latitude = req->position.latitude * 1E7; gpo.longitude = req->position.longitude * 1E7; gpo.altitude = (req->position.altitude + - uas->data.ellipsoid_to_geoid_height(req->position)) * 1E3; + uas->data.ellipsoid_to_geoid_height(req->position)) * 1E3; uas->send_message(gpo); } diff --git a/mavros/src/plugins/home_position.cpp b/mavros/src/plugins/home_position.cpp index 57325fe60..7b7f3c195 100644 --- a/mavros/src/plugins/home_position.cpp +++ b/mavros/src/plugins/home_position.cpp @@ -130,7 +130,7 @@ class HomePositionPlugin : public plugin::Plugin hp.geo.latitude = home_position.latitude / 1E7; // deg hp.geo.longitude = home_position.longitude / 1E7; // deg hp.geo.altitude = home_position.altitude / 1E3 + - uas->data.geoid_to_ellipsoid_height(hp.geo); // in meters + uas->data.geoid_to_ellipsoid_height(hp.geo); // in meters hp.orientation = tf2::toMsg(q); hp.position = tf2::toMsg(pos); tf2::toMsg(hp_approach_enu, hp.approach); diff --git a/mavros/test/test_uas.cpp b/mavros/test/test_uas.cpp index a6d1edd5a..e23f378cc 100644 --- a/mavros/test/test_uas.cpp +++ b/mavros/test/test_uas.cpp @@ -61,7 +61,7 @@ class MockPlugin : public plugin::Plugin public: using SharedPtr = std::shared_ptr; - explicit MockPlugin(UAS::SharedPtr uas_) + explicit MockPlugin(UASPtr uas_) : Plugin(uas_, "mock_plugin") {} MOCK_METHOD0(get_subscriptions, plugin::Plugin::Subscriptions(void)); @@ -208,9 +208,9 @@ TEST_F(TestUAS, is_plugin_allowed) TEST_F(TestUAS, add_plugin__route_message__filter) { auto uas = create_node(); - auto plugin1 = std::make_shared(uas); + auto plugin1 = std::make_shared(uas.get()); auto subs1 = plugin1->allsubs(); - auto plugin2 = std::make_shared(uas); + auto plugin2 = std::make_shared(uas.get()); auto subs2 = plugin2->rawsubs(); // XXX(vooon): silence leak warnings: they work badly with shared_ptr