Skip to content

Commit ff525e9

Browse files
author
marco-tranzatto
committed
using std::shared_ptr instead of raw pointer for TF broadcaster
1 parent 2c4bf9b commit ff525e9

File tree

1 file changed

+6
-6
lines changed

1 file changed

+6
-6
lines changed

src/gps_to_pose_conversion_node.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,7 @@ double g_covariance_orientation_z;
3737
std::string g_frame_id;
3838
std::string g_tf_child_frame_id;
3939

40-
tf::TransformBroadcaster *tf_broadcaster;
40+
std::shared_ptr<tf::TransformBroadcaster> p_tf_broadcaster;
4141

4242
void imu_callback(const sensor_msgs::ImuConstPtr& msg)
4343
{
@@ -160,10 +160,10 @@ void gps_callback(const sensor_msgs::NavSatFixConstPtr& msg)
160160
g_latest_imu_msg.orientation.y,
161161
g_latest_imu_msg.orientation.z,
162162
g_latest_imu_msg.orientation.w));
163-
tf_broadcaster->sendTransform(tf::StampedTransform(transform,
164-
ros::Time::now(),
165-
g_frame_id,
166-
g_tf_child_frame_id));
163+
p_tf_broadcaster->sendTransform(tf::StampedTransform(transform,
164+
ros::Time::now(),
165+
g_frame_id,
166+
g_tf_child_frame_id));
167167
}
168168

169169
int main(int argc, char **argv) {
@@ -173,7 +173,7 @@ int main(int argc, char **argv) {
173173

174174
g_got_imu = false;
175175
g_got_altitude = false;
176-
tf_broadcaster = new tf::TransformBroadcaster();
176+
p_tf_broadcaster = std::make_shared<tf::TransformBroadcaster>();
177177

178178
// Use different coordinate transform if using simulator
179179
if (!pnh.getParam("is_sim", g_is_sim)) {

0 commit comments

Comments
 (0)