Skip to content

Commit 0658b39

Browse files
committed
Only instantiate tf_listeners if needed
- We find that the transform listeners in sensor models are negatively impacting performance - Do not instantiate transform listeners if target frames are empty - Target frames are empty by default - Existing logic already does not do the transforms when target frames are empty
1 parent 9f2a5d6 commit 0658b39

File tree

8 files changed

+30
-8
lines changed

8 files changed

+30
-8
lines changed

fuse_models/include/fuse_models/acceleration_2d.h

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,8 @@
4444
#include <ros/ros.h>
4545
#include <tf2_ros/transform_listener.h>
4646

47+
#include <memory>
48+
4749

4850
namespace fuse_models
4951
{
@@ -113,7 +115,7 @@ class Acceleration2D : public fuse_core::AsyncSensorModel
113115

114116
tf2_ros::Buffer tf_buffer_;
115117

116-
tf2_ros::TransformListener tf_listener_;
118+
std::unique_ptr<tf2_ros::TransformListener> tf_listener_;
117119

118120
ros::Subscriber subscriber_;
119121

fuse_models/include/fuse_models/imu_2d.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -146,7 +146,7 @@ class Imu2D : public fuse_core::AsyncSensorModel
146146

147147
tf2_ros::Buffer tf_buffer_;
148148

149-
tf2_ros::TransformListener tf_listener_;
149+
std::unique_ptr<tf2_ros::TransformListener> tf_listener_;
150150

151151
ros::Subscriber subscriber_;
152152

fuse_models/include/fuse_models/odometry_2d.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -141,7 +141,7 @@ class Odometry2D : public fuse_core::AsyncSensorModel
141141

142142
tf2_ros::Buffer tf_buffer_;
143143

144-
tf2_ros::TransformListener tf_listener_;
144+
std::unique_ptr<tf2_ros::TransformListener> tf_listener_;
145145

146146
ros::Subscriber subscriber_;
147147

fuse_models/include/fuse_models/pose_2d.h

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,8 @@
4444
#include <ros/ros.h>
4545
#include <tf2_ros/transform_listener.h>
4646

47+
#include <memory>
48+
4749

4850
namespace fuse_models
4951
{
@@ -128,7 +130,7 @@ class Pose2D : public fuse_core::AsyncSensorModel
128130

129131
tf2_ros::Buffer tf_buffer_;
130132

131-
tf2_ros::TransformListener tf_listener_;
133+
std::unique_ptr<tf2_ros::TransformListener> tf_listener_;
132134

133135
ros::Subscriber subscriber_;
134136

fuse_models/src/acceleration_2d.cpp

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,6 @@ namespace fuse_models
5151
Acceleration2D::Acceleration2D() :
5252
fuse_core::AsyncSensorModel(1),
5353
device_id_(fuse_core::uuid::NIL),
54-
tf_listener_(tf_buffer_),
5554
throttled_callback_(std::bind(&Acceleration2D::process, this, std::placeholders::_1))
5655
{
5756
}
@@ -71,6 +70,11 @@ void Acceleration2D::onInit()
7170
ROS_WARN_STREAM("No dimensions were specified. Data from topic " << ros::names::resolve(params_.topic) <<
7271
" will be ignored.");
7372
}
73+
74+
if (!params_.target_frame.empty())
75+
{
76+
tf_listener_ = std::make_unique<tf2_ros::TransformListener>(tf_buffer_);
77+
}
7478
}
7579

7680
void Acceleration2D::onStart()

fuse_models/src/imu_2d.cpp

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -57,7 +57,6 @@ namespace fuse_models
5757
Imu2D::Imu2D() :
5858
fuse_core::AsyncSensorModel(1),
5959
device_id_(fuse_core::uuid::NIL),
60-
tf_listener_(tf_buffer_),
6160
throttled_callback_(std::bind(&Imu2D::process, this, std::placeholders::_1))
6261
{
6362
}
@@ -79,6 +78,13 @@ void Imu2D::onInit()
7978
ROS_WARN_STREAM("No dimensions were specified. Data from topic " << ros::names::resolve(params_.topic) <<
8079
" will be ignored.");
8180
}
81+
82+
if (!params_.acceleration_target_frame.empty() ||
83+
!params_.twist_target_frame.empty() ||
84+
!params_.orientation_target_frame.empty())
85+
{
86+
tf_listener_ = std::make_unique<tf2_ros::TransformListener>(tf_buffer_);
87+
}
8288
}
8389

8490
void Imu2D::onStart()

fuse_models/src/odometry_2d.cpp

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -56,7 +56,6 @@ namespace fuse_models
5656
Odometry2D::Odometry2D() :
5757
fuse_core::AsyncSensorModel(1),
5858
device_id_(fuse_core::uuid::NIL),
59-
tf_listener_(tf_buffer_),
6059
throttled_callback_(std::bind(&Odometry2D::process, this, std::placeholders::_1))
6160
{
6261
}
@@ -79,6 +78,11 @@ void Odometry2D::onInit()
7978
ROS_WARN_STREAM("No dimensions were specified. Data from topic " << ros::names::resolve(params_.topic) <<
8079
" will be ignored.");
8180
}
81+
82+
if (!params_.pose_target_frame.empty() || !params_.twist_target_frame.empty())
83+
{
84+
tf_listener_ = std::make_unique<tf2_ros::TransformListener>(tf_buffer_);
85+
}
8286
}
8387

8488
void Odometry2D::onStart()

fuse_models/src/pose_2d.cpp

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -54,7 +54,6 @@ namespace fuse_models
5454
Pose2D::Pose2D() :
5555
fuse_core::AsyncSensorModel(1),
5656
device_id_(fuse_core::uuid::NIL),
57-
tf_listener_(tf_buffer_),
5857
throttled_callback_(std::bind(&Pose2D::process, this, std::placeholders::_1))
5958
{
6059
}
@@ -75,6 +74,11 @@ void Pose2D::onInit()
7574
ROS_WARN_STREAM("No dimensions were specified. Data from topic " << ros::names::resolve(params_.topic) <<
7675
" will be ignored.");
7776
}
77+
78+
if (!params_.target_frame.empty())
79+
{
80+
tf_listener_ = std::make_unique<tf2_ros::TransformListener>(tf_buffer_);
81+
}
7882
}
7983

8084
void Pose2D::onStart()

0 commit comments

Comments
 (0)