File tree 5 files changed +8
-8
lines changed
5 files changed +8
-8
lines changed Original file line number Diff line number Diff line change @@ -44,7 +44,7 @@ namespace plugin
44
44
{
45
45
46
46
using mavros::uas::UAS;
47
- using UASPtr = std::shared_ptr< UAS> ;
47
+ using UASPtr = UAS * ;
48
48
using r_unique_lock = std::unique_lock<std::recursive_mutex>;
49
49
using s_unique_lock = std::unique_lock<std::shared_timed_mutex>;
50
50
using s_shared_lock = std::shared_lock<std::shared_timed_mutex>;
Original file line number Diff line number Diff line change @@ -32,7 +32,7 @@ namespace filter
32
32
{
33
33
using mavros::plugin::Filter;
34
34
using mavros::uas::UAS;
35
- using UASPtr = UAS::SharedPtr ;
35
+ using UASPtr = UAS * ;
36
36
using mavconn::Framing;
37
37
38
38
Original file line number Diff line number Diff line change @@ -84,7 +84,7 @@ UAS::UAS(
84
84
this ->declare_parameter (" odom_frame_id" , odom_frame_id);
85
85
this ->declare_parameter (" map_frame_id" , map_frame_id);
86
86
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()
88
88
startup_delay_timer = this ->create_wall_timer (
89
89
10ms, [this ]() {
90
90
startup_delay_timer->cancel ();
@@ -264,7 +264,7 @@ plugin::Plugin::SharedPtr UAS::create_plugin_instance(const std::string & pl_nam
264
264
auto plugin_factory = plugin_factory_loader.createSharedInstance (pl_name);
265
265
266
266
return
267
- plugin_factory->create_plugin_instance (std::static_pointer_cast<UAS>( shared_from_this ()) );
267
+ plugin_factory->create_plugin_instance (this );
268
268
}
269
269
270
270
void UAS::add_plugin (const std::string & pl_name)
Original file line number Diff line number Diff line change @@ -130,7 +130,7 @@ class HomePositionPlugin : public plugin::Plugin
130
130
hp.geo .latitude = home_position.latitude / 1E7 ; // deg
131
131
hp.geo .longitude = home_position.longitude / 1E7 ; // deg
132
132
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
134
134
hp.orientation = tf2::toMsg (q);
135
135
hp.position = tf2::toMsg (pos);
136
136
tf2::toMsg (hp_approach_enu, hp.approach );
Original file line number Diff line number Diff line change @@ -61,7 +61,7 @@ class MockPlugin : public plugin::Plugin
61
61
public:
62
62
using SharedPtr = std::shared_ptr<MockPlugin>;
63
63
64
- explicit MockPlugin (UAS::SharedPtr uas_)
64
+ explicit MockPlugin (UASPtr uas_)
65
65
: Plugin(uas_, " mock_plugin" ) {}
66
66
67
67
MOCK_METHOD0 (get_subscriptions, plugin::Plugin::Subscriptions(void ));
@@ -208,9 +208,9 @@ TEST_F(TestUAS, is_plugin_allowed)
208
208
TEST_F (TestUAS, add_plugin__route_message__filter)
209
209
{
210
210
auto uas = create_node ();
211
- auto plugin1 = std::make_shared<MockPlugin>(uas);
211
+ auto plugin1 = std::make_shared<MockPlugin>(uas. get () );
212
212
auto subs1 = plugin1->allsubs ();
213
- auto plugin2 = std::make_shared<MockPlugin>(uas);
213
+ auto plugin2 = std::make_shared<MockPlugin>(uas. get () );
214
214
auto subs2 = plugin2->rawsubs ();
215
215
216
216
// XXX(vooon): silence leak warnings: they work badly with shared_ptr
You can’t perform that action at this time.
0 commit comments