File tree 8 files changed +30
-8
lines changed
8 files changed +30
-8
lines changed Original file line number Diff line number Diff line change 44
44
#include < ros/ros.h>
45
45
#include < tf2_ros/transform_listener.h>
46
46
47
+ #include < memory>
48
+
47
49
48
50
namespace fuse_models
49
51
{
@@ -113,7 +115,7 @@ class Acceleration2D : public fuse_core::AsyncSensorModel
113
115
114
116
tf2_ros::Buffer tf_buffer_;
115
117
116
- tf2_ros::TransformListener tf_listener_;
118
+ std::unique_ptr< tf2_ros::TransformListener> tf_listener_;
117
119
118
120
ros::Subscriber subscriber_;
119
121
Original file line number Diff line number Diff line change @@ -146,7 +146,7 @@ class Imu2D : public fuse_core::AsyncSensorModel
146
146
147
147
tf2_ros::Buffer tf_buffer_;
148
148
149
- tf2_ros::TransformListener tf_listener_;
149
+ std::unique_ptr< tf2_ros::TransformListener> tf_listener_;
150
150
151
151
ros::Subscriber subscriber_;
152
152
Original file line number Diff line number Diff line change @@ -141,7 +141,7 @@ class Odometry2D : public fuse_core::AsyncSensorModel
141
141
142
142
tf2_ros::Buffer tf_buffer_;
143
143
144
- tf2_ros::TransformListener tf_listener_;
144
+ std::unique_ptr< tf2_ros::TransformListener> tf_listener_;
145
145
146
146
ros::Subscriber subscriber_;
147
147
Original file line number Diff line number Diff line change 44
44
#include < ros/ros.h>
45
45
#include < tf2_ros/transform_listener.h>
46
46
47
+ #include < memory>
48
+
47
49
48
50
namespace fuse_models
49
51
{
@@ -128,7 +130,7 @@ class Pose2D : public fuse_core::AsyncSensorModel
128
130
129
131
tf2_ros::Buffer tf_buffer_;
130
132
131
- tf2_ros::TransformListener tf_listener_;
133
+ std::unique_ptr< tf2_ros::TransformListener> tf_listener_;
132
134
133
135
ros::Subscriber subscriber_;
134
136
Original file line number Diff line number Diff line change @@ -51,7 +51,6 @@ namespace fuse_models
51
51
Acceleration2D::Acceleration2D () :
52
52
fuse_core::AsyncSensorModel (1 ),
53
53
device_id_ (fuse_core::uuid::NIL),
54
- tf_listener_ (tf_buffer_),
55
54
throttled_callback_ (std::bind (&Acceleration2D::process, this , std::placeholders::_1))
56
55
{
57
56
}
@@ -71,6 +70,11 @@ void Acceleration2D::onInit()
71
70
ROS_WARN_STREAM (" No dimensions were specified. Data from topic " << ros::names::resolve (params_.topic ) <<
72
71
" will be ignored." );
73
72
}
73
+
74
+ if (!params_.target_frame .empty ())
75
+ {
76
+ tf_listener_ = std::make_unique<tf2_ros::TransformListener>(tf_buffer_);
77
+ }
74
78
}
75
79
76
80
void Acceleration2D::onStart ()
Original file line number Diff line number Diff line change @@ -57,7 +57,6 @@ namespace fuse_models
57
57
Imu2D::Imu2D () :
58
58
fuse_core::AsyncSensorModel (1 ),
59
59
device_id_ (fuse_core::uuid::NIL),
60
- tf_listener_ (tf_buffer_),
61
60
throttled_callback_ (std::bind (&Imu2D::process, this , std::placeholders::_1))
62
61
{
63
62
}
@@ -79,6 +78,13 @@ void Imu2D::onInit()
79
78
ROS_WARN_STREAM (" No dimensions were specified. Data from topic " << ros::names::resolve (params_.topic ) <<
80
79
" will be ignored." );
81
80
}
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
+ }
82
88
}
83
89
84
90
void Imu2D::onStart ()
Original file line number Diff line number Diff line change @@ -56,7 +56,6 @@ namespace fuse_models
56
56
Odometry2D::Odometry2D () :
57
57
fuse_core::AsyncSensorModel (1 ),
58
58
device_id_ (fuse_core::uuid::NIL),
59
- tf_listener_ (tf_buffer_),
60
59
throttled_callback_ (std::bind (&Odometry2D::process, this , std::placeholders::_1))
61
60
{
62
61
}
@@ -79,6 +78,11 @@ void Odometry2D::onInit()
79
78
ROS_WARN_STREAM (" No dimensions were specified. Data from topic " << ros::names::resolve (params_.topic ) <<
80
79
" will be ignored." );
81
80
}
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
+ }
82
86
}
83
87
84
88
void Odometry2D::onStart ()
Original file line number Diff line number Diff line change @@ -54,7 +54,6 @@ namespace fuse_models
54
54
Pose2D::Pose2D () :
55
55
fuse_core::AsyncSensorModel (1 ),
56
56
device_id_ (fuse_core::uuid::NIL),
57
- tf_listener_ (tf_buffer_),
58
57
throttled_callback_ (std::bind (&Pose2D::process, this , std::placeholders::_1))
59
58
{
60
59
}
@@ -75,6 +74,11 @@ void Pose2D::onInit()
75
74
ROS_WARN_STREAM (" No dimensions were specified. Data from topic " << ros::names::resolve (params_.topic ) <<
76
75
" will be ignored." );
77
76
}
77
+
78
+ if (!params_.target_frame .empty ())
79
+ {
80
+ tf_listener_ = std::make_unique<tf2_ros::TransformListener>(tf_buffer_);
81
+ }
78
82
}
79
83
80
84
void Pose2D::onStart ()
You can’t perform that action at this time.
0 commit comments